$search
00001 /* 00002 * safe_trajectory_planner.cpp 00003 * 00004 * Created on: Mar 25, 2010 00005 * Author: duhadway 00006 */ 00007 00008 #include <safe_teleop_base/safe_trajectory_planner_ros.h> 00009 #include <ros/console.h> 00010 #include <sys/time.h> 00011 00012 #include "geometry_msgs/PolygonStamped.h" 00013 #include "nav_msgs/Path.h" 00014 00015 using namespace std; 00016 using namespace costmap_2d; 00017 using namespace base_local_planner; 00018 00019 namespace safe_teleop { 00020 00021 SafeTrajectoryPlannerROS::SafeTrajectoryPlannerROS(tf::TransformListener* tf, Costmap2DROS* costmap_ros) 00022 : nh_(), world_model_(NULL), tc_(NULL), costmap_ros_(costmap_ros), tf_(tf) { 00023 rot_stopped_velocity_ = 1e-2; 00024 trans_stopped_velocity_ = 1e-2; 00025 double acc_lim_x, acc_lim_y, acc_lim_theta, sim_time, sim_granularity; 00026 int vx_samples, vy_samples, vtheta_samples; 00027 double userdist_scale, occdist_scale; 00028 bool dwa, holonomic_robot; 00029 double max_vel_x, min_vel_x; 00030 double max_vel_y, min_vel_y; 00031 string world_model_type; 00032 00033 //initialize the copy of the costmap the controller will use 00034 costmap_ros_->getCostmapCopy(costmap_); 00035 00036 ros::NodeHandle private_nh("~"); 00037 00038 l_plan_pub_ = private_nh.advertise<nav_msgs::Path>("local_plan", 1); 00039 u_plan_pub_ = private_nh.advertise<nav_msgs::Path>("user_plan", 1); 00040 00041 global_frame_ = costmap_ros_->getGlobalFrameID(); 00042 robot_base_frame_ = costmap_ros_->getBaseFrameID(); 00043 00044 odom_sub_ = nh_.subscribe<nav_msgs::Odometry>("/odom", 1, &SafeTrajectoryPlannerROS::odomCallback, this); 00045 user_sub_ = nh_.subscribe<geometry_msgs::Twist>("base_velocity", 1, boost::bind(&SafeTrajectoryPlannerROS::cmdCallback, this, _1)); 00046 00047 cmd_pub_ = private_nh.advertise<geometry_msgs::Twist>("safe_vel", 1); 00048 00049 geometry_msgs::Twist vel; 00050 cmd_pub_.publish(vel); 00051 00052 //we'll get the parameters for the robot radius from the costmap we're associated with 00053 inscribed_radius_ = costmap_ros_->getInscribedRadius(); 00054 circumscribed_radius_ = costmap_ros_->getCircumscribedRadius(); 00055 inflation_radius_ = costmap_ros_->getInflationRadius(); 00056 00057 private_nh.param("acc_lim_x", acc_lim_x, 2.5); 00058 private_nh.param("acc_lim_y", acc_lim_y, 2.5); 00059 private_nh.param("acc_lim_th", acc_lim_theta, 3.2); 00060 private_nh.param("sim_time", sim_time, 1.0); 00061 private_nh.param("sim_granularity", sim_granularity, 0.025); 00062 private_nh.param("vx_samples", vx_samples, 3); 00063 private_nh.param("vy_samples", vy_samples, 5); 00064 private_nh.param("vtheta_samples", vtheta_samples, 10); 00065 private_nh.param("user_bias", userdist_scale, 0.6); 00066 private_nh.param("occdist_scale", occdist_scale, 0.01); 00067 private_nh.param("max_vel_x", max_vel_x, 0.5); 00068 private_nh.param("min_vel_x", min_vel_x, 0.1); 00069 private_nh.param("max_vel_y", max_vel_y, 0.2); 00070 private_nh.param("min_vel_y", min_vel_y, -0.2); 00071 00072 00073 double max_rotational_vel; 00074 private_nh.param("max_rotational_vel", max_rotational_vel, 1.0); 00075 max_vel_th_ = max_rotational_vel; 00076 min_vel_th_ = -1.0 * max_rotational_vel; 00077 00078 private_nh.param("world_model", world_model_type, string("costmap")); 00079 private_nh.param("holonomic_robot", holonomic_robot, true); 00080 private_nh.param("dwa", dwa, true); 00081 00082 //parameters for using the freespace controller 00083 double min_pt_separation, max_obstacle_height, grid_resolution; 00084 private_nh.param("point_grid/max_sensor_range", max_sensor_range_, 2.0); 00085 private_nh.param("point_grid/min_pt_separation", min_pt_separation, 0.01); 00086 private_nh.param("point_grid/max_obstacle_height", max_obstacle_height, 2.0); 00087 private_nh.param("point_grid/grid_resolution", grid_resolution, 0.2); 00088 00089 ROS_ASSERT_MSG(world_model_type == "costmap", "At this time, only costmap world models are supported by this controller"); 00090 world_model_ = new CostmapModel(costmap_); 00091 00092 std::vector<double> y_vels = loadYVels(private_nh); 00093 00094 tc_ = new SafeTrajectoryPlanner(*world_model_, costmap_, costmap_ros_->getRobotFootprint(), inscribed_radius_, circumscribed_radius_, 00095 acc_lim_x, acc_lim_y, acc_lim_theta, sim_time, sim_granularity, vx_samples, vy_samples, vtheta_samples, 00096 userdist_scale, occdist_scale, 00097 max_vel_x, min_vel_x, max_vel_y, min_vel_y, max_vel_th_, min_vel_th_, 00098 holonomic_robot, dwa); 00099 } 00100 00101 std::vector<double> SafeTrajectoryPlannerROS::loadYVels(ros::NodeHandle node){ 00102 std::vector<double> y_vels; 00103 00104 XmlRpc::XmlRpcValue y_vel_list; 00105 if(node.getParam("y_vels", y_vel_list)){ 00106 ROS_ASSERT_MSG(y_vel_list.getType() == XmlRpc::XmlRpcValue::TypeArray, 00107 "The y velocities to explore must be specified as a list"); 00108 00109 for(int i = 0; i < y_vel_list.size(); ++i){ 00110 //make sure we have a list of lists of size 2 00111 XmlRpc::XmlRpcValue vel = y_vel_list[i]; 00112 00113 //make sure that the value we're looking at is either a double or an int 00114 ROS_ASSERT(vel.getType() == XmlRpc::XmlRpcValue::TypeInt || vel.getType() == XmlRpc::XmlRpcValue::TypeDouble); 00115 double y_vel = vel.getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(vel) : (double)(vel); 00116 00117 y_vels.push_back(y_vel); 00118 00119 } 00120 } 00121 else{ 00122 //if no values are passed in, we'll provide defaults 00123 y_vels.push_back(-0.3); 00124 y_vels.push_back(-0.1); 00125 y_vels.push_back(0.1); 00126 y_vels.push_back(0.3); 00127 } 00128 00129 return y_vels; 00130 } 00131 00132 SafeTrajectoryPlannerROS::~SafeTrajectoryPlannerROS(){ 00133 if(tc_ != NULL) 00134 delete tc_; 00135 00136 if(world_model_ != NULL) 00137 delete world_model_; 00138 } 00139 00140 bool SafeTrajectoryPlannerROS::stopped(){ 00141 boost::recursive_mutex::scoped_lock(odom_lock_); 00142 return abs(base_odom_.twist.twist.angular.z) <= rot_stopped_velocity_ 00143 && abs(base_odom_.twist.twist.linear.x) <= trans_stopped_velocity_ 00144 && abs(base_odom_.twist.twist.linear.y) <= trans_stopped_velocity_; 00145 } 00146 00147 double SafeTrajectoryPlannerROS::distance(double x1, double y1, double x2, double y2){ 00148 return sqrt((x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1)); 00149 } 00150 00151 void SafeTrajectoryPlannerROS::odomCallback(const nav_msgs::Odometry::ConstPtr& msg){ 00152 //we assume that the odometry is published in the frame of the base 00153 boost::recursive_mutex::scoped_lock(odom_lock_); 00154 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x; 00155 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y; 00156 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z; 00157 // ROS_DEBUG("In the odometry callback with velocity values: (%.2f, %.2f, %.2f)", 00158 // base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z); 00159 } 00160 00161 void SafeTrajectoryPlannerROS::cmdCallback(const geometry_msgs::Twist::ConstPtr& vel) { 00162 if ((vel->linear.x > 0) || (fabs(vel->linear.y) > 0)) { 00163 geometry_msgs::Twist safe_vel; 00164 if (computeVelocityCommands(vel, safe_vel)) { 00165 cmd_pub_.publish(safe_vel); 00166 if ((vel->linear.x != safe_vel.linear.x) || (vel->angular.z != safe_vel.angular.z)) { 00167 ROS_DEBUG("safe: (%.2f, %.2f) -> (%.2f, %.2f)", 00168 vel->linear.x, vel->angular.z, 00169 safe_vel.linear.x, safe_vel.angular.z); 00170 } 00171 } else { 00172 geometry_msgs::Twist zero_vel; 00173 cmd_pub_.publish(zero_vel); 00174 ROS_DEBUG("zero: (%.2f, %.2f) -> (%.2f, %.2f)", 00175 vel->linear.x, vel->angular.z, 00176 zero_vel.linear.x, zero_vel.angular.z); 00177 } 00178 00179 } else { // backwards and rotations allowed to pass through directly 00180 cmd_pub_.publish(vel); 00181 } 00182 } 00183 00184 bool SafeTrajectoryPlannerROS::computeVelocityCommands(const geometry_msgs::Twist::ConstPtr& vel, geometry_msgs::Twist& cmd_vel){ 00185 std::vector<geometry_msgs::PoseStamped> local_plan; 00186 std::vector<geometry_msgs::PoseStamped> user_plan; 00187 tf::Stamped<tf::Pose> global_pose; 00188 if(!costmap_ros_->getRobotPose(global_pose)) 00189 return false; 00190 00191 //we also want to clear the robot footprint from the costmap we're using 00192 // costmap_ros_->clearRobotFootprint(); 00193 00194 //make sure to update the costmap we'll use for this cycle 00195 costmap_ros_->getCostmapCopy(costmap_); 00196 00197 // Set current velocities from odometry 00198 geometry_msgs::Twist global_vel; 00199 00200 odom_lock_.lock(); 00201 global_vel.linear.x = base_odom_.twist.twist.linear.x; 00202 global_vel.linear.y = base_odom_.twist.twist.linear.y; 00203 global_vel.angular.z = base_odom_.twist.twist.angular.z; 00204 odom_lock_.unlock(); 00205 00206 tf::Stamped<tf::Pose> drive_cmds; 00207 drive_cmds.frame_id_ = robot_base_frame_; 00208 00209 tf::Stamped<tf::Pose> robot_vel; 00210 00211 robot_vel.setData(btTransform(tf::createQuaternionFromYaw(global_vel.angular.z), btVector3(global_vel.linear.x, global_vel.linear.y, 0))); 00212 robot_vel.frame_id_ = robot_base_frame_; 00213 robot_vel.stamp_ = ros::Time(); 00214 00215 tf::Stamped<tf::Pose> user_vel; 00216 user_vel.setData(btTransform(tf::createQuaternionFromYaw(vel->angular.z), btVector3(vel->linear.x, vel->linear.y, 0))); 00217 user_vel.frame_id_ = robot_base_frame_; 00218 user_vel.stamp_ = ros::Time(); 00219 00220 /* For timing uncomment 00221 struct timeval start, end; 00222 double start_t, end_t, t_diff; 00223 gettimeofday(&start, NULL); 00224 */ 00225 00226 //compute what trajectory to drive along 00227 Trajectory path = tc_->findBestPath(global_pose, robot_vel, user_vel, drive_cmds); 00228 Trajectory user_path = tc_->findPath(global_pose, robot_vel, user_vel); 00229 00230 /* For timing uncomment 00231 gettimeofday(&end, NULL); 00232 start_t = start.tv_sec + double(start.tv_usec) / 1e6; 00233 end_t = end.tv_sec + double(end.tv_usec) / 1e6; 00234 t_diff = end_t - start_t; 00235 ROS_INFO("Cycle time: %.9f", t_diff); 00236 */ 00237 00238 //pass along drive commands 00239 cmd_vel.linear.x = drive_cmds.getOrigin().getX(); 00240 cmd_vel.linear.y = drive_cmds.getOrigin().getY(); 00241 cmd_vel.angular.z = tf::getYaw(drive_cmds.getRotation()); 00242 00243 //if we cannot move... tell someone 00244 if(path.cost_ < 0){ 00245 local_plan.clear(); 00246 // publishPlan(transformed_plan, g_plan_pub_, 0.0, 1.0, 0.0, 0.0); 00247 publishPlan(local_plan, l_plan_pub_, 0.0, 0.0, 1.0, 0.0); 00248 return false; 00249 } 00250 00251 // Fill out the local plan 00252 for(unsigned int i = 0; i < path.getPointsSize(); ++i){ 00253 double p_x, p_y, p_th; 00254 path.getPoint(i, p_x, p_y, p_th); 00255 00256 tf::Stamped<tf::Pose> p = tf::Stamped<tf::Pose>(tf::Pose(tf::createQuaternionFromYaw(p_th), tf::Point(p_x, p_y, 0.0)), ros::Time::now(), global_frame_); 00257 geometry_msgs::PoseStamped pose; 00258 tf::poseStampedTFToMsg(p, pose); 00259 local_plan.push_back(pose); 00260 } 00261 00262 // Fill out the user plan 00263 for(unsigned int i = 0; i < user_path.getPointsSize(); ++i){ 00264 double p_x, p_y, p_th; 00265 user_path.getPoint(i, p_x, p_y, p_th); 00266 00267 tf::Stamped<tf::Pose> p = tf::Stamped<tf::Pose>(tf::Pose(tf::createQuaternionFromYaw(p_th), tf::Point(p_x, p_y, 0.0)), ros::Time::now(), global_frame_); 00268 geometry_msgs::PoseStamped pose; 00269 tf::poseStampedTFToMsg(p, pose); 00270 user_plan.push_back(pose); 00271 } 00272 00273 //publish information to the visualizer 00274 publishPlan(local_plan, l_plan_pub_, 0.0, 0.0, 1.0, 0.0); 00275 publishPlan(user_plan, u_plan_pub_, 0.0, 0.0, 1.0, 0.0); 00276 return true; 00277 } 00278 00279 void SafeTrajectoryPlannerROS::publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, const ros::Publisher& pub, double r, double g, double b, double a){ 00280 //given an empty path we won't do anything 00281 if(path.empty()) 00282 return; 00283 00284 //create a path message 00285 nav_msgs::Path gui_path; 00286 gui_path.set_poses_size(path.size()); 00287 gui_path.header.frame_id = global_frame_; 00288 gui_path.header.stamp = path[0].header.stamp; 00289 00290 // Extract the plan in world co-ordinates, we assume the path is all in the same frame 00291 for(unsigned int i=0; i < path.size(); i++){ 00292 gui_path.poses[i] = path[i]; 00293 } 00294 00295 pub.publish(gui_path); 00296 } 00297 }; 00298 00299 int main(int argc, char** argv) { 00300 ros::init(argc, argv, "safe_trajectory_node"); 00301 tf::TransformListener tf(ros::Duration(10)); 00302 costmap_2d::Costmap2DROS* costmap_ros = new costmap_2d::Costmap2DROS("local_costmap", tf); 00303 safe_teleop::SafeTrajectoryPlannerROS* planner = new safe_teleop::SafeTrajectoryPlannerROS(&tf, costmap_ros); 00304 00305 ros::spin(); 00306 00307 delete planner; 00308 delete costmap_ros; 00309 return(0); 00310 }