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   collision_proximity_space_->setCollisionTolerance(.05);
00113 
00114   
00115   vis_marker_array_publisher_ = root_handle_.advertise<visualization_msgs::MarkerArray>( "visualization_marker_array", 0 );
00116   vis_marker_publisher_ = root_handle_.advertise<visualization_msgs::Marker>( "visualization_marker", 0 );
00117 
00118   
00119   plan_kinematic_path_service_ = root_handle_.advertiseService("chomp_planner_longrange/plan_path", &ChompPlannerNode::planKinematicPath, this);
00120 
00121   filter_joint_trajectory_service_ = root_handle_.advertiseService("chomp_planner_longrange/filter_trajectory_with_constraints", &ChompPlannerNode::filterJointTrajectory, this);
00122 
00123   if(use_trajectory_filter_) {
00124     filter_trajectory_client_ = root_handle_.serviceClient<arm_navigation_msgs::FilterJointTrajectoryWithConstraints>("trajectory_filter/filter_trajectory_with_constraints");    
00125   
00126     ros::service::waitForService("trajectory_filter/filter_trajectory_with_constraints");
00127   }
00128 
00129   ROS_INFO("Initalized CHOMP planning service...");
00130 
00131   return true;
00132 }
00133 
00134 ChompPlannerNode::~ChompPlannerNode()
00135 {
00136   delete collision_models_;
00137 }
00138 
00139 int ChompPlannerNode::run()
00140 {
00141   ros::spin();
00142   return 0;
00143 }
00144 
00145 bool ChompPlannerNode::planKinematicPath(arm_navigation_msgs::GetMotionPlan::Request &reqIn, arm_navigation_msgs::GetMotionPlan::Response &res)
00146 {
00147   arm_navigation_msgs::GetMotionPlan::Request req = reqIn;
00148   if (!(req.motion_plan_request.goal_constraints.position_constraints.empty() && req.motion_plan_request.goal_constraints.orientation_constraints.empty()))
00149   {
00150     ROS_ERROR("CHOMP cannot handle pose contraints yet.");
00151     res.error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::INVALID_GOAL_POSITION_CONSTRAINTS;
00152     return false;
00153   }
00154 
00155   sensor_msgs::JointState joint_goal_chomp = arm_navigation_msgs::jointConstraintsToJointState(req.motion_plan_request.goal_constraints.joint_constraints);
00156   ROS_INFO("Chomp goal");
00157 
00158   if(joint_goal_chomp.name.size() != joint_goal_chomp.position.size())
00159   {
00160     ROS_ERROR("Invalid chomp goal");
00161     res.error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::INVALID_GOAL_JOINT_CONSTRAINTS;
00162     return false;
00163   }
00164 
00165   for(unsigned int i=0; i<joint_goal_chomp.name.size(); i++)
00166   {
00167     ROS_INFO("%s %f",joint_goal_chomp.name[i].c_str(),joint_goal_chomp.position[i]);
00168   }
00169 
00170   ros::WallTime start_time = ros::WallTime::now();
00171   ROS_INFO("Received planning request...");
00172 
00173   string group_name;
00174   group_name = req.motion_plan_request.group_name;
00175 
00176   vector<string> linkNames;
00177   vector<string> attachedBodies;
00178   ros::WallTime start = ros::WallTime::now();
00179   collision_proximity_space_->setupForGroupQueries(group_name,
00180                                                    req.motion_plan_request.start_state,
00181                                                    linkNames,
00182                                                    attachedBodies);
00183   ROS_INFO_STREAM("Setting up for queries time is " << (ros::WallTime::now() - start));
00184   
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     
00265     
00266     res.trajectory.joint_trajectory.points[i].time_from_start = ros::Duration(0.0);
00267   }
00268 
00269   ROS_INFO("Bottom took %f sec to create", (ros::WallTime::now() - create_time).toSec());
00270   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());
00271   res.error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::SUCCESS;
00272   res.planning_time = ros::Duration((ros::WallTime::now() - start_time).toSec());
00273   return true;
00274 }
00275 
00276 bool ChompPlannerNode::filterJointTrajectory(arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Request &request, arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Response &res)
00277 {
00278   arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Request req = request;
00279   ros::WallTime start_time = ros::WallTime::now();
00280   ROS_INFO_STREAM("Received filtering request with trajectory size " << req.trajectory.points.size());
00281 
00282   if(req.path_constraints.joint_constraints.size() > 0 ||
00283      req.path_constraints.position_constraints.size() > 0 ||
00284      req.path_constraints.orientation_constraints.size() > 0 ||
00285      req.path_constraints.visibility_constraints.size() > 0) {
00286     if(use_trajectory_filter_) {
00287       ROS_INFO("Chomp can't handle path constraints, passing through to other trajectory filters");
00288       if(!filter_trajectory_client_.call(req,res)) {
00289         ROS_INFO("Pass through failed");
00290       } else {
00291         ROS_INFO("Pass through succeeded");
00292       }
00293     } else {
00294       ROS_INFO("Chomp can't handle path constraints, and not set up to use additional filter");
00295     }
00296     return true;
00297   } 
00298   for (unsigned int i=0; i< req.trajectory.points.size(); i++)
00299   {
00300     req.trajectory.points[i].velocities.resize(req.trajectory.joint_names.size(),0.0);
00301   }
00302 
00303   getLimits(req.trajectory, req.limits);
00304 
00305   trajectory_msgs::JointTrajectory jtraj;
00306 
00307   int num_points = req.trajectory.points.size();
00308   if(num_points > maximum_spline_points_) {
00309     num_points = maximum_spline_points_;
00310   } else if(num_points < minimum_spline_points_) {
00311     num_points = minimum_spline_points_;
00312   }
00313 
00314 
00315   
00316   spline_smoother::CubicTrajectory trajectory_solver;
00317   spline_smoother::SplineTrajectory spline;
00318 
00319   planning_environment::setRobotStateAndComputeTransforms(req.start_state,
00320                                                           *collision_proximity_space_->getCollisionModelsInterface()->getPlanningSceneState());
00321   
00322   trajectory_solver.parameterize(req.trajectory,req.limits,spline);  
00323   
00324   double smoother_time;
00325   spline_smoother::getTotalTime(spline, smoother_time);
00326   
00327   ROS_INFO_STREAM("Total time given is " << smoother_time);
00328   
00329   double t = 0.0;
00330   vector<double> times(num_points);
00331   for(int i = 0; i < num_points; i++,t += smoother_time/(1.0*(num_points-1))) {
00332     times[i] = t;
00333   }
00334     
00335   spline_smoother::sampleSplineTrajectory(spline, times, jtraj);
00336   
00337   
00338   
00339   t = 0.0;
00340   for(unsigned int i = 0; i < jtraj.points.size(); i++, t += smoother_time/(1.0*(num_points-1))) {
00341     jtraj.points[i].time_from_start = ros::Duration(t);
00342   }
00343   
00344   ROS_INFO_STREAM("Sampled trajectory has " << jtraj.points.size() << " points with " << jtraj.points[0].positions.size() << " joints");
00345 
00346 
00347   string group_name;
00348   group_name = req.group_name;
00349 
00350   vector<string> linkNames;
00351   vector<string> attachedBodies;
00352   collision_proximity_space_->setupForGroupQueries(group_name,
00353                                                    req.start_state,
00354                                                    linkNames,
00355                                                    attachedBodies);
00356 
00357   ChompTrajectory trajectory(robot_model_, group_name, jtraj);
00358 
00359   
00360   arm_navigation_msgs::RobotState robot_state = req.start_state;
00361 
00362   jointStateToArray(arm_navigation_msgs::createJointState(req.trajectory.joint_names, jtraj.points[0].positions), group_name, trajectory.getTrajectoryPoint(0));
00363 
00364   
00365   
00366   int goal_index = trajectory.getNumPoints()-1;
00367   trajectory.getTrajectoryPoint(goal_index) = trajectory.getTrajectoryPoint(0);
00368 
00369   sensor_msgs::JointState goal_state = arm_navigation_msgs::createJointState(req.trajectory.joint_names, jtraj.points.back().positions);
00370 
00371   jointStateToArray(goal_state, group_name,trajectory.getTrajectoryPoint(goal_index));
00372   
00373   map<string, KinematicModel::JointModelGroup*> groupMap = robot_model_->getJointModelGroupMap();
00374   KinematicModel::JointModelGroup* modelGroup = groupMap[group_name];
00375 
00376   
00377   for (size_t i = 0; i < modelGroup->getJointModels().size(); i++)
00378   {
00379     const KinematicModel::JointModel* model = modelGroup->getJointModels()[i];
00380     const KinematicModel::RevoluteJointModel* revoluteJoint = dynamic_cast<const KinematicModel::RevoluteJointModel*>(model);
00381 
00382     if (revoluteJoint != NULL)
00383     {
00384       if(revoluteJoint->continuous_)
00385       {
00386         double start = trajectory(0, i);
00387         double end = trajectory(goal_index, i);
00388         trajectory(goal_index, i) = start + angles::shortest_angular_distance(start, end);
00389       }
00390     }
00391   }
00392 
00393   
00394   trajectory.fillInMinJerk();
00395   trajectory.overwriteTrajectory(jtraj);
00396   
00397   
00398   chomp_parameters_.setPlanningTimeLimit(req.allowed_time.toSec());
00399   chomp_parameters_.setFilterMode(true);
00400   
00401   ChompOptimizer optimizer(&trajectory, robot_model_, group_name, &chomp_parameters_,
00402       vis_marker_array_publisher_, vis_marker_publisher_, collision_proximity_space_);
00403   optimizer.optimize();
00404   
00405   
00406 
00407   vector<double> velocity_limits(trajectory.getNumJoints(), numeric_limits<double>::max());
00408   res.trajectory.points.resize(trajectory.getNumPoints());
00409   
00410   res.trajectory.joint_names.resize(trajectory.getNumJoints());
00411   for (size_t i = 0; i < modelGroup->getJointModels().size(); i++)
00412   {
00413     res.trajectory.joint_names[i] = modelGroup->getJointModels()[i]->getName();
00414     velocity_limits[i] = joint_limits_[res.trajectory.joint_names[i]].max_velocity;
00415   }
00416   
00417   res.trajectory.header.stamp = ros::Time::now();
00418   res.trajectory.header.frame_id = reference_frame_;
00419 
00420   
00421 
00422   for (size_t i = 0; i < (unsigned int)trajectory.getNumPoints(); i++)
00423   {
00424     res.trajectory.points[i].positions.resize(trajectory.getNumJoints());
00425     res.trajectory.points[i].velocities.resize(trajectory.getNumJoints());
00426     for (size_t j=0; j < res.trajectory.points[i].positions.size(); j++)
00427     {
00428       res.trajectory.points[i].positions[j] = trajectory(i, j);
00429     }
00430     if (i==0)
00431       res.trajectory.points[i].time_from_start = ros::Duration(0.0);
00432     else
00433     {
00434       double duration = trajectory.getDiscretization();
00435       
00436       for (int j=0; j < trajectory.getNumJoints(); j++)
00437       {
00438         double d = fabs(res.trajectory.points[i].positions[j] - res.trajectory.points[i-1].positions[j]) / velocity_limits[j];
00439         if (d > duration)
00440           duration = d;
00441       }
00442       try {
00443         res.trajectory.points[i].time_from_start = res.trajectory.points[i-1].time_from_start + ros::Duration(duration);
00444       } catch(...) {
00445         ROS_INFO_STREAM("Potentially weird duration of " << duration);
00446       }
00447     }
00448   }
00449   arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Request  next_req;
00450   arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Response next_res;
00451 
00452   if(use_trajectory_filter_) {
00453     next_req = req;
00454     next_req.trajectory = res.trajectory;  
00455     next_req.allowed_time=ros::Duration(1.0);
00456     
00457     if(filter_trajectory_client_.call(next_req, next_res)) {
00458       ROS_INFO_STREAM("Filter call ok. Sent trajectory had " << res.trajectory.points.size() << " points.  Returned trajectory has " << next_res.trajectory.points.size() << " points ");
00459     } else {
00460       ROS_INFO("Filter call not ok");
00461     }
00462     
00463     res.trajectory = next_res.trajectory;
00464     res.error_code = next_res.error_code;
00465     res.trajectory.header.stamp = ros::Time::now();
00466     res.trajectory.header.frame_id = reference_frame_;
00467   } else {
00468     res.error_code.val = res.error_code.val = res.error_code.SUCCESS;
00469   }
00470 
00471   
00472   for (unsigned int i=1; i<res.trajectory.points.size()-1; ++i)
00473   {
00474     double dt1 = (res.trajectory.points[i].time_from_start - res.trajectory.points[i-1].time_from_start).toSec();
00475     double dt2 = (res.trajectory.points[i+1].time_from_start - res.trajectory.points[i].time_from_start).toSec();
00476 
00477     
00478     for (int j=0; j < trajectory.getNumJoints(); ++j)
00479     {
00480       double dx1 = res.trajectory.points[i].positions[j] - res.trajectory.points[i-1].positions[j];
00481       double dx2 = res.trajectory.points[i+1].positions[j] - res.trajectory.points[i].positions[j];
00482 
00483       double v1 = dx1/dt1;
00484       double v2 = dx2/dt2;
00485 
00486       res.trajectory.points[i].velocities[j] = 0.5*(v1 + v2);
00487     }
00488   }
00489 
00490   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());
00491   return true;
00492 
00493 }
00494 
00495 
00496 void ChompPlannerNode::getLimits(const trajectory_msgs::JointTrajectory& trajectory, 
00497                                  vector<arm_navigation_msgs::JointLimits>& limits_out)
00498 {
00499   int num_joints = trajectory.joint_names.size();
00500   limits_out.resize(num_joints);
00501   for (int i=0; i<num_joints; ++i)
00502   {
00503     map<string, arm_navigation_msgs::JointLimits>::const_iterator limit_it = joint_limits_.find(trajectory.joint_names[i]);
00504     arm_navigation_msgs::JointLimits limits;
00505     if (limit_it == joint_limits_.end())
00506     {
00507       
00508       node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/min_position", limits.min_position, -numeric_limits<double>::max());
00509       node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/max_position", limits.max_position, numeric_limits<double>::max());
00510       node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/max_velocity", limits.max_velocity, numeric_limits<double>::max());
00511       node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/max_acceleration", limits.max_acceleration, numeric_limits<double>::max());
00512       bool boolean;
00513       node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/has_position_limits", boolean, false);
00514       limits.has_position_limits = boolean?1:0;
00515       node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/has_velocity_limits", boolean, false);
00516       limits.has_velocity_limits = boolean?1:0;
00517       node_handle_.param("joint_limits/"+trajectory.joint_names[i]+"/has_acceleration_limits", boolean, false);
00518       limits.has_acceleration_limits = boolean?1:0;
00519       joint_limits_.insert(make_pair(trajectory.joint_names[i], limits));
00520     }
00521     else
00522     {
00523       limits = limit_it->second;
00524     }
00525     limits_out[i] = limits;
00526   }
00527 }
00528 
00529 } 
00530 
00531 int main(int argc, char** argv)
00532 {
00533   ros::init(argc, argv, "chomp_planner_node");
00534 
00535   
00536   
00537 
00538   ros::NodeHandle node_handle("~");
00539   string robotDescription;
00540   ros::param::param<string>("robot_description_file_name", robotDescription, "");
00541   bool use_signed_environment_field = false;
00542   bool use_signed_self_field = false;
00543   ros::param::param<bool>("use_signed_environment_field", use_signed_environment_field, false);
00544   ros::param::param<bool>("use_signed_self_field", use_signed_self_field, false);
00545   chomp::ChompPlannerNode chomp_planner_node(node_handle, new CollisionProximitySpace("robot_description",true,use_signed_environment_field, use_signed_self_field));
00546   if (!chomp_planner_node.init())
00547     return 1;
00548   return chomp_planner_node.run();
00549   
00550 }