@@ -37,6 +37,8 @@ using namespace std::placeholders;
37
37
ImuFilterMadgwickRos::ImuFilterMadgwickRos (const rclcpp::NodeOptions &options)
38
38
: BaseNode(" imu_filter_madgwick" , options),
39
39
tf_broadcaster_(this ),
40
+ tf_buffer_(this ->get_clock ()),
41
+ tf_listener_(tf_buffer_),
40
42
initialized_(false )
41
43
{
42
44
RCLCPP_INFO (get_logger (), " Starting ImuFilter" );
@@ -194,6 +196,10 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
194
196
rpy_raw_debug_publisher_ =
195
197
create_publisher<geometry_msgs::msg::Vector3Stamped>(" imu/rpy/raw" ,
196
198
5 );
199
+
200
+ orientation_filtered_publisher_ =
201
+ create_publisher<geometry_msgs::msg::PoseStamped>(
202
+ " imu/orientation/filtered" , 5 );
197
203
}
198
204
199
205
// **** register subscribers
@@ -483,7 +489,38 @@ void ImuFilterMadgwickRos::publishFilteredMsg(
483
489
484
490
rpy.header = imu_msg_raw->header ;
485
491
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 ;
486
517
}
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);
487
524
}
488
525
489
526
void ImuFilterMadgwickRos::publishRawMsg (const rclcpp::Time &t, float roll,
0 commit comments