3232
3333#include " robot_localization/navsat_transform.h"
3434#include " robot_localization/filter_common.h"
35+ #include " robot_localization/filter_utilities.h"
3536#include " robot_localization/navsat_conversions.h"
37+ #include " robot_localization/ros_filter_utilities.h"
3638
3739#include < tf2_geometry_msgs/tf2_geometry_msgs.h>
3840
@@ -56,7 +58,9 @@ namespace RobotLocalization
5658 useManualDatum_ (false ),
5759 zeroAltitude_ (false ),
5860 worldFrameId_ (" odom" ),
59- utmZone_ (" " )
61+ baseLinkFrameId_ (" base_link" ),
62+ utmZone_ (" " ),
63+ tfListener_ (tfBuffer_)
6064 {
6165 latestUtmCovariance_.resize (POSE_SIZE, POSE_SIZE);
6266 }
@@ -171,6 +175,7 @@ namespace RobotLocalization
171175 {
172176 tf2::fromMsg (msg->pose .pose , transformWorldPose_);
173177 worldFrameId_ = msg->header .frame_id ;
178+ baseLinkFrameId_ = msg->child_frame_id ;
174179 hasTransformOdom_ = true ;
175180
176181 ROS_INFO_STREAM (" Initial odometry position is (" << std::fixed <<
@@ -184,29 +189,64 @@ namespace RobotLocalization
184189 // UTM->world_frame transform.
185190 if (!transformGood_ && useOdometryYaw_ && !useManualDatum_)
186191 {
187- sensor_msgs::Imu imu;
188- imu. orientation = msg->pose .pose .orientation ;
189- imu. header .frame_id = msg->child_frame_id ;
190- sensor_msgs::ImuConstPtr imuPtr (& imu);
192+ sensor_msgs::Imu * imu = new sensor_msgs::Imu () ;
193+ imu-> orientation = msg->pose .pose .orientation ;
194+ imu-> header .frame_id = msg->child_frame_id ;
195+ sensor_msgs::ImuConstPtr imuPtr (imu);
191196 imuCallback (imuPtr);
192197 }
193198 }
194199
195200 void NavSatTransform::imuCallback (const sensor_msgs::ImuConstPtr& msg)
196201 {
197- /* This method only gets called if we don't yet have the
198- * IMU data (the subscriber gets shut down once we compute
199- * the transform), so we can assumed that every IMU message
200- * that comes here is meant to be used for that purpose. */
201- tf2::fromMsg (msg->orientation , transformOrientation_);
202- hasTransformImu_ = true ;
203-
204- double roll, pitch, yaw;
205- tf2::Matrix3x3 mat;
206- mat.setRotation (transformOrientation_);
207- mat.getRPY (roll, pitch, yaw);
208- ROS_INFO_STREAM (" Initial orientation roll, pitch, yaw is (" <<
209- roll << " , " << pitch << " , " << yaw << " )" );
202+ // We need the baseLinkFrameId_ from the odometry message, so
203+ // we need to wait until we receive it.
204+ if (hasTransformOdom_)
205+ {
206+ /* This method only gets called if we don't yet have the
207+ * IMU data (the subscriber gets shut down once we compute
208+ * the transform), so we can assumed that every IMU message
209+ * that comes here is meant to be used for that purpose. */
210+ tf2::fromMsg (msg->orientation , transformOrientation_);
211+
212+ // Correct for the IMU's orientation w.r.t. base_link
213+ tf2::Transform targetFrameTrans;
214+ RosFilterUtilities::lookupTransformSafe (tfBuffer_,
215+ baseLinkFrameId_,
216+ msg->header .frame_id ,
217+ msg->header .stamp ,
218+ targetFrameTrans);
219+
220+ double rollOffset = 0 ;
221+ double pitchOffset = 0 ;
222+ double yawOffset = 0 ;
223+ double roll = 0 ;
224+ double pitch = 0 ;
225+ double yaw = 0 ;
226+ RosFilterUtilities::quatToRPY (targetFrameTrans.getRotation (), rollOffset, pitchOffset, yawOffset);
227+ RosFilterUtilities::quatToRPY (transformOrientation_, roll, pitch, yaw);
228+
229+ ROS_DEBUG_STREAM (" Initial orientation roll, pitch, yaw is (" <<
230+ roll << " , " << pitch << " , " << yaw << " )" );
231+
232+ // Apply the offset (making sure to bound them), and throw them in a vector
233+ tf2::Vector3 rpyAngles (FilterUtilities::clampRotation (roll - rollOffset),
234+ FilterUtilities::clampRotation (pitch - pitchOffset),
235+ FilterUtilities::clampRotation (yaw - yawOffset));
236+
237+ // Now we need to rotate the roll and pitch by the yaw offset value.
238+ // Imagine a case where an IMU is mounted facing sideways. In that case
239+ // pitch for the IMU's world frame is roll for the robot.
240+ tf2::Matrix3x3 mat;
241+ mat.setRPY (0.0 , 0.0 , yawOffset);
242+ rpyAngles = mat * rpyAngles;
243+ transformOrientation_.setRPY (rpyAngles.getX (), rpyAngles.getY (), rpyAngles.getZ ());
244+
245+ ROS_DEBUG_STREAM (" Initial corrected orientation roll, pitch, yaw is (" <<
246+ rpyAngles.getX () << " , " << rpyAngles.getY () << " , " << rpyAngles.getZ () << " )" );
247+
248+ hasTransformImu_ = true ;
249+ }
210250 }
211251
212252 void NavSatTransform::computeTransform ()
0 commit comments