3 #include "geometry_msgs/Vector3Stamped.h" 64 MagMsg::ConstPtr mag_in = msg->instantiate<
MagMsg>();
66 if(
tf2_->canTransform(
target_frame_, mag_in->header.frame_id, mag_in->header.stamp, &error)){
86 geometry_msgs::Vector3Stamped::ConstPtr mag_in = msg->instantiate<geometry_msgs::Vector3Stamped>();
88 if(
tf2_->canTransform(
target_frame_, mag_in->header.frame_id, mag_in->header.stamp, &error)){
94 MagMsg mag_temp_in, mag_temp_out;
95 geometry_msgs::Vector3Stamped mag_out;
97 mag_temp_in.header = mag_in->header;
98 mag_temp_in.magnetic_field = mag_in->vector;
100 mag_out.header = mag_temp_out.header;
101 mag_out.vector = mag_temp_out.magnetic_field;
114 "geometry_msgs::Vector3Stamped message types on the imu_in/mag_in topic, received " << msg->getDataType());
#define NODELET_ERROR_STREAM_THROTTLE(rate,...)
#define NODELET_WARN_STREAM_THROTTLE(rate,...)
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle & getPrivateNodeHandle() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
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
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Connection registerCallback(const C &callback)