29 #include "../helpers/transform_helpers.hpp"
39 p_motion_(
session->service(
"ALMotion").value()),
40 tf2_buffer_( tf2_buffer )
51 if (pose_msg->header.frame_id ==
"odom") {
52 geometry_msgs::PoseStamped pose_msg_bf;
61 std::cout <<
"Cannot transform from "
63 <<
" to base_footprint"
78 std::cout <<
"odom to move x: " << pose_msg_bf.pose.position.x
79 <<
" y: " << pose_msg_bf.pose.position.y
80 <<
" yaw: " << yaw << std::endl;
82 if (std::isnan(yaw)) {
84 std::cout <<
"Yaw is nan, changed to 0.0" << std::endl;
89 pose_msg_bf.pose.position.x,
90 pose_msg_bf.pose.position.y,
94 std::cout << e.what() << std::endl;
95 std::cout <<
"moveto position in frame_id "
96 << pose_msg->header.frame_id
97 <<
"is not supported in any other base frame than "
101 std::cout <<
"received an error on the time lookup" << std::endl;
104 else if (pose_msg->header.frame_id ==
"base_footprint"){
106 std::cout <<
"going to move x: "
107 << pose_msg->pose.position.x
108 <<
" y: " << pose_msg->pose.position.y
109 <<
" yaw: " << yaw << std::endl;
111 if (std::isnan(yaw)) {
113 std::cout <<
"Yaw is nan, changed to 0.0" << std::endl;
118 pose_msg->pose.position.x,
119 pose_msg->pose.position.y,
124 std::cout <<
"Cannot reach position expressed in the "
125 << pose_msg->header.frame_id
126 <<
" frame, enter a valid frame id in the pose's header"
127 " (base_footprint or odom)"