$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2008, 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 the Willow Garage 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: Jonathan Scholz 00036 *********************************************************************/ 00037 00038 #include <costmap_trajectory_checker/costmap_trajectory_checker.h> 00039 #include "nav_msgs/Path.h" 00040 #include <ros/console.h> 00041 #include <sys/time.h> 00042 00043 using namespace std; 00044 using namespace costmap_2d; 00045 00046 CostmapTrajectoryChecker::CostmapTrajectoryChecker() : 00047 world_model_(NULL), costmap_ros_(NULL), initialized_(false) { 00048 } 00049 00050 CostmapTrajectoryChecker::CostmapTrajectoryChecker(Costmap2DROS* costmap_ros, std::string topic) : 00051 world_model_(NULL), costmap_ros_(NULL), initialized_(false) 00052 { 00053 initialize(costmap_ros, topic); 00054 } 00055 00056 CostmapTrajectoryChecker::CostmapTrajectoryChecker( 00057 costmap_2d::Costmap2DROS* costmap_ros, 00058 std::string frame_id, 00059 std::vector<geometry_msgs::Point> footprint, 00060 std::string topic) : 00061 world_model_(NULL), costmap_ros_(NULL), initialized_(false) 00062 { 00063 initialize(costmap_ros, topic); 00064 robot_frame_ = frame_id; 00065 footprint_spec_ = footprint; 00066 } 00067 00068 CostmapTrajectoryChecker::CostmapTrajectoryChecker(const CostmapTrajectoryChecker &checker) : world_model_(NULL), costmap_ros_(NULL), initialized_(false) 00069 { 00070 if(this == &checker) 00071 return; 00072 00073 initialize(checker.costmap_ros_, checker.traj_topic_name_); 00074 robot_frame_ = checker.robot_frame_; 00075 footprint_spec_ = checker.footprint_spec_; 00076 } 00077 00078 CostmapTrajectoryChecker& CostmapTrajectoryChecker::operator=(const CostmapTrajectoryChecker &checker) 00079 { 00080 if(this == &checker) 00081 return *this; 00082 00083 initialize(checker.costmap_ros_, checker.traj_topic_name_); 00084 robot_frame_ = checker.robot_frame_; 00085 footprint_spec_ = checker.footprint_spec_; 00086 return *this; 00087 } 00088 00089 CostmapTrajectoryChecker::~CostmapTrajectoryChecker(){} 00090 00091 void CostmapTrajectoryChecker::initialize(Costmap2DROS* costmap_ros, std::string topic) 00092 { 00093 if (!initialized_) { 00094 costmap_ros_ = costmap_ros; 00095 00096 //initialize the copy of the costmap the controller will use 00097 costmap_ros_->getCostmapCopy(costmap_); 00098 00099 robot_frame_ = costmap_ros_->getBaseFrameID(); 00100 global_frame_ = costmap_ros_->getGlobalFrameID(); 00101 footprint_spec_ = costmap_ros_->getRobotFootprint(); 00102 00103 //we'll get the parameters for the robot radius from the costmap we're associated with 00104 inscribed_radius_ = costmap_ros_->getInscribedRadius(); 00105 circumscribed_radius_ = costmap_ros_->getCircumscribedRadius(); 00106 inflation_radius_ = costmap_ros_->getInflationRadius(); 00107 00108 world_model_ = new base_local_planner::CostmapModel(costmap_); 00109 00110 setPubTopic(topic); 00111 00112 initialized_ = true; 00113 } 00114 else 00115 ROS_WARN("This planner has already been initialized, you can't call it twice, doing nothing"); 00116 } 00117 00118 void CostmapTrajectoryChecker::setFootprint(const std::vector< 00119 geometry_msgs::Point> &footprint) { 00120 footprint_spec_ = footprint; 00121 } 00122 00123 void CostmapTrajectoryChecker::setFootprint(double length, double width, double x_offset, double y_offset) 00124 { 00125 footprint_spec_.resize(4); 00126 footprint_spec_[0].x = -x_offset; 00127 footprint_spec_[0].y = -y_offset; 00128 footprint_spec_[1].x = -x_offset + length; 00129 footprint_spec_[1].y = -y_offset; 00130 footprint_spec_[2].x = -x_offset + length; 00131 footprint_spec_[2].y = -y_offset + width; 00132 footprint_spec_[3].x = -x_offset; 00133 footprint_spec_[3].y = -y_offset + width; 00134 } 00135 00136 std::vector<geometry_msgs::Point> CostmapTrajectoryChecker::getFootprint() 00137 { 00138 return footprint_spec_; 00139 } 00140 00141 void CostmapTrajectoryChecker::setGlobalFrameID(std::string frame_id) 00142 { 00143 global_frame_ = frame_id; 00144 } 00145 00146 00147 void CostmapTrajectoryChecker::setRobotFrameID(std::string frame_id) 00148 { 00149 robot_frame_ = frame_id; 00150 } 00151 00152 std::string CostmapTrajectoryChecker::getGlobalFrameID() 00153 { 00154 return global_frame_; 00155 } 00156 00157 std::string CostmapTrajectoryChecker::getRobotFrameID() 00158 { 00159 return robot_frame_; 00160 } 00161 00162 void CostmapTrajectoryChecker::setPubTopic(std::string topic) 00163 { 00164 traj_topic_name_ = topic; 00165 if (traj_topic_name_ != "") 00166 traj_pub_ = nh_.advertise<nav_msgs::Path> (traj_topic_name_, 1); 00167 } 00168 00169 std::string CostmapTrajectoryChecker::getPubTopic() 00170 { 00171 return traj_topic_name_; 00172 } 00173 00174 void CostmapTrajectoryChecker::generateTrajectory( 00175 const geometry_msgs::Pose2D &start_pose, 00176 const geometry_msgs::Twist &vel, unsigned int num_steps, double dt, 00177 std::vector<geometry_msgs::Pose2D>& traj) { 00178 00179 traj.resize(0); 00180 traj.push_back(start_pose); 00181 geometry_msgs::Pose2D cur_pose = start_pose; 00182 00183 for (unsigned int i = 1; i < num_steps; ++i) { 00184 integratePose(vel, dt, cur_pose); 00185 ROS_DEBUG("dt: %f, cur_pose: %f %f %f",dt,cur_pose.x,cur_pose.y,cur_pose.theta); 00186 traj.push_back(cur_pose); 00187 } 00188 } 00189 00190 double CostmapTrajectoryChecker::checkTrajectory(const std::vector<geometry_msgs::Pose2D>& traj, bool update_map, bool clear_footprint) 00191 { 00192 //make sure to update the costmap we'll use for this cycle 00193 if (update_map) 00194 costmap_ros_->getCostmapCopy(costmap_); 00195 00196 if (clear_footprint) { 00197 vector<geometry_msgs::Point> oriented_footprint; 00198 getOrientedFootprint(traj[0], oriented_footprint); 00199 00200 //we also want to clear the robot footprint from the costmap we're using 00201 if(!costmap_.setConvexPolygonCost(oriented_footprint, costmap_2d::FREE_SPACE)) { 00202 ROS_ERROR("Could not clear robot footprint: "); 00203 for (uint i = 0; i < oriented_footprint.size(); ++i) 00204 ROS_ERROR("oriented_footprint: %.2lf %.2lf %.2lf", oriented_footprint[i].x, oriented_footprint[i].y, oriented_footprint[i].z); 00205 return false; 00206 } 00207 } 00208 00209 double cost = -1.0; 00210 for (unsigned int i = 0; i < traj.size(); ++i) { 00211 double newcost = footprintCost(traj[i]); 00212 // get footprint cost 00213 cost = newcost < 0 ? -1.0 : std::max(cost, newcost); 00214 } 00215 00216 if (traj_topic_name_ != "") 00217 publishTrajectory(traj); 00218 00219 ROS_DEBUG("trajectory cost = %.4lf", cost); 00220 return cost; 00221 } 00222 00223 bool CostmapTrajectoryChecker::clearFootprint(const geometry_msgs::Pose2D &traj, bool update_map) 00224 { 00225 //make sure to update the costmap we'll use for this cycle 00226 if(update_map) 00227 costmap_ros_->getCostmapCopy(costmap_); 00228 00229 vector<geometry_msgs::Point> oriented_footprint; 00230 getOrientedFootprint(traj, oriented_footprint); 00231 00232 //we also want to clear the robot footprint from the costmap we're using 00233 if(!costmap_.setConvexPolygonCost(oriented_footprint, costmap_2d::FREE_SPACE)) 00234 { 00235 ROS_ERROR("Could not clear robot footprint: "); 00236 for (uint i = 0; i < oriented_footprint.size(); ++i) 00237 ROS_ERROR("oriented_footprint: %.2lf %.2lf %.2lf", oriented_footprint[i].x, oriented_footprint[i].y, oriented_footprint[i].z); 00238 return false; 00239 } 00240 return true; 00241 } 00242 00243 bool CostmapTrajectoryChecker::clearFootprint(bool update_map) 00244 { 00245 //make sure to update the costmap we'll use for this cycle 00246 if(update_map) 00247 costmap_ros_->getCostmapCopy(costmap_); 00248 00249 vector<geometry_msgs::Point> oriented_footprint; 00250 geometry_msgs::Pose2D pose; 00251 getRobotPose(pose); 00252 getOrientedFootprint(pose, oriented_footprint); 00253 00254 //we also want to clear the robot footprint from the costmap we're using 00255 if(!costmap_.setConvexPolygonCost(oriented_footprint, costmap_2d::FREE_SPACE)) 00256 { 00257 ROS_ERROR("Could not clear robot footprint: "); 00258 for (uint i = 0; i < oriented_footprint.size(); ++i) 00259 ROS_ERROR("oriented_footprint: %.2lf %.2lf %.2lf", oriented_footprint[i].x, oriented_footprint[i].y, oriented_footprint[i].z); 00260 return false; 00261 } 00262 return true; 00263 } 00264 00265 00266 double CostmapTrajectoryChecker::checkTrajectoryMonotonic(const std::vector<geometry_msgs::Pose2D>& traj, 00267 bool update_map, 00268 bool clear_footprint, 00269 unsigned int num_consec_points_in_collision) 00270 { 00271 //make sure to update the costmap we'll use for this cycle 00272 if (update_map) 00273 costmap_ros_->getCostmapCopy(costmap_); 00274 00275 if (clear_footprint) { 00276 vector<geometry_msgs::Point> oriented_footprint; 00277 getOrientedFootprint(traj[0], oriented_footprint); 00278 00279 //we also want to clear the robot footprint from the costmap we're using 00280 if(!costmap_.setConvexPolygonCost(oriented_footprint, costmap_2d::FREE_SPACE)) { 00281 ROS_ERROR("Could not clear robot footprint: "); 00282 for (uint i = 0; i < oriented_footprint.size(); ++i) 00283 ROS_ERROR("oriented_footprint: %.2lf %.2lf %.2lf", oriented_footprint[i].x, oriented_footprint[i].y, oriented_footprint[i].z); 00284 return false; 00285 } 00286 } 00287 00288 double cost = -1.0; 00289 double lastcost = 0.0; 00290 unsigned int num_lethal_cost = 0; 00291 00292 for (unsigned int i = 0; i < traj.size(); ++i) { 00293 // ROS_INFO("Checking pose: %d :: %f %f %f",i,traj[i].x,traj[i].y,traj[i].theta); 00294 00295 double newcost = footprintCost(traj[i]); 00296 cost = std::max(newcost,cost); 00297 if(newcost < 0) 00298 newcost = costmap_2d::LETHAL_OBSTACLE; 00299 00300 if(i > 0 && i < (num_consec_points_in_collision+1)&& lastcost==costmap_2d::LETHAL_OBSTACLE && newcost == costmap_2d::LETHAL_OBSTACLE) 00301 num_lethal_cost++; 00302 00303 if(i > 0 && lastcost < costmap_2d::LETHAL_OBSTACLE && (newcost==costmap_2d::LETHAL_OBSTACLE) ) 00304 { 00305 ROS_INFO("Twist points: %d %d are leading us into collision",i-1,i); 00306 return -1.0; 00307 } 00308 00309 if(num_lethal_cost > num_consec_points_in_collision || num_lethal_cost == traj.size()-1) 00310 return -1.0; 00311 lastcost = newcost; 00312 } 00313 00314 if (traj_topic_name_ != "") 00315 publishTrajectory(traj); 00316 00317 ROS_DEBUG("trajectory cost = %.4lf", cost); 00318 return cost; 00319 } 00320 00321 double CostmapTrajectoryChecker::checkTwistMonotonic(const geometry_msgs::Twist &vel, unsigned int num_steps, double dt, bool update_map, bool clear_footprint) 00322 { 00323 geometry_msgs::Pose2D pose; 00324 getRobotPose(pose); 00325 std::vector<geometry_msgs::Pose2D> traj; 00326 generateTrajectory(pose, vel, num_steps, dt, traj); 00327 00328 return checkTrajectoryMonotonic(traj, update_map, clear_footprint,5); 00329 } 00330 00331 00332 double CostmapTrajectoryChecker::checkTwist(const geometry_msgs::Twist &vel, unsigned int num_steps, double dt, bool update_map, bool clear_footprint) 00333 { 00334 geometry_msgs::Pose2D pose; 00335 getRobotPose(pose); 00336 std::vector<geometry_msgs::Pose2D> traj; 00337 generateTrajectory(pose, vel, num_steps, dt, traj); 00338 00339 return checkTrajectory(traj, update_map, clear_footprint); 00340 } 00341 00342 void CostmapTrajectoryChecker::getOrientedFootprint(const geometry_msgs::Pose2D &pose, std::vector<geometry_msgs::Point> &oriented_footprint) 00343 { 00344 oriented_footprint.resize(0); 00345 double cos_th = cos(pose.theta); 00346 double sin_th = sin(pose.theta); 00347 for(unsigned int i = 0; i < footprint_spec_.size(); ++i){ 00348 geometry_msgs::Point new_pt; 00349 new_pt.x = pose.x + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th); 00350 new_pt.y = pose.y + (footprint_spec_[i].x * sin_th + footprint_spec_[i].y * cos_th); 00351 oriented_footprint.push_back(new_pt); 00352 } 00353 } 00354 00355 //we need to take the footprint of the robot into account when we calculate cost to obstacles 00356 double CostmapTrajectoryChecker::footprintCost(const geometry_msgs::Pose2D &pose) 00357 { 00358 //build the oriented footprint 00359 vector<geometry_msgs::Point> oriented_footprint; 00360 getOrientedFootprint(pose, oriented_footprint); 00361 00362 geometry_msgs::Point robot_position; 00363 robot_position.x = pose.x; 00364 robot_position.y = pose.y; 00365 00366 //ROS_WARN("costmap checker:"); 00367 //ROS_WARN("robot_position: %.2lf %.2lf", robot_position.x, robot_position.y); 00368 //for (uint i = 0; i < oriented_footprint.size(); ++i) 00369 // ROS_WARN("oriented_footprint: %.2lf %.2lf %.2lf", oriented_footprint[i].x, oriented_footprint[i].y, oriented_footprint[i].z); 00370 //ROS_WARN("inscribed radius = %.2lf, circumscribed_radius_ = %.2lf", inscribed_radius_, circumscribed_radius_); 00371 //ROS_WARN("ctc footprint cost = %.4lf", world_model_->footprintCost(robot_position, oriented_footprint, inscribed_radius_, circumscribed_radius_)); 00372 return world_model_->footprintCost(robot_position, oriented_footprint, inscribed_radius_, circumscribed_radius_); 00373 } 00374 00375 void CostmapTrajectoryChecker::poseTFToPose2D(const tf::Pose &pose_tf, geometry_msgs::Pose2D &pose_2d) 00376 { 00377 btScalar pitch, roll, yaw; 00378 pose_tf.getBasis().getRPY(roll, pitch, yaw); 00379 00380 pose_2d.x = pose_tf.getOrigin()[0]; 00381 pose_2d.y = pose_tf.getOrigin()[1]; 00382 pose_2d.theta = yaw; 00383 00384 if (pose_tf.getOrigin()[2]>0.1) { 00385 ROS_WARN_THROTTLE(0.5, "Large linear Z component lost in conversion to 2D pose (%.2f)", pose_tf.getOrigin()[2]); 00386 } 00387 if (roll>0.1) { 00388 ROS_WARN_THROTTLE(0.5, "Large roll component lost in conversion to 2D pose (%.2f)", roll); 00389 } 00390 if (pitch>0.1) { 00391 ROS_WARN_THROTTLE(0.5, "Large roll component lost in conversion to 2D pose (%.2f)", pitch); 00392 } 00393 } 00394 00395 void CostmapTrajectoryChecker::pose2DToTF(const geometry_msgs::Pose2D pose_2d, tf::Pose &pose_tf) 00396 { 00397 btQuaternion q; 00398 q.setRPY(0, 0, pose_2d.theta); 00399 pose_tf.setRotation(q); 00400 pose_tf.setOrigin(btVector3(pose_2d.x, pose_2d.y, 0)); 00401 } 00402 00403 void CostmapTrajectoryChecker::pose2DToPose(const geometry_msgs::Pose2D pose_2d, geometry_msgs::Pose &pose) 00404 { 00405 pose.position.x = pose_2d.x; 00406 pose.position.y = pose_2d.y; 00407 pose.position.z = 0; 00408 pose.orientation = tf::createQuaternionMsgFromYaw(pose_2d.theta); 00409 } 00410 00411 void CostmapTrajectoryChecker::poseToPose2D(const geometry_msgs::Pose pose, geometry_msgs::Pose2D &pose_2d) 00412 { 00413 pose_2d.x = pose.position.x; 00414 pose_2d.y = pose.position.y; 00415 pose_2d.theta = tf::getYaw(pose.orientation); 00416 } 00417 00418 bool CostmapTrajectoryChecker::getRobotPose(geometry_msgs::Pose2D &pose_2d) const 00419 { 00420 tf::StampedTransform pose_tf; 00421 00422 //get the global pose of the robot 00423 try { 00424 tl_.lookupTransform(global_frame_, robot_frame_, ros::Time(), pose_tf); 00425 } catch (tf::LookupException& ex) { 00426 ROS_ERROR("No Transform available Error: %s\n", ex.what()); 00427 return false; 00428 } catch (tf::ConnectivityException& ex) { 00429 ROS_ERROR("Connectivity Error: %s\n", ex.what()); 00430 return false; 00431 } catch (tf::ExtrapolationException& ex) { 00432 ROS_ERROR("Extrapolation Error: %s\n", ex.what()); 00433 return false; 00434 } 00435 00436 poseTFToPose2D(pose_tf, pose_2d); 00437 00438 return true; 00439 } 00440 00441 void CostmapTrajectoryChecker::integratePose(const geometry_msgs::Twist &vel, double dt, 00442 geometry_msgs::Pose2D &pose) 00443 { 00444 pose.x += (vel.linear.x * cos(pose.theta) + vel.linear.y * cos(M_PI_2 + pose.theta)) * dt; 00445 pose.y += (vel.linear.x * sin(pose.theta) + vel.linear.y * sin(M_PI_2 + pose.theta)) * dt; 00446 pose.theta += vel.angular.z * dt; 00447 } 00448 00449 void CostmapTrajectoryChecker::publishTrajectory(const std::vector<geometry_msgs::Pose2D>& path) 00450 { 00451 //given an empty path we won't do anything 00452 if(path.empty()) 00453 return; 00454 00455 //create a path message 00456 nav_msgs::Path gui_path; 00457 gui_path.poses.resize(path.size()); 00458 gui_path.header.frame_id = global_frame_; 00459 gui_path.header.stamp = ros::Time::now(); 00460 00461 // Extract the plan in world co-ordinates, we assume the path is all in the same frame 00462 for(unsigned int i=0; i < path.size(); i++){ 00463 gui_path.poses[i].header.frame_id = global_frame_; 00464 gui_path.poses[i].header.stamp = ros::Time::now(); 00465 pose2DToPose(path[i], gui_path.poses[i].pose); 00466 } 00467 00468 traj_pub_.publish(gui_path); 00469 }