navigation_utility.cpp
Go to the documentation of this file.
00001 /*
00002  *  Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón
00003  *
00004  *  Redistribution and use in source and binary forms, with or without
00005  *  modification, are permitted provided that the following conditions
00006  *  are met:
00007  *
00008  *  1. Redistributions of source code must retain the above copyright
00009  *     notice, this list of conditions and the following disclaimer.
00010  *
00011  *  2. Redistributions in binary form must reproduce the above
00012  *     copyright notice, this list of conditions and the following
00013  *     disclaimer in the documentation and/or other materials provided
00014  *     with the distribution.
00015  *
00016  *  3. Neither the name of the copyright holder nor the names of its
00017  *     contributors may be used to endorse or promote products derived
00018  *     from this software without specific prior written permission.
00019  *
00020  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  *  POSSIBILITY OF SUCH DAMAGE.
00032  *
00033  *  navigation_utility.cpp
00034  *
00035  *  authors:
00036  *    Sebastian Pütz <spuetz@uni-osnabrueck.de>
00037  *    Jorge Santos Simón <santos@magazino.eu>
00038  *
00039  */
00040 
00041 #include "mbf_utility/navigation_utility.h"
00042 
00043 namespace mbf_utility
00044 {
00045 
00046 bool getRobotPose(const TF &tf,
00047                   const std::string &robot_frame,
00048                   const std::string &global_frame,
00049                   const ros::Duration &timeout,
00050                   geometry_msgs::PoseStamped &robot_pose)
00051 {
00052   tf::Stamped<tf::Pose> local_pose;
00053   local_pose.setIdentity();
00054   local_pose.frame_id_ = robot_frame;
00055   geometry_msgs::PoseStamped local_pose_msg;
00056   tf::poseStampedTFToMsg(local_pose, local_pose_msg);
00057   return transformPose(tf,
00058                        global_frame,
00059                        ros::Time(0), // most recent available
00060                        timeout,
00061                        local_pose_msg,
00062                        global_frame,
00063                        robot_pose);
00064 }
00065 
00066 bool transformPose(const TF &tf,
00067                    const std::string &target_frame,
00068                    const ros::Time &target_time,
00069                    const ros::Duration &timeout,
00070                    const geometry_msgs::PoseStamped &in,
00071                    const std::string &fixed_frame,
00072                    geometry_msgs::PoseStamped &out)
00073 {
00074   std::string error_msg;
00075 
00076 #ifdef USE_OLD_TF
00077   bool success = tf.waitForTransform(target_frame,
00078                                      target_time,
00079                                      in.header.frame_id,
00080                                      in.header.stamp,
00081                                      fixed_frame,
00082                                      timeout,
00083                                      ros::Duration(0.01),
00084                                      &error_msg);
00085 #else
00086   bool success = tf.canTransform(target_frame,
00087                                  target_time,
00088                                  in.header.frame_id,
00089                                  in.header.stamp,
00090                                  fixed_frame,
00091                                  timeout,
00092                                  &error_msg);
00093 #endif
00094 
00095   if (!success)
00096   {
00097     ROS_WARN_STREAM("Failed to look up transform from frame '" << in.header.frame_id << "' into frame '" << target_frame
00098                     << "': " << error_msg);
00099     return false;
00100   }
00101 
00102   try
00103   {
00104 #ifdef USE_OLD_TF
00105     tf.transformPose(target_frame, target_time, in, fixed_frame, out);
00106 #else
00107     tf.transform(in, out, target_frame, target_time, fixed_frame);
00108 #endif
00109   }
00110   catch (const TFException &ex)
00111   {
00112     ROS_WARN_STREAM("Failed to transform pose from frame '" <<  in.header.frame_id << " ' into frame '"
00113                     << target_frame << "' with exception: " << ex.what());
00114     return false;
00115   }
00116   return true;
00117 }
00118 
00119 bool transformPoint(const TF &tf,
00120                     const std::string &target_frame,
00121                     const ros::Time &target_time,
00122                     const ros::Duration &timeout,
00123                     const geometry_msgs::PointStamped &in,
00124                     const std::string &fixed_frame,
00125                     geometry_msgs::PointStamped &out)
00126 {
00127   std::string error_msg;
00128 
00129 #ifdef USE_OLD_TF
00130   bool success = tf.waitForTransform(target_frame,
00131                                      target_time,
00132                                      in.header.frame_id,
00133                                      in.header.stamp,
00134                                      fixed_frame,
00135                                      timeout,
00136                                      ros::Duration(0.01),
00137                                      &error_msg);
00138 #else
00139   bool success = tf.canTransform(target_frame,
00140                                  target_time,
00141                                  in.header.frame_id,
00142                                  in.header.stamp,
00143                                  fixed_frame,
00144                                  timeout,
00145                                  &error_msg);
00146 #endif
00147 
00148   if (!success)
00149   {
00150     ROS_WARN_STREAM("Failed to look up transform from frame '" << in.header.frame_id << "' into frame '" << target_frame
00151                                                                << "': " << error_msg);
00152     return false;
00153   }
00154 
00155   try
00156   {
00157 #ifdef USE_OLD_TF
00158     tf.transformPoint(target_frame, target_time, in, fixed_frame, out);
00159 #else
00160     tf.transform(in, out, target_frame, target_time, fixed_frame);
00161 #endif
00162   }
00163   catch (const TFException &ex)
00164   {
00165     ROS_WARN_STREAM("Failed to transform point from frame '" <<  in.header.frame_id << " ' into frame '"
00166                                                             << target_frame << "' with exception: " << ex.what());
00167     return false;
00168   }
00169   return true;
00170 }
00171 
00172 double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
00173 {
00174   const geometry_msgs::Point &p1 = pose1.pose.position;
00175   const geometry_msgs::Point &p2 = pose2.pose.position;
00176   const double dx = p1.x - p2.x;
00177   const double dy = p1.y - p2.y;
00178   const double dz = p1.z - p2.z;
00179   return sqrt(dx * dx + dy * dy + dz * dz);
00180 }
00181 
00182 double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
00183 {
00184   const geometry_msgs::Quaternion &q1 = pose1.pose.orientation;
00185   const geometry_msgs::Quaternion &q2 = pose2.pose.orientation;
00186   tf::Quaternion rot1, rot2;
00187   tf::quaternionMsgToTF(q1, rot1);
00188   tf::quaternionMsgToTF(q2, rot2);
00189   return rot1.angleShortestPath(rot2);
00190 }
00191 
00192 } /* namespace mbf_utility */


mbf_utility
Author(s): Sebastian Pütz
autogenerated on Mon Jun 17 2019 20:11:33