imu_transformer_nodelet.cpp
Go to the documentation of this file.
3 #include "geometry_msgs/Vector3Stamped.h"
4 
5 //#include "tf2_sensor_msgs/tf2_sensor_msgs.h"
6 //Remove this header when https://github.com/ros/geometry_experimental/pull/78 is released
8 
9 namespace imu_transformer
10 {
11 
13 
14  nh_in_ = ros::NodeHandle(getNodeHandle(), "imu_in");
15  nh_out_ = ros::NodeHandle(getNodeHandle(), "imu_out");
17 
18  private_nh_.param<std::string>("target_frame", target_frame_, "base_link");
19 
20  tf2_.reset(new tf2_ros::Buffer());
22 
23  imu_sub_.subscribe(nh_in_, "data", 10);
24  imu_filter_.reset(new ImuFilter(imu_sub_, *tf2_, target_frame_, 10, nh_in_));
25  imu_filter_->registerCallback(boost::bind(&ImuTransformerNodelet::imuCallback, this, _1));
26  imu_filter_->registerFailureCallback(boost::bind(&ImuTransformerNodelet::failureCb, this, _2));
27 
28  mag_sub_.subscribe(nh_in_, "mag", 10);
29  // TF Message filter doesn't support ShapeShifter, which we use for Mag messages. Uncomment when IMU Rep goes into
30  // effect and we don't need to support two types of Mag message.
31 // mag_filter_.reset(new MagFilter(mag_sub_, *tf2_, target_frame_, 10, nh_in_));
32 // mag_filter_->registerCallback(boost::bind(&ImuTransformerNodelet::magCallback, this, _1));
33 // mag_filter_->registerFailureCallback(boost::bind(&ImuTransformerNodelet::failureCb, this, _2));
35  }
36 
37  void ImuTransformerNodelet::imuCallback(const ImuMsg::ConstPtr &imu_in)
38  {
39  if(imu_pub_.getTopic().empty()){
40  imu_pub_ = nh_out_.advertise<ImuMsg>("data", 10);
41  }
42 
43  try
44  {
45  ImuMsg imu_out;
46  tf2_->transform(*imu_in, imu_out, target_frame_);
47  imu_pub_.publish(imu_out);
48  }
49  catch (tf2::TransformException ex)
50  {
51  NODELET_ERROR_STREAM_THROTTLE(1.0, "IMU Transform failure: " << ex.what());
52  return;
53  }
54  }
55 
56  // Need to support two types of magnemoter message for now, replace with MagMsg subscriber when IMU REP goes into
57  // effect
59  {
60 
61  std::string error;
62  try
63  {
64  MagMsg::ConstPtr mag_in = msg->instantiate<MagMsg>();
65 
66  if(tf2_->canTransform(target_frame_, mag_in->header.frame_id, mag_in->header.stamp, &error)){
67 
68  if(mag_pub_.getTopic().empty()){
69  mag_pub_ = nh_out_.advertise<MagMsg>("mag", 10);
70  }
71 
72  MagMsg out;
73  tf2_->transform(*mag_in, out, target_frame_);
74  mag_pub_.publish(out);
75  }else{
76  NODELET_WARN_STREAM_THROTTLE(1.0, error);
77  }
78  return;
79  }
81  NODELET_DEBUG_STREAM(e.what());
82  }
83 
84  try
85  {
86  geometry_msgs::Vector3Stamped::ConstPtr mag_in = msg->instantiate<geometry_msgs::Vector3Stamped>();
87 
88  if(tf2_->canTransform(target_frame_, mag_in->header.frame_id, mag_in->header.stamp, &error)){
89 
90  if(mag_pub_.getTopic().empty()){
91  mag_pub_ = nh_out_.advertise<geometry_msgs::Vector3Stamped>("mag", 10);
92  }
93 
94  MagMsg mag_temp_in, mag_temp_out;
95  geometry_msgs::Vector3Stamped mag_out;
96 
97  mag_temp_in.header = mag_in->header;
98  mag_temp_in.magnetic_field = mag_in->vector;
99  tf2_->transform(mag_temp_in, mag_temp_out, target_frame_);
100  mag_out.header = mag_temp_out.header;
101  mag_out.vector = mag_temp_out.magnetic_field;
102 
103  mag_pub_.publish(mag_out);
104  }else{
105  NODELET_WARN_STREAM_THROTTLE(1.0, error);
106  }
107  return;
108  }
110  NODELET_DEBUG_STREAM(e.what());
111  }
112 
113  NODELET_ERROR_STREAM_THROTTLE(1.0, "imu_transformer only accepts sensor_msgs::MagneticField and "
114  "geometry_msgs::Vector3Stamped message types on the imu_in/mag_in topic, received " << msg->getDataType());
115 
116  }
117 
119  {
120  NODELET_WARN_STREAM_THROTTLE(1.0, "Can't transform incoming IMU data to " << target_frame_ << " " <<
121  reason);
122  }
123 
124 }
125 
#define NODELET_ERROR_STREAM_THROTTLE(rate,...)
boost::shared_ptr< ImuFilter > imu_filter_
#define NODELET_WARN_STREAM_THROTTLE(rate,...)
void publish(const boost::shared_ptr< M > &message) const
void magCallback(const topic_tools::ShapeShifter::ConstPtr &msg)
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_
ros::NodeHandle & getPrivateNodeHandle() const
sensor_msgs::Imu ImuMsg
bool param(const std::string &param_name, T &param_val, const T &default_val) const
tf2_ros::MessageFilter< ImuMsg > ImuFilter
boost::shared_ptr< tf2_ros::Buffer > tf2_
void imuCallback(const ImuMsg::ConstPtr &imu_in)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
#define NODELET_DEBUG_STREAM(...)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
std::string getTopic() const
sensor_msgs::MagneticField MagMsg
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void failureCb(tf2_ros::filter_failure_reasons::FilterFailureReason reason)
Connection registerCallback(const C &callback)


imu_transformer
Author(s): Paul Bovbel
autogenerated on Thu Jun 4 2020 03:23:01