34 #include <geometry_msgs/PoseWithCovarianceStamped.h> 53 void cbPose(
const geometry_msgs::PoseWithCovarianceStamped::Ptr& msg)
57 geometry_msgs::PoseStamped in;
58 geometry_msgs::PoseStamped out;
59 geometry_msgs::PoseWithCovarianceStamped out_msg;
60 in.header = msg->header;
62 in.pose = msg->pose.pose;
64 to_, msg->header.frame_id, in.header.stamp,
ros::Duration(0.5));
67 out_msg.header = out.header;
68 out_msg.pose.pose = out.pose;
73 ROS_WARN(
"pose_transform: %s", e.what());
86 pub_pose_ = neonavigation_common::compat::advertise<geometry_msgs::PoseWithCovarianceStamped>(
88 pnh_,
"pose_out", 1,
false);
89 pnh_.param(
"to_frame", to_, std::string(
"map"));
93 int main(
int argc,
char** argv)
void publish(const boost::shared_ptr< M > &message) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) 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)