32 #include <geometry_msgs/PoseWithCovarianceStamped.h> 41 std::shared_ptr<tf2_ros::Buffer>
tfbuf;
45 void cbPose(
const geometry_msgs::PoseWithCovarianceStamped::Ptr& msg)
49 geometry_msgs::PoseStamped in;
50 geometry_msgs::PoseStamped out;
51 geometry_msgs::PoseWithCovarianceStamped out_msg;
52 in.header = msg->header;
54 in.pose = msg->pose.pose;
55 geometry_msgs::TransformStamped trans =
tfbuf->lookupTransform(
59 out_msg.header = out.header;
60 out_msg.pose.pose = out.pose;
65 ROS_WARN(
"pose_transform: %s", e.what());
69 int main(
int argc,
char** argv)
78 pnh,
"pose_in", 1,
cbPose);
79 pub_pose = neonavigation_common::compat::advertise<geometry_msgs::PoseWithCovarianceStamped>(
81 pnh,
"pose_out", 1,
false);
82 pnh.param(
"to_frame",
to, std::string(
"map"));
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
ROSCPP_DECL void spin(Spinner &spinner)