conversions_and_types.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2010, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * Author: Christian Connette
00036  *********************************************************************/
00037 
00038 #include <eband_local_planner/conversions_and_types.h>
00039 
00040 namespace eband_local_planner{
00041 
00042   void PoseToPose2D(const geometry_msgs::Pose pose, geometry_msgs::Pose2D& pose2D)
00043   {
00044     // use tf-pkg to convert angles
00045     tf::Pose pose_tf;
00046 
00047     // convert geometry_msgs::PoseStamped to tf::Pose
00048     tf::poseMsgToTF(pose, pose_tf);
00049 
00050     // now get Euler-Angles from pose_tf
00051     double useless_pitch, useless_roll, yaw;
00052     pose_tf.getBasis().getEulerYPR(yaw, useless_pitch, useless_roll);
00053 
00054     // normalize angle
00055     yaw = angles::normalize_angle(yaw);
00056 
00057     // and set to pose2D
00058     pose2D.x = pose.position.x;
00059     pose2D.y = pose.position.y;
00060     pose2D.theta = yaw;
00061 
00062     return;
00063   }
00064 
00065 
00066   void Pose2DToPose(geometry_msgs::Pose& pose, const geometry_msgs::Pose2D pose2D)
00067   {
00068     // use tf-pkg to convert angles
00069     tf::Quaternion frame_quat;
00070 
00071     // transform angle from euler-angle to quaternion representation
00072     frame_quat = tf::createQuaternionFromYaw(pose2D.theta);
00073 
00074     // set position
00075     pose.position.x = pose2D.x;
00076     pose.position.y = pose2D.y;
00077     pose.position.z = 0.0;
00078 
00079     // set quaternion
00080     pose.orientation.x = frame_quat.x();
00081     pose.orientation.y = frame_quat.y();
00082     pose.orientation.z = frame_quat.z();
00083     pose.orientation.w = frame_quat.w();
00084 
00085     return;
00086   }
00087 
00088 
00089   bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan, 
00090       costmap_2d::Costmap2DROS& costmap, const std::string& global_frame, 
00091       std::vector<geometry_msgs::PoseStamped>& transformed_plan, std::vector<int>& start_end_counts)
00092   {
00093     const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
00094 
00095     // initiate refernce variables
00096     transformed_plan.clear();
00097 
00098     try
00099     {
00100       if (!global_plan.size() > 0)
00101       {
00102         ROS_ERROR("Recieved plan with zero length");
00103         return false;
00104       }
00105 
00106       tf::StampedTransform transform;
00107       tf.lookupTransform(global_frame, ros::Time(), plan_pose.header.frame_id, plan_pose.header.stamp, 
00108           plan_pose.header.frame_id, transform);
00109 
00110       //let's get the pose of the robot in the frame of the plan
00111       tf::Stamped<tf::Pose> robot_pose;
00112       robot_pose.setIdentity();
00113       robot_pose.frame_id_ = costmap.getBaseFrameID();
00114       robot_pose.stamp_ = ros::Time();
00115       tf.transformPose(plan_pose.header.frame_id, robot_pose, robot_pose);
00116 
00117       //we'll keep points on the plan that are within the window that we're looking at
00118 
00119       double dist_threshold = std::max(
00120           costmap.getCostmap()->getSizeInMetersX() / 2.0,
00121           costmap.getCostmap()->getSizeInMetersY() / 2.0
00122           );
00123 
00124       unsigned int i = 0;
00125       double sq_dist_threshold = dist_threshold * dist_threshold;
00126       double sq_dist = DBL_MAX;
00127 
00128       // --- start - modification w.r.t. base_local_planner
00129       // initiate start_end_count
00130       std::vector<int> start_end_count;
00131       start_end_count.assign(2, 0);
00132 
00133       // we know only one direction and that is forward! - initiate search with previous start_end_counts
00134       // this is neccesserry to work with the sampling based planners - path may severall time enter and leave moving window
00135       ROS_ASSERT( (start_end_counts.at(0) > 0) && (start_end_counts.at(0) <= (int) global_plan.size()) );
00136       i = (unsigned int) global_plan.size() - (unsigned int) start_end_counts.at(0);
00137       // --- end - modification w.r.t. base_local_planner
00138 
00139       //we need to loop to a point on the plan that is within a certain distance of the robot
00140       while(i < (unsigned int)global_plan.size() && sq_dist > sq_dist_threshold)
00141       {
00142         double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
00143         double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
00144         sq_dist = x_diff * x_diff + y_diff * y_diff;
00145 
00146         // --- start - modification w.r.t. base_local_planner
00147         // not yet in reach - get next frame
00148         if( sq_dist > sq_dist_threshold )
00149           ++i;
00150         else
00151           // set counter for start of transformed intervall - from back as beginning of plan might be prunned
00152           start_end_count.at(0) = (int) (((unsigned int) global_plan.size()) - i);
00153         // --- end - modification w.r.t. base_local_planner
00154       }
00155 
00156 
00157       tf::Stamped<tf::Pose> tf_pose;
00158       geometry_msgs::PoseStamped newer_pose;
00159 
00160       //now we'll transform until points are outside of our distance threshold
00161       while(i < (unsigned int)global_plan.size() && sq_dist < sq_dist_threshold)
00162       {
00163         double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
00164         double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
00165         sq_dist = x_diff * x_diff + y_diff * y_diff;
00166 
00167         const geometry_msgs::PoseStamped& pose = global_plan[i];
00168         poseStampedMsgToTF(pose, tf_pose);
00169         tf_pose.setData(transform * tf_pose);
00170         tf_pose.stamp_ = transform.stamp_;
00171         tf_pose.frame_id_ = global_frame;
00172         poseStampedTFToMsg(tf_pose, newer_pose);
00173 
00174         transformed_plan.push_back(newer_pose);
00175 
00176         // --- start - modification w.r.t. base_local_planner
00177         // set counter for end of transformed intervall - from back as beginning of plan might be prunned
00178         start_end_count.at(1) = int (((unsigned int) global_plan.size()) - i);
00179         // --- end - modification w.r.t. base_local_planner
00180 
00181         ++i;
00182       }
00183 
00184       // --- start - modification w.r.t. base_local_planner
00185       // write to reference variable
00186       start_end_counts = start_end_count;
00187       // --- end - modification w.r.t. base_local_planner
00188     }
00189     catch(tf::LookupException& ex)
00190     {
00191       ROS_ERROR("No Transform available Error: %s\n", ex.what());
00192       return false;
00193     }
00194     catch(tf::ConnectivityException& ex)
00195     {
00196       ROS_ERROR("Connectivity Error: %s\n", ex.what());
00197       return false;
00198     }
00199     catch(tf::ExtrapolationException& ex)
00200     {
00201       ROS_ERROR("Extrapolation Error: %s\n", ex.what());
00202       if (global_plan.size() > 0)
00203         ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
00204 
00205       return false;
00206     }
00207 
00208     return true;
00209   }
00210 
00211   double getCircumscribedRadius(costmap_2d::Costmap2DROS& costmap) {
00212     std::vector<geometry_msgs::Point> footprint(costmap.getRobotFootprint());
00213     double max_distance_sqr = 0;
00214     for (size_t i = 0; i < footprint.size(); ++i) {
00215       geometry_msgs::Point& p = footprint[i];
00216       double distance_sqr = p.x*p.x + p.y*p.y;
00217       if (distance_sqr > max_distance_sqr) {
00218         max_distance_sqr = distance_sqr;
00219       }
00220     }
00221     return sqrt(max_distance_sqr);
00222   }
00223 
00224 
00225 }


eband_local_planner
Author(s): Christian Connette, Bhaskara Marthi, Piyush Khandelwal
autogenerated on Thu Jun 6 2019 18:50:52