51 const std::string &robot_frame,
52 const std::string &global_frame,
54 geometry_msgs::PoseStamped &robot_pose)
56 geometry_msgs::PoseStamped local_pose;
57 local_pose.header.frame_id = robot_frame;
59 local_pose.pose.orientation.w = 1.0;
65 if (success &&
ros::Time::now() - robot_pose.header.stamp > timeout)
67 ROS_WARN(
"Most recent robot pose is %gs old (tolerance %gs)",
80 static bool isNormalized(
const geometry_msgs::Quaternion& _q,
double _epsilon)
82 const double sq_sum = std::pow(_q.x, 2) + std::pow(_q.y, 2) + std::pow(_q.z, 2) + std::pow(_q.w, 2);
83 return std::abs(sq_sum - 1.) <= _epsilon;
87 const std::string &target_frame,
89 const geometry_msgs::PoseStamped &in,
90 geometry_msgs::PoseStamped &out)
95 ROS_WARN_STREAM(
"The given quaterinon " << in.pose.orientation <<
" is not normalized");
99 std::string error_msg;
102 bool success =
tf.waitForTransform(target_frame,
109 bool success =
tf.canTransform(target_frame,
118 ROS_WARN_STREAM(
"Failed to look up transform from frame '" << in.header.frame_id <<
"' into frame '" << target_frame
119 <<
"': " << error_msg);
126 tf.transformPose(target_frame, in, out);
128 tf.transform(in, out, target_frame);
133 ROS_WARN_STREAM(
"Failed to transform pose from frame '" << in.header.frame_id <<
" ' into frame '"
134 << target_frame <<
"' with exception: " << ex.what());
141 const std::string &target_frame,
143 const geometry_msgs::PointStamped &in,
144 geometry_msgs::PointStamped &out)
146 std::string error_msg;
149 bool success =
tf.waitForTransform(target_frame,
156 bool success =
tf.canTransform(target_frame,
165 ROS_WARN_STREAM(
"Failed to look up transform from frame '" << in.header.frame_id <<
"' into frame '" << target_frame
166 <<
"': " << error_msg);
173 tf.transformPoint(target_frame, in, out);
175 tf.transform(in, out, target_frame);
180 ROS_WARN_STREAM(
"Failed to transform point from frame '" << in.header.frame_id <<
" ' into frame '"
181 << target_frame <<
"' with exception: " << ex.what());
187 double distance(
const geometry_msgs::PoseStamped &pose1,
const geometry_msgs::PoseStamped &pose2)
189 const geometry_msgs::Point &p1 = pose1.pose.position;
190 const geometry_msgs::Point &p2 = pose2.pose.position;
191 const double dx = p1.x - p2.x;
192 const double dy = p1.y - p2.y;
193 const double dz = p1.z - p2.z;
194 return sqrt(dx * dx + dy * dy + dz * dz);
197 double angle(
const geometry_msgs::PoseStamped &pose1,
const geometry_msgs::PoseStamped &pose2)
199 const geometry_msgs::Quaternion &q1 = pose1.pose.orientation;
200 const geometry_msgs::Quaternion &q2 = pose2.pose.orientation;