49 const std::string &robot_frame,
50 const std::string &global_frame,
52 geometry_msgs::PoseStamped &robot_pose)
54 geometry_msgs::PoseStamped local_pose;
55 local_pose.header.frame_id = robot_frame;
57 local_pose.pose.orientation.w = 1.0;
63 if (success &&
ros::Time::now() - robot_pose.header.stamp > timeout)
65 ROS_WARN(
"Most recent robot pose is %gs old (tolerance %gs)",
73 const std::string &target_frame,
75 const geometry_msgs::PoseStamped &in,
76 geometry_msgs::PoseStamped &out)
78 std::string error_msg;
97 ROS_WARN_STREAM(
"Failed to look up transform from frame '" << in.header.frame_id <<
"' into frame '" << target_frame
98 <<
"': " << error_msg);
107 tf.transform(in, out, target_frame);
112 ROS_WARN_STREAM(
"Failed to transform pose from frame '" << in.header.frame_id <<
" ' into frame '" 113 << target_frame <<
"' with exception: " << ex.what());
120 const std::string &target_frame,
122 const geometry_msgs::PointStamped &in,
123 geometry_msgs::PointStamped &out)
125 std::string error_msg;
144 ROS_WARN_STREAM(
"Failed to look up transform from frame '" << in.header.frame_id <<
"' into frame '" << target_frame
145 <<
"': " << error_msg);
154 tf.transform(in, out, target_frame);
159 ROS_WARN_STREAM(
"Failed to transform point from frame '" << in.header.frame_id <<
" ' into frame '" 160 << target_frame <<
"' with exception: " << ex.what());
166 double distance(
const geometry_msgs::PoseStamped &pose1,
const geometry_msgs::PoseStamped &pose2)
168 const geometry_msgs::Point &p1 = pose1.pose.position;
169 const geometry_msgs::Point &p2 = pose2.pose.position;
170 const double dx = p1.x - p2.x;
171 const double dy = p1.y - p2.y;
172 const double dz = p1.z - p2.z;
173 return sqrt(dx * dx + dy * dy + dz * dz);
176 double angle(
const geometry_msgs::PoseStamped &pose1,
const geometry_msgs::PoseStamped &pose2)
178 const geometry_msgs::Quaternion &q1 = pose1.pose.orientation;
179 const geometry_msgs::Quaternion &q2 = pose2.pose.orientation;
double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
computes the smallest angle between two poses.
bool transformPoint(const TF &tf, const std::string &target_frame, const ros::Duration &timeout, const geometry_msgs::PointStamped &in, geometry_msgs::PointStamped &out)
Transforms a point from one frame into another.
bool getRobotPose(const TF &tf, const std::string &robot_frame, const std::string &global_frame, const ros::Duration &timeout, geometry_msgs::PoseStamped &robot_pose)
Computes the robot pose.
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
#define ROS_WARN_STREAM(args)
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
Computes the Euclidean-distance between two poses.
tfScalar angleShortestPath(const Quaternion &q) const
bool transformPose(const TF &tf, const std::string &target_frame, const ros::Duration &timeout, const geometry_msgs::PoseStamped &in, geometry_msgs::PoseStamped &out)
Transforms a pose from one frame into another.