00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include <chomp_motion_planner/chomp_planner_node.h>
00038 #include <chomp_motion_planner/chomp_trajectory.h>
00039 #include <chomp_motion_planner/chomp_utils.h>
00040 #include <chomp_motion_planner/chomp_parameters.h>
00041 #include <chomp_motion_planner/chomp_optimizer.h>
00042 #include <kdl/jntarray.hpp>
00043 #include <angles/angles.h>
00044 #include <visualization_msgs/MarkerArray.h>
00045 #include <spline_smoother/cubic_trajectory.h>
00046 #include <arm_navigation_msgs/FilterJointTrajectory.h>
00047 #include <planning_environment/models/model_utils.h>
00048 #include <spline_smoother/fritsch_butland_spline_smoother.h>
00049
00050 #include <map>
00051 #include <vector>
00052 #include <string>
00053
00054 using namespace std;
00055 using namespace planning_models;
00056 using namespace collision_proximity;
00057
00058 namespace chomp
00059 {
00060
00061 ChompPlannerNode::ChompPlannerNode(ros::NodeHandle node_handle, CollisionProximitySpace* space) : node_handle_(node_handle), collision_proximity_space_(space)
00062
00063 {
00064
00065 }
00066
00067 bool ChompPlannerNode::init()
00068 {
00069
00070 node_handle_.param("trajectory_duration", trajectory_duration_, 3.0);
00071 node_handle_.param("trajectory_discretization", trajectory_discretization_, 0.03);
00072 node_handle_.param("use_additional_trajectory_filter", use_trajectory_filter_, false);
00073 node_handle_.param("minimum_spline_points", minimum_spline_points_, 40);
00074 node_handle_.param("maximum_spline_points", maximum_spline_points_, 100);
00075 if(node_handle_.hasParam("joint_velocity_limits")) {
00076 XmlRpc::XmlRpcValue velocity_limits;
00077
00078 node_handle_.getParam("joint_velocity_limits", velocity_limits);
00079
00080 if(velocity_limits.getType() == XmlRpc::XmlRpcValue::TypeStruct) {
00081 if(velocity_limits.size() > 0) {
00082 for(XmlRpc::XmlRpcValue::iterator it = velocity_limits.begin();
00083 it != velocity_limits.end();
00084 it++) {
00085 joint_velocity_limits_[it->first] = it->second;
00086 ROS_DEBUG_STREAM("Vel limit for " << it->first << " is " << joint_velocity_limits_[it->first]);
00087 }
00088 }
00089 }
00090 }
00091
00092
00093
00094
00095 collision_models_ = collision_proximity_space_->getCollisionModelsInterface();
00096
00097 if(!collision_models_->loadedModels()) {
00098 ROS_ERROR("Collision models could not load models");
00099 return false;
00100 }
00101
00102
00103
00104 reference_frame_ = collision_proximity_space_->getCollisionModelsInterface()->getWorldFrameId();
00105
00106
00107 robot_model_= (planning_models::KinematicModel*)collision_proximity_space_->getCollisionModelsInterface()->getKinematicModel();
00108
00109
00110 chomp_parameters_.initFromNodeHandle();
00111
00112 double max_radius_clearance;
00113 node_handle_.param("collision_clearance",max_radius_clearance, 0.10);
00114
00115
00116
00117 vis_marker_array_publisher_ = root_handle_.advertise<visualization_msgs::MarkerArray>( "visualization_marker_array", 0 );
00118 vis_marker_publisher_ = root_handle_.advertise<visualization_msgs::Marker>( "visualization_marker", 0 );
00119
00120
00121 plan_kinematic_path_service_ = root_handle_.advertiseService("chomp_planner_longrange/plan_path", &ChompPlannerNode::planKinematicPath, this);
00122
00123 filter_joint_trajectory_service_ = root_handle_.advertiseService("chomp_planner_longrange/filter_trajectory_with_constraints", &ChompPlannerNode::filterJointTrajectory, this);
00124
00125 if(use_trajectory_filter_) {
00126 filter_trajectory_client_ = root_handle_.serviceClient<arm_navigation_msgs::FilterJointTrajectoryWithConstraints>("trajectory_filter/filter_trajectory_with_constraints");
00127
00128 ros::service::waitForService("trajectory_filter/filter_trajectory_with_constraints");
00129 }
00130
00131 ROS_INFO("Initalized CHOMP planning service...");
00132
00133 return true;
00134 }
00135
00136 ChompPlannerNode::~ChompPlannerNode()
00137 {
00138 delete collision_models_;
00139 }
00140
00141 int ChompPlannerNode::run()
00142 {
00143 ros::spin();
00144 return 0;
00145 }
00146
00147 bool ChompPlannerNode::planKinematicPath(arm_navigation_msgs::GetMotionPlan::Request &reqIn, arm_navigation_msgs::GetMotionPlan::Response &res)
00148 {
00149 arm_navigation_msgs::GetMotionPlan::Request req = reqIn;
00150 if (!(req.motion_plan_request.goal_constraints.position_constraints.empty() && req.motion_plan_request.goal_constraints.orientation_constraints.empty()))
00151 {
00152 ROS_ERROR("CHOMP cannot handle pose contraints yet.");
00153 res.error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::INVALID_GOAL_POSITION_CONSTRAINTS;
00154 return false;
00155 }
00156
00157 sensor_msgs::JointState joint_goal_chomp = arm_navigation_msgs::jointConstraintsToJointState(req.motion_plan_request.goal_constraints.joint_constraints);
00158 ROS_INFO("Chomp goal");
00159
00160 if(joint_goal_chomp.name.size() != joint_goal_chomp.position.size())
00161 {
00162 ROS_ERROR("Invalid chomp goal");
00163 res.error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::INVALID_GOAL_JOINT_CONSTRAINTS;
00164 return false;
00165 }
00166
00167 for(unsigned int i=0; i<joint_goal_chomp.name.size(); i++)
00168 {
00169 ROS_INFO("%s %f",joint_goal_chomp.name[i].c_str(),joint_goal_chomp.position[i]);
00170 }
00171
00172 ros::WallTime start_time = ros::WallTime::now();
00173 ROS_INFO("Received planning request...");
00174
00175 string group_name;
00176 group_name = req.motion_plan_request.group_name;
00177
00178 vector<string> linkNames;
00179 vector<string> attachedBodies;
00180 collision_proximity_space_->setupForGroupQueries(group_name,
00181 req.motion_plan_request.start_state,
00182 linkNames,
00183 attachedBodies);
00184 collision_proximity_space_->visualizeObjectSpheres(collision_proximity_space_->getCurrentLinkNames());
00185 ChompTrajectory trajectory(robot_model_, trajectory_duration_, trajectory_discretization_, group_name);
00186
00187 ROS_INFO("Initial trajectory has %d points", trajectory.getNumPoints());
00188
00189 jointStateToArray(req.motion_plan_request.start_state.joint_state, group_name, trajectory.getTrajectoryPoint(0));
00190
00191 ROS_INFO_STREAM("Joint state has " << req.motion_plan_request.start_state.joint_state.name.size() << " joints");
00192
00193
00194
00195 int goal_index = trajectory.getNumPoints()- 1;
00196 trajectory.getTrajectoryPoint(goal_index) = trajectory.getTrajectoryPoint(0);
00197 jointStateToArray(arm_navigation_msgs::jointConstraintsToJointState(req.motion_plan_request.goal_constraints.joint_constraints), group_name, trajectory.getTrajectoryPoint(goal_index));
00198
00199
00200 map<string, KinematicModel::JointModelGroup*> groupMap = robot_model_->getJointModelGroupMap();
00201 KinematicModel::JointModelGroup* modelGroup = groupMap[group_name];
00202
00203
00204
00205 for (size_t i = 0; i < modelGroup->getJointModels().size(); i++)
00206 {
00207 const KinematicModel::JointModel* model = modelGroup->getJointModels()[i];
00208 const KinematicModel::RevoluteJointModel* revoluteJoint = dynamic_cast<const KinematicModel::RevoluteJointModel*>(model);
00209
00210 if (revoluteJoint != NULL)
00211 {
00212 if(revoluteJoint->continuous_)
00213 {
00214 double start = (trajectory)(0, i);
00215 double end = (trajectory)(goal_index, i);
00216 (trajectory)(goal_index, i) = start + angles::shortest_angular_distance(start, end);
00217 }
00218 }
00219 }
00220
00221
00222 trajectory.fillInMinJerk();
00223
00224
00225 chomp_parameters_.setPlanningTimeLimit(req.motion_plan_request.allowed_planning_time.toSec());
00226
00227
00228 ros::WallTime create_time = ros::WallTime::now();
00229 ChompOptimizer optimizer(&trajectory, robot_model_, group_name, &chomp_parameters_,
00230 vis_marker_array_publisher_, vis_marker_publisher_, collision_proximity_space_);
00231 ROS_INFO("Optimization took %f sec to create", (ros::WallTime::now() - create_time).toSec());
00232 optimizer.optimize();
00233 ROS_INFO("Optimization actually took %f sec to run", (ros::WallTime::now() - create_time).toSec());
00234 create_time = ros::WallTime::now();
00235
00236
00237 ROS_INFO("Output trajectory has %d joints", trajectory.getNumJoints());
00238 vector<double> velocity_limits(trajectory.getNumJoints(), numeric_limits<double>::max());
00239
00240
00241 res.trajectory.joint_trajectory.joint_names.resize(trajectory.getNumJoints());
00242 for (size_t i = 0; i < modelGroup->getJointModels().size(); i++)
00243 {
00244 res.trajectory.joint_trajectory.joint_names[i] = modelGroup->getJointModels()[i]->getName();
00245
00246 if (joint_velocity_limits_.find(res.trajectory.joint_trajectory.joint_names[i])==joint_velocity_limits_.end())
00247 {
00248 joint_velocity_limits_[res.trajectory.joint_trajectory.joint_names[i]] = numeric_limits<double>::max();
00249 }
00250 velocity_limits[i] = joint_velocity_limits_[res.trajectory.joint_trajectory.joint_names[i]];
00251 }
00252
00253 res.trajectory.joint_trajectory.header = req.motion_plan_request.start_state.joint_state.header;
00254
00255
00256 res.trajectory.joint_trajectory.points.resize(trajectory.getNumPoints());
00257 for (int i=0; i < trajectory.getNumPoints(); i++)
00258 {
00259 res.trajectory.joint_trajectory.points[i].positions.resize(trajectory.getNumJoints());
00260 for (size_t j=0; j < res.trajectory.joint_trajectory.points[i].positions.size(); j++)
00261 {
00262 res.trajectory.joint_trajectory.points[i].positions[j] = trajectory.getTrajectoryPoint(i)(j);
00263 }
00264 if (i==0)
00265 res.trajectory.joint_trajectory.points[i].time_from_start = ros::Duration(0.0);
00266 else
00267 {
00268 double duration = trajectory.getDiscretization();
00269
00270 for (int j=0; j < trajectory.getNumJoints(); j++)
00271 {
00272 double d = fabs(res.trajectory.joint_trajectory.points[i].positions[j] - res.trajectory.joint_trajectory.points[i-1].positions[j]) / velocity_limits[j];
00273 if (d > duration)
00274 duration = d;
00275 }
00276 res.trajectory.joint_trajectory.points[i].time_from_start = res.trajectory.joint_trajectory.points[i-1].time_from_start + ros::Duration(duration);
00277 }
00278 }
00279
00280 ROS_INFO("Bottom took %f sec to create", (ros::WallTime::now() - create_time).toSec());
00281 ROS_INFO("Serviced planning request in %f wall-seconds, trajectory duration is %f", (ros::WallTime::now() - start_time).toSec(), res.trajectory.joint_trajectory.points[goal_index].time_from_start.toSec());
00282 res.error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::SUCCESS;
00283 res.planning_time = ros::Duration((ros::WallTime::now() - start_time).toSec());
00284 return true;
00285 }
00286
00287 bool ChompPlannerNode::filterJointTrajectory(arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Request &request, arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Response &res)
00288 {
00289 arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Request req = request;
00290 ros::WallTime start_time = ros::WallTime::now();
00291 ROS_INFO_STREAM("Received filtering request with trajectory size " << req.trajectory.points.size());
00292
00293 if(req.path_constraints.joint_constraints.size() > 0 ||
00294 req.path_constraints.position_constraints.size() > 0 ||
00295 req.path_constraints.orientation_constraints.size() > 0 ||
00296 req.path_constraints.visibility_constraints.size() > 0) {
00297 if(use_trajectory_filter_) {
00298 ROS_INFO("Chomp can't handle path constraints, passing through to other trajectory filters");
00299 if(!filter_trajectory_client_.call(req,res)) {
00300 ROS_INFO("Pass through failed");
00301 } else {
00302 ROS_INFO("Pass through succeeded");
00303 }
00304 } else {
00305 ROS_INFO("Chomp can't handle path constraints, and not set up to use additional filter");
00306 }
00307 return true;
00308 }
00309 for (unsigned int i=0; i< req.trajectory.points.size(); i++)
00310 {
00311 req.trajectory.points[i].velocities.resize(req.trajectory.joint_names.size(),0.0);
00312 }
00313
00314 getLimits(req.trajectory, req.limits);
00315
00316 trajectory_msgs::JointTrajectory jtraj;
00317
00318 int num_points = req.trajectory.points.size();
00319 if(num_points > maximum_spline_points_) {
00320 num_points = maximum_spline_points_;
00321 } else if(num_points < minimum_spline_points_) {
00322 num_points = minimum_spline_points_;
00323 }
00324
00325
00326
00327 spline_smoother::CubicTrajectory trajectory_solver;
00328 spline_smoother::SplineTrajectory spline;
00329
00330 planning_environment::setRobotStateAndComputeTransforms(req.start_state,
00331 *collision_proximity_space_->getCollisionModelsInterface()->getPlanningSceneState());
00332
00333 trajectory_solver.parameterize(req.trajectory,req.limits,spline);
00334
00335 double smoother_time;
00336 spline_smoother::getTotalTime(spline, smoother_time);
00337
00338 ROS_INFO_STREAM("Total time given is " << smoother_time);
00339
00340 double t = 0.0;
00341 vector<double> times(num_points);
00342 for(int i = 0; i < num_points; i++,t += smoother_time/(1.0*(num_points-1))) {
00343 times[i] = t;
00344 }
00345
00346 spline_smoother::sampleSplineTrajectory(spline, times, jtraj);
00347
00348
00349
00350 t = 0.0;
00351 for(unsigned int i = 0; i < jtraj.points.size(); i++, t += smoother_time/(1.0*(num_points-1))) {
00352 jtraj.points[i].time_from_start = ros::Duration(t);
00353 }
00354
00355 ROS_INFO_STREAM("Sampled trajectory has " << jtraj.points.size() << " points with " << jtraj.points[0].positions.size() << " joints");
00356
00357
00358 string group_name;
00359 group_name = req.group_name;
00360
00361 vector<string> linkNames;
00362 vector<string> attachedBodies;
00363 collision_proximity_space_->setupForGroupQueries(group_name,
00364 req.start_state,
00365 linkNames,
00366 attachedBodies);
00367
00368 ChompTrajectory trajectory(robot_model_, group_name, jtraj);
00369
00370
00371 arm_navigation_msgs::RobotState robot_state = req.start_state;
00372
00373 jointStateToArray(arm_navigation_msgs::createJointState(req.trajectory.joint_names, jtraj.points[0].positions), group_name, trajectory.getTrajectoryPoint(0));
00374
00375
00376
00377 int goal_index = trajectory.getNumPoints()-1;
00378 trajectory.getTrajectoryPoint(goal_index) = trajectory.getTrajectoryPoint(0);
00379
00380 sensor_msgs::JointState goal_state = arm_navigation_msgs::createJointState(req.trajectory.joint_names, jtraj.points.back().positions);
00381
00382 jointStateToArray(goal_state, group_name,trajectory.getTrajectoryPoint(goal_index));
00383
00384 map<string, KinematicModel::JointModelGroup*> groupMap = robot_model_->getJointModelGroupMap();
00385 KinematicModel::JointModelGroup* modelGroup = groupMap[group_name];
00386
00387
00388 for (size_t i = 0; i < modelGroup->getJointModels().size(); i++)
00389 {
00390 const KinematicModel::JointModel* model = modelGroup->getJointModels()[i];
00391 const KinematicModel::RevoluteJointModel* revoluteJoint = dynamic_cast<const KinematicModel::RevoluteJointModel*>(model);
00392
00393 if (revoluteJoint != NULL)
00394 {
00395 if(revoluteJoint->continuous_)
00396 {
00397 double start = trajectory(0, i);
00398 double end = trajectory(goal_index, i);
00399 trajectory(goal_index, i) = start + angles::shortest_angular_distance(start, end);
00400 }
00401 }
00402 }
00403
00404
00405 trajectory.fillInMinJerk();
00406 trajectory.overwriteTrajectory(jtraj);
00407
00408
00409 chomp_parameters_.setPlanningTimeLimit(req.allowed_time.toSec());
00410 chomp_parameters_.setFilterMode(true);
00411
00412 ChompOptimizer optimizer(&trajectory, robot_model_, group_name, &chomp_parameters_,
00413 vis_marker_array_publisher_, vis_marker_publisher_, collision_proximity_space_);
00414 optimizer.optimize();
00415
00416
00417
00418 vector<double> velocity_limits(trajectory.getNumJoints(), numeric_limits<double>::max());
00419 res.trajectory.points.resize(trajectory.getNumPoints());
00420
00421 res.trajectory.joint_names.resize(trajectory.getNumJoints());
00422 for (size_t i = 0; i < modelGroup->getJointModels().size(); i++)
00423 {
00424 res.trajectory.joint_names[i] = modelGroup->getJointModels()[i]->getName();
00425 velocity_limits[i] = joint_limits_[res.trajectory.joint_names[i]].max_velocity;
00426 }
00427
00428 res.trajectory.header.stamp = ros::Time::now();
00429 res.trajectory.header.frame_id = reference_frame_;
00430
00431
00432
00433 for (size_t i = 0; i < trajectory.getNumPoints(); i++)
00434 {
00435 res.trajectory.points[i].positions.resize(trajectory.getNumJoints());
00436 res.trajectory.points[i].velocities.resize(trajectory.getNumJoints());
00437 for (size_t j=0; j < res.trajectory.points[i].positions.size(); j++)
00438 {
00439 res.trajectory.points[i].positions[j] = trajectory(i, j);
00440 }
00441 if (i==0)
00442 res.trajectory.points[i].time_from_start = ros::Duration(0.0);
00443 else
00444 {
00445 double duration = trajectory.getDiscretization();
00446
00447 for (int j=0; j < trajectory.getNumJoints(); j++)
00448 {
00449 double d = fabs(res.trajectory.points[i].positions[j] - res.trajectory.points[i-1].positions[j]) / velocity_limits[j];
00450 if (d > duration)
00451 duration = d;
00452 }
00453 try {
00454 res.trajectory.points[i].time_from_start = res.trajectory.points[i-1].time_from_start + ros::Duration(duration);
00455 } catch(...) {
00456 ROS_INFO_STREAM("Potentially weird duration of " << duration);
00457 }
00458 }
00459 }
00460 arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Request next_req;
00461 arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Response next_res;
00462
00463 if(use_trajectory_filter_) {
00464 next_req = req;
00465 next_req.trajectory = res.trajectory;
00466 next_req.allowed_time=ros::Duration(1.0);
00467
00468 if(filter_trajectory_client_.call(next_req, next_res)) {
00469 ROS_INFO_STREAM("Filter call ok. Sent trajectory had " << res.trajectory.points.size() << " points. Returned trajectory has " << next_res.trajectory.points.size() << " points ");
00470 } else {
00471 ROS_INFO("Filter call not ok");
00472 }
00473
00474 res.trajectory = next_res.trajectory;
00475 res.error_code = next_res.error_code;
00476 res.trajectory.header.stamp = ros::Time::now();
00477 res.trajectory.header.frame_id = reference_frame_;
00478 } else {
00479 res.error_code.val = res.error_code.val = res.error_code.SUCCESS;
00480 }
00481
00482
00483 for (unsigned int i=1; i<res.trajectory.points.size()-1; ++i)
00484 {
00485 double dt1 = (res.trajectory.points[i].time_from_start - res.trajectory.points[i-1].time_from_start).toSec();
00486 double dt2 = (res.trajectory.points[i+1].time_from_start - res.trajectory.points[i].time_from_start).toSec();
00487
00488
00489 for (int j=0; j < trajectory.getNumJoints(); ++j)
00490 {
00491 double dx1 = res.trajectory.points[i].positions[j] - res.trajectory.points[i-1].positions[j];
00492 double dx2 = res.trajectory.points[i+1].positions[j] - res.trajectory.points[i].positions[j];
00493
00494 double v1 = dx1/dt1;
00495 double v2 = dx2/dt2;
00496
00497 res.trajectory.points[i].velocities[j] = 0.5*(v1 + v2);
00498 }
00499 }
00500
00501 ROS_INFO("Serviced filter request in %f wall-seconds, trajectory duration is %f", (ros::WallTime::now() - start_time).toSec(), res.trajectory.points.back().time_from_start.toSec());
00502 return true;
00503
00504 }
00505
00506
00507 void ChompPlannerNode::getLimits(const trajectory_msgs::JointTrajectory& trajectory,
00508 vector<arm_navigation_msgs::JointLimits>& limits_out)
00509 {
00510 int num_joints = trajectory.joint_names.size();
00511 limits_out.resize(num_joints);
00512 for (int i=0; i<num_joints; ++i)
00513 {
00514 map<string, arm_navigation_msgs::JointLimits>::const_iterator limit_it = joint_limits_.find(trajectory.joint_names[i]);
00515 arm_navigation_msgs::JointLimits limits;
00516 if (limit_it == joint_limits_.end())
00517 {
00518
00519 node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/min_position", limits.min_position, -numeric_limits<double>::max());
00520 node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/max_position", limits.max_position, numeric_limits<double>::max());
00521 node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/max_velocity", limits.max_velocity, numeric_limits<double>::max());
00522 node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/max_acceleration", limits.max_acceleration, numeric_limits<double>::max());
00523 bool boolean;
00524 node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/has_position_limits", boolean, false);
00525 limits.has_position_limits = boolean?1:0;
00526 node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/has_velocity_limits", boolean, false);
00527 limits.has_velocity_limits = boolean?1:0;
00528 node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/has_acceleration_limits", boolean, false);
00529 limits.has_acceleration_limits = boolean?1:0;
00530 joint_limits_.insert(make_pair(trajectory.joint_names[i], limits));
00531 }
00532 else
00533 {
00534 limits = limit_it->second;
00535 }
00536 limits_out[i] = limits;
00537 }
00538 }
00539
00540 }
00541
00542 int main(int argc, char** argv)
00543 {
00544 ros::init(argc, argv, "chomp_planner_node");
00545
00546
00547
00548
00549 ros::NodeHandle node_handle("~");
00550 string robotDescription;
00551 ros::param::param<string>("robot_description_file_name", robotDescription, "");
00552 bool use_signed_environment_field = false;
00553 bool use_signed_self_field = false;
00554 ros::param::param<bool>("use_signed_environment_field", use_signed_environment_field, false);
00555 ros::param::param<bool>("use_signed_self_field", use_signed_self_field, false);
00556 chomp::ChompPlannerNode chomp_planner_node(node_handle, new CollisionProximitySpace("robot_description",true,use_signed_environment_field, use_signed_self_field));
00557 if (!chomp_planner_node.init())
00558 return 1;
00559 return chomp_planner_node.run();
00560
00561 }