Skip to content

Commit 660e257

Browse files
committed
Merge pull request #206 from ayrton04/master
Merging ayrton04's branches
2 parents 88dee3f + 96e68a0 commit 660e257

13 files changed

+385
-249
lines changed

CHANGELOG.rst

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,33 @@
22
Changelog for package robot_localization
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
2.2.0 (2015-05-22)
6+
------------------
7+
* Added tf2-friendly tf_prefix appending
8+
* Corrected for IMU orientation in navsat_transform
9+
* Fixed issue with out-of-order measurements and pose resets
10+
* Nodes now assume ENU standard for yaw data
11+
* Removed gps_common dependency
12+
* Adding option to navsat_transform_node that enables the use of the heading from the odometry message instead of an IMU.
13+
* Changed frame_id used in setPoseCallback to be the world_frame
14+
* Optimized Eigen arithmetic for signficiant performance boost
15+
* Migrated to tf2
16+
* Code refactoring and reorganization
17+
* Removed roll and pitch from navsat_transform calculations
18+
* Fixed transform for IMU data to better support mounting IMUs in non-standard orientations
19+
* Added feature to navsat_transform_node whereby filtered odometry data can be coverted back into navsat data
20+
* Added a parameter to allow future dating the world_frame->base_link_frame transform.
21+
* Removed deprecated differential setting handler
22+
* Added relative mode
23+
* Updated and improved tests
24+
* Fixing source frame_id in pose data handling
25+
* Added initial covariance parameter
26+
* Fixed bug in covariance copyinh
27+
* Added parameters for topic queue sizes
28+
* Improved motion model's handling of angular velocities when robot has non-zero roll and pitch
29+
* Changed the way differential measurements are handled
30+
* Added diagnostics
31+
532
2.1.7 (2015-01-05)
633
------------------
734
* Added some checks to eliminate unnecessary callbacks

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,7 @@ target_link_libraries(ukf filter_base ${catkin_LIBRARIES})
8888
target_link_libraries(ros_filter ekf ukf ros_filter_utilities ${catkin_LIBRARIES})
8989
target_link_libraries(ekf_localization_node ros_filter ${catkin_LIBRARIES})
9090
target_link_libraries(ukf_localization_node ros_filter ${catkin_LIBRARIES})
91-
target_link_libraries(navsat_transform ${catkin_LIBRARIES})
91+
target_link_libraries(navsat_transform filter_utilities ros_filter_utilities ${catkin_LIBRARIES})
9292
target_link_libraries(navsat_transform_node navsat_transform ${catkin_LIBRARIES})
9393

9494
#############

include/robot_localization/filter_utilities.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,12 @@ namespace RobotLocalization
5656
//! @return the bounded value
5757
//!
5858
double clampRotation(double rotation);
59+
60+
//! @brief Utility method for appending tf2 prefixes cleanly
61+
//! @param[in] tfPrefix - the tf2 prefix to append
62+
//! @paramp[in, out] frameId - the resulting frame_id value
63+
//!
64+
void appendPrefix(std::string tfPrefix, std::string &frameId);
5965
}
6066
}
6167

include/robot_localization/navsat_transform.h

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,8 @@
4040

4141
#include <tf2/LinearMath/Transform.h>
4242
#include <tf2_ros/static_transform_broadcaster.h>
43+
#include <tf2_ros/buffer.h>
44+
#include <tf2_ros/transform_listener.h>
4345

4446
#include <Eigen/Dense>
4547

@@ -148,6 +150,13 @@ namespace RobotLocalization
148150
//!
149151
bool useManualDatum_;
150152

153+
//! @brief Frame ID of the robot's body frame
154+
//!
155+
//! This is needed for obtaining transforms from the robot's body
156+
//! frame to the frames of sensors (IMU and GPS)
157+
//!
158+
std::string baseLinkFrameId_;
159+
151160
//! @brief Frame ID of the GPS odometry output
152161
//!
153162
//! This will just match whatever your odometry message has
@@ -186,6 +195,14 @@ namespace RobotLocalization
186195
//!
187196
Eigen::MatrixXd latestOdomCovariance_;
188197

198+
//! @brief Transform buffer for managing coordinate transforms
199+
//!
200+
tf2_ros::Buffer tfBuffer_;
201+
202+
//! @brief Transform listener for receiving transforms
203+
//!
204+
tf2_ros::TransformListener tfListener_;
205+
189206
//! @brief Used for publishing the static world_frame->utm transform
190207
//!
191208
tf2_ros::StaticTransformBroadcaster utmBroadcaster_;

include/robot_localization/ros_filter.h

