Skip to content

Commit efd9b89

Browse files
committed
Publish filtered orientation as Pose
1 parent c6b73da commit efd9b89

File tree

2 files changed

+45
-0
lines changed

2 files changed

+45
-0
lines changed

imu_filter_madgwick/include/imu_filter_madgwick/imu_filter_ros.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,10 @@
2626
#include "rclcpp/rclcpp.hpp"
2727
#include "std_msgs/msg/string.hpp"
2828

29+
#include "tf2_ros/buffer.h"
2930
#include "tf2_ros/transform_broadcaster.h"
31+
#include "tf2_ros/transform_listener.h"
32+
#include <geometry_msgs/msg/pose_stamped.hpp>
3033
#include <geometry_msgs/msg/vector3_stamped.hpp>
3134
#include <message_filters/subscriber.h>
3235
#include <message_filters/sync_policies/approximate_time.h>
@@ -44,6 +47,7 @@ class ImuFilterMadgwickRos : public imu_filter::BaseNode
4447
typedef sensor_msgs::msg::Imu ImuMsg;
4548
typedef sensor_msgs::msg::MagneticField MagMsg;
4649
typedef geometry_msgs::msg::Vector3Stamped RpyVectorMsg;
50+
typedef geometry_msgs::msg::PoseStamped PoseMsg;
4751

4852
typedef message_filters::sync_policies::ApproximateTime<ImuMsg, MagMsg>
4953
SyncPolicy;
@@ -68,7 +72,10 @@ class ImuFilterMadgwickRos : public imu_filter::BaseNode
6872
rclcpp::Publisher<RpyVectorMsg>::SharedPtr rpy_filtered_debug_publisher_;
6973
rclcpp::Publisher<RpyVectorMsg>::SharedPtr rpy_raw_debug_publisher_;
7074
rclcpp::Publisher<ImuMsg>::SharedPtr imu_publisher_;
75+
rclcpp::Publisher<PoseMsg>::SharedPtr orientation_filtered_publisher_;
7176
tf2_ros::TransformBroadcaster tf_broadcaster_;
77+
tf2_ros::Buffer tf_buffer_;
78+
tf2_ros::TransformListener tf_listener_;
7279

7380
rclcpp::TimerBase::SharedPtr check_topics_timer_;
7481

@@ -104,6 +111,7 @@ class ImuFilterMadgwickRos : public imu_filter::BaseNode
104111
// **** member functions
105112
void publishFilteredMsg(ImuMsg::ConstSharedPtr imu_msg_raw);
106113
void publishTransform(ImuMsg::ConstSharedPtr imu_msg_raw);
114+
void publishOrientationFiltered(const ImuMsg& imu_msg);
107115

108116
void publishRawMsg(const rclcpp::Time& t, float roll, float pitch,
109117
float yaw);

imu_filter_madgwick/src/imu_filter_ros.cpp

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,8 @@ using namespace std::placeholders;
3737
ImuFilterMadgwickRos::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");
@@ -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

489526
void ImuFilterMadgwickRos::publishRawMsg(const rclcpp::Time &t, float roll,

0 commit comments

Comments
 (0)