Skip to content

Commit

Permalink
fix to magic number
Browse files Browse the repository at this point in the history
Signed-off-by: scepter914 <scepter914@gmail.com>
  • Loading branch information
scepter914 committed Sep 6, 2022
1 parent 23e2d58 commit 229d15a
Show file tree
Hide file tree
Showing 2 changed files with 40 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,45 @@ using geometry_msgs::msg::TwistWithCovariance;
using tier4_autoware_utils::LinearRing2d;
using tier4_autoware_utils::Point2d;

enum MSG_COV_IDX {
X_X = 0,
X_Y = 1,
X_Z = 2,
X_ROLL = 3,
X_PITCH = 4,
X_YAW = 5,
Y_X = 6,
Y_Y = 7,
Y_Z = 8,
Y_ROLL = 9,
Y_PITCH = 10,
Y_YAW = 11,
Z_X = 12,
Z_Y = 13,
Z_Z = 14,
Z_ROLL = 15,
Z_PITCH = 16,
Z_YAW = 17,
ROLL_X = 18,
ROLL_Y = 19,
ROLL_Z = 20,
ROLL_ROLL = 21,
ROLL_PITCH = 22,
ROLL_YAW = 23,
PITCH_X = 24,
PITCH_Y = 25,
PITCH_Z = 26,
PITCH_ROLL = 27,
PITCH_PITCH = 28,
PITCH_YAW = 29,
YAW_X = 30,
YAW_Y = 31,
YAW_Z = 32,
YAW_ROLL = 33,
YAW_PITCH = 34,
YAW_YAW = 35
};

class RadarFusionToDetectedObject
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ bool RadarFusionToDetectedObject::hasTwistCovariance(
const TwistWithCovariance & twist_with_covariance)
{
auto covariance = twist_with_covariance.covariance;
if (covariance.at(0) == 0.0 && covariance.at(7) == 0.0 && covariance.at(14) == 0.0) {
if (covariance[X_X] == 0.0 && covariance[Y_Y] == 0.0 && covariance[Z_Z] == 0.0) {
return false;
} else {
return true;
Expand Down

0 comments on commit 229d15a

Please sign in to comment.