Lines changed: 0 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -303,24 +303,6 @@ namespace RobotLocalization
303303
//!
304304
std::vector<int> loadUpdateConfig(const std::string &topicName);
305305

306-
//! @brief Method for safely obtaining transforms.
307-
//! @param[in] targetFrame - The target frame of the desired transform
308-
//! @param[in] sourceFrame - The source frame of the desired transform
309-
//! @param[in] time - The time at which we want the transform
310-
//! @param[out] targetFrameTrans - The resulting transform object
311-
//! @return Sets the value of @p targetFrameTrans and returns true if successful,
312-
//! false otherwise.
313-
//!
314-
//! This method attempts to obtain a transform from the @p sourceFrame to the @p
315-
//! targetFrame at the specific @p time. If no transform is available at that time,
316-
//! it attempts to simply obtain the latest transform. If that still fails, then the
317-
//! method checks to see if the transform is going from a given frame_id to itself.
318-
//! If any of these checks succeed, the method sets the value of @p targetFrameTrans
319-
//! and returns true, otherwise it returns false.
320-
//!
321-
bool lookupTransformSafe(const std::string &targetFrame, const std::string &sourceFrame,
322-
const ros::Time &time, tf2::Transform &targetFrameTrans);
323-
324306
//! @brief Prepares an IMU message's linear acceleration for integration into the filter
325307
//! @param[in] msg - The IMU message to prepare
326308
//! @param[in] topicName - The name of the topic over which this message was received
@@ -532,10 +514,6 @@ namespace RobotLocalization
532514
//!
533515
tf2_ros::TransformListener tfListener_;
534516

535-
//! @brief tf prefix
536-
//!
537-
std::string tfPrefix_;
538-
539517
//! @brief For future (or past) dating the world_frame->base_link_frame transform
540518
//!
541519
ros::Duration tfTimeOffset_;

include/robot_localization/ros_filter_utilities.h

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@
3535

3636
#include <tf2/LinearMath/Quaternion.h>
3737
#include <tf2/LinearMath/Transform.h>
38+
#include <tf2_ros/buffer.h>
3839

3940
#include <Eigen/Dense>
4041

@@ -52,6 +53,28 @@ namespace RobotLocalization
5253
{
5354
namespace RosFilterUtilities
5455
{
56+
//! @brief Method for safely obtaining transforms.
57+
//! @param[in] buffer - tf buffer object to use for looking up the transform
58+
//! @param[in] targetFrame - The target frame of the desired transform
59+
//! @param[in] sourceFrame - The source frame of the desired transform
60+
//! @param[in] time - The time at which we want the transform
61+
//! @param[out] targetFrameTrans - The resulting transform object
62+
//! @return Sets the value of @p targetFrameTrans and returns true if successful,
63+
//! false otherwise.
64+
//!
65+
//! This method attempts to obtain a transform from the @p sourceFrame to the @p
66+
//! targetFrame at the specific @p time. If no transform is available at that time,
67+
//! it attempts to simply obtain the latest transform. If that still fails, then the
68+
//! method checks to see if the transform is going from a given frame_id to itself.
69+
//! If any of these checks succeed, the method sets the value of @p targetFrameTrans
70+
//! and returns true, otherwise it returns false.
71+
//!
72+
bool lookupTransformSafe(const tf2_ros::Buffer &buffer,
73+
const std::string &targetFrame,
74+
const std::string &sourceFrame,
75+
const ros::Time &time,
76+
tf2::Transform &targetFrameTrans);
77+
5578
//! @brief Utility method for converting quaternion to RPY
5679
//! @param[in] quat - The quaternion to convert
5780
//! @param[out] roll - The converted roll

src/filter_utilities.cpp

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -116,5 +116,26 @@ namespace RobotLocalization
116116

117117
return rotation;
118118
}
119+
120+
void appendPrefix(std::string tfPrefix, std::string &frameId)
121+
{
122+
// Strip all leading slashes for tf2 compliance
123+
if(!frameId.empty() && frameId.at(0) == '/')
124+
{
125+
frameId = frameId.substr(1);
126+
}
127+
128+
if(!tfPrefix.empty() && tfPrefix.at(0) == '/')
129+
{
130+
tfPrefix = tfPrefix.substr(1);
131+
}
132+
133+
// If we do have a tf prefix, then put a slash in between
134+
if(!tfPrefix.empty())
135+
{
136+
frameId = tfPrefix + "/" + frameId;
137+
}
138+
}
139+
119140
}
120141
}

src/navsat_transform.cpp

Lines changed: 58 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,9 @@
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

Comments
 (0)