@@ -37,6 +37,8 @@ using namespace std::placeholders;
3737ImuFilterMadgwickRos::ImuFilterMadgwickRos (const rclcpp::NodeOptions &options)
3838 : BaseNode(" imu_filter_madgwick" , options),
3939 tf_broadcaster_(this ),
40+ tf_buffer_(this ->get_clock ()),
41+ tf_listener_(tf_buffer_),
4042 initialized_(false )
4143{
4244 RCLCPP_INFO (get_logger (), " Starting ImuFilter" );
@@ -151,7 +153,7 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
151153 add_parameter (" mag_bias_z" , rclcpp::ParameterValue (0.0 ), float_range,
152154 " Magnetometer bias (hard iron correction), z component." );
153155 double orientation_stddev;
154- float_range = {0.0 , 1 .0 , 0 };
156+ float_range = {0.0 , 100 .0 , 0 };
155157 add_parameter (" orientation_stddev" , rclcpp::ParameterValue (0.0 ),
156158 float_range,
157159 " Standard deviation of the orientation estimate." );
@@ -194,6 +196,10 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
194196 rpy_raw_debug_publisher_ =
195197 create_publisher<geometry_msgs::msg::Vector3Stamped>(" imu/rpy/raw" ,
196198 5 );
199+
200+ orientation_filtered_publisher_ =
201+ create_publisher<geometry_msgs::msg::PoseStamped>(
202+ " imu/orientation_filtered" , 5 );
197203 }
198204
199205 // **** register subscribers
@@ -483,7 +489,38 @@ void ImuFilterMadgwickRos::publishFilteredMsg(
483489
484490 rpy.header = imu_msg_raw->header ;
485491 rpy_filtered_debug_publisher_->publish (rpy);
492+
493+ publishOrientationFiltered (imu_msg);
494+ }
495+ }
496+
497+ void ImuFilterMadgwickRos::publishOrientationFiltered (const ImuMsg &imu_msg)
498+ {
499+ geometry_msgs::msg::PoseStamped pose;
500+ pose.header .stamp = imu_msg.header .stamp ;
501+ pose.header .frame_id = fixed_frame_;
502+ pose.pose .orientation = imu_msg.orientation ;
503+
504+ // get the current transform from the fixed frame to the imu frame
505+ geometry_msgs::msg::TransformStamped transform;
506+ try
507+ {
508+ transform = tf_buffer_.lookupTransform (
509+ fixed_frame_, imu_msg.header .frame_id , imu_msg.header .stamp ,
510+ rclcpp::Duration::from_seconds (0.1 ));
511+ } catch (tf2::TransformException &ex)
512+ {
513+ RCLCPP_WARN (
514+ this ->get_logger (), " Could not get transform from %s to %s: %s" ,
515+ fixed_frame_.c_str (), imu_msg.header .frame_id .c_str (), ex.what ());
516+ return ;
486517 }
518+
519+ pose.pose .position .x = transform.transform .translation .x ;
520+ pose.pose .position .y = transform.transform .translation .y ;
521+ pose.pose .position .z = transform.transform .translation .z ;
522+
523+ orientation_filtered_publisher_->publish (pose);
487524}
488525
489526void ImuFilterMadgwickRos::publishRawMsg (const rclcpp::Time &t, float roll,
0 commit comments