Skip to content

Commit

Permalink
Merge pull request #40 from Greenzie/jonathansanabria/initial-prevent…
Browse files Browse the repository at this point in the history
…ion-of-0-0-0-gps-odometry/sc-32541

Prevention of (0,0,0) Gps Odometry Due To Failed Transform
  • Loading branch information
1hada authored Sep 22, 2023
2 parents 280c903 + f7c9f36 commit ee5cfe1
Show file tree
Hide file tree
Showing 3 changed files with 39 additions and 31 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ Forthcoming
* Adding Pipeline
* Throttling GNSS Origin data warning
* Added precision to origin output
* Added check to prevent null GPS odometry from being published due to missing transform

2.7.3 (2021-07-23)
------------------
Expand Down
5 changes: 4 additions & 1 deletion include/robot_localization/navsat_transform.h
Original file line number Diff line number Diff line change
Expand Up @@ -108,8 +108,10 @@ class NavSatTransform

//! @brief Given the pose of the navsat sensor in the world frame, removes the offset from the vehicle's centroid
//! and returns the world-frame pose of said centroid.
//! @param[out] gps_odom The world-frame pose of base_link
//! @return whether robot_odom_pose was transformed
//!
void getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose,
bool getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose,
tf2::Transform &robot_odom_pose,
const ros::Time &transform_time);

Expand Down Expand Up @@ -401,3 +403,4 @@ class NavSatTransform
} // namespace RobotLocalization

#endif // ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H

64 changes: 34 additions & 30 deletions src/navsat_transform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -564,7 +564,7 @@ namespace RobotLocalization
}
}

void NavSatTransform::getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose,
bool NavSatTransform::getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose,
tf2::Transform &robot_odom_pose,
const ros::Time &transform_time)
{
Expand Down Expand Up @@ -610,6 +610,7 @@ namespace RobotLocalization
ROS_WARN_STREAM_THROTTLE(5.0, "Could not obtain " << base_link_frame_id_ << "->" << gps_frame_id_ <<
" transform. Will not remove offset of navsat device from robot's origin.");
}
return can_transform;
}

void NavSatTransform::gpsFixCallback(const sensor_msgs::NavSatFixConstPtr& msg)
Expand Down Expand Up @@ -867,42 +868,44 @@ namespace RobotLocalization

// Want the pose of the vehicle origin, not the GPS
tf2::Transform transformed_cartesian_robot;
getRobotOriginWorldPose(transformed_cartesian_gps, transformed_cartesian_robot, gps_odom.header.stamp);

// Rotate the covariance as well
tf2::Matrix3x3 rot(cartesian_world_transform_.getRotation());
Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE);
rot_6d.setIdentity();

for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd)
bool is_transformed = getRobotOriginWorldPose(transformed_cartesian_gps, transformed_cartesian_robot, gps_odom.header.stamp);
if (is_transformed)
{
rot_6d(rInd, 0) = rot.getRow(rInd).getX();
rot_6d(rInd, 1) = rot.getRow(rInd).getY();
rot_6d(rInd, 2) = rot.getRow(rInd).getZ();
rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX();
rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY();
rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ();
}
// Rotate the covariance as well
tf2::Matrix3x3 rot(cartesian_world_transform_.getRotation());
Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE);
rot_6d.setIdentity();

// Rotate the covariance
latest_cartesian_covariance_ = rot_6d * latest_cartesian_covariance_.eval() * rot_6d.transpose();
for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd)
{
rot_6d(rInd, 0) = rot.getRow(rInd).getX();
rot_6d(rInd, 1) = rot.getRow(rInd).getY();
rot_6d(rInd, 2) = rot.getRow(rInd).getZ();
rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX();
rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY();
rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ();
}

// Now fill out the message. Set the orientation to the identity.
tf2::toMsg(transformed_cartesian_robot, gps_odom.pose.pose);
gps_odom.pose.pose.position.z = (zero_altitude_ ? 0.0 : gps_odom.pose.pose.position.z);
// Rotate the covariance
latest_cartesian_covariance_ = rot_6d * latest_cartesian_covariance_.eval() * rot_6d.transpose();

// Copy the measurement's covariance matrix so that we can rotate it later
for (size_t i = 0; i < POSE_SIZE; i++)
{
for (size_t j = 0; j < POSE_SIZE; j++)
// Now fill out the message. Set the orientation to the identity.
tf2::toMsg(transformed_cartesian_robot, gps_odom.pose.pose);
gps_odom.pose.pose.position.z = (zero_altitude_ ? 0.0 : gps_odom.pose.pose.position.z);

// Copy the measurement's covariance matrix so that we can rotate it later
for (size_t i = 0; i < POSE_SIZE; i++)
{
gps_odom.pose.covariance[POSE_SIZE * i + j] = latest_cartesian_covariance_(i, j);
for (size_t j = 0; j < POSE_SIZE; j++)
{
gps_odom.pose.covariance[POSE_SIZE * i + j] = latest_cartesian_covariance_(i, j);
}
}
}

// Mark this GPS as used
gps_updated_ = false;
new_data = true;
// Mark this GPS as used
gps_updated_ = false;
new_data = true;
}
}

return new_data;
Expand Down Expand Up @@ -964,3 +967,4 @@ namespace RobotLocalization
}

} // namespace RobotLocalization

0 comments on commit ee5cfe1

Please sign in to comment.