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 #ifndef LINEAR_SPLINE_SHORT_CUTTER_H_
00038 #define LINEAR_SPLINE_SHORT_CUTTER_H_
00039
00040 #include <ros/ros.h>
00041 #include <tf/tf.h>
00042 #include <spline_smoother/spline_smoother.h>
00043 #include <spline_smoother/linear_trajectory.h>
00044 #include <planning_environment/monitors/planning_monitor.h>
00045 #include <motion_planning_msgs/RobotState.h>
00046 #include <motion_planning_msgs/ArmNavigationErrorCodes.h>
00047 #include <trajectory_msgs/JointTrajectoryPoint.h>
00048
00049 namespace constraint_aware_spline_smoother
00050 {
00051
00055 template <typename T>
00056 class LinearSplineShortCutter: public spline_smoother::SplineSmoother<T>
00057 {
00058 public:
00062 LinearSplineShortCutter();
00063 virtual ~LinearSplineShortCutter();
00064 virtual bool smooth(const T& trajectory_in,
00065 T& trajectory_out) const;
00068 virtual bool configure();
00069 private:
00070 bool active_;
00071 double discretization_;
00072 bool setupCollisionEnvironment();
00073 planning_environment::CollisionModels *collision_models_;
00074 planning_environment::PlanningMonitor *planning_monitor_;
00075 ros::NodeHandle node_handle_;
00076 tf::TransformListener tf_;
00077 int getRandomInt(int min,int max) const;
00078 double getRandomTimeStamp(double min,double max) const;
00079 void discretizeTrajectory(const spline_smoother::SplineTrajectory &spline,
00080 const double &discretization,
00081 trajectory_msgs::JointTrajectory &joint_trajectory) const;
00082 bool trimTrajectory(trajectory_msgs::JointTrajectory &trajectory_out,
00083 const double &segment_start_time,
00084 const double &segment_end_time) const;
00085 bool findTrajectoryPointsInInterval(const trajectory_msgs::JointTrajectory &trajectory,
00086 const double &segment_start_time,
00087 const double &segment_end_time,
00088 int &index_1,
00089 int &index_2) const;
00090 bool getWaypoints(const spline_smoother::SplineTrajectory &spline,
00091 trajectory_msgs::JointTrajectory &joint_trajectory) const;
00092 bool addToTrajectory(trajectory_msgs::JointTrajectory &trajectory_out,
00093 const trajectory_msgs::JointTrajectoryPoint &trajectory_point,
00094 const ros::Duration& delta_time) const;
00095
00096 void printTrajectory(const trajectory_msgs::JointTrajectory &joint_trajectory) const;
00097
00098 void discretizeAndAppendSegment(const spline_smoother::SplineTrajectorySegment &spline_segment,
00099 const double &discretization,
00100 trajectory_msgs::JointTrajectory &joint_trajectory,
00101 const ros::Duration &segment_start_time,
00102 const bool &include_segment_end) const;
00103
00104 double maxLInfDistance(const trajectory_msgs::JointTrajectoryPoint &start,
00105 const trajectory_msgs::JointTrajectoryPoint &end) const;
00106
00107 void refineTrajectory(T &trajectory) const;
00108
00109 };
00110
00111 template <typename T>
00112 bool LinearSplineShortCutter<T>::configure()
00113 {
00114 if (!spline_smoother::SplineSmoother<T>::getParam("discretization", discretization_))
00115 {
00116 ROS_ERROR("Spline smoother, \"%s\", params has no attribute discretization.", spline_smoother::SplineSmoother<T>::getName().c_str());
00117 return false;
00118 }
00119 else
00120 {
00121 ROS_DEBUG("Using a discretization value of %f",discretization_);
00122 return true;
00123 }
00124 };
00125
00126 template <typename T>
00127 LinearSplineShortCutter<T>::LinearSplineShortCutter()
00128 {
00129 if(!setupCollisionEnvironment())
00130 active_ = false;
00131 else
00132 active_ = true;
00133 }
00134
00135 template <typename T>
00136 LinearSplineShortCutter<T>::~LinearSplineShortCutter()
00137 {
00138 }
00139
00140 template <typename T>
00141 int LinearSplineShortCutter<T>::getRandomInt(int min_index,int max_index)const
00142 {
00143 int rand_num = rand()%100+1;
00144 double result = min_index + (double)((max_index-min_index)*rand_num)/101.0;
00145 return (int) result;
00146 }
00147
00148 template <typename T>
00149 double LinearSplineShortCutter<T>::getRandomTimeStamp(double min,double max)const
00150 {
00151 int rand_num = rand()%100+1;
00152 double result = min + (double)((max-min)*rand_num)/101.0;
00153 return result;
00154 }
00155
00156 template <typename T>
00157 bool LinearSplineShortCutter<T>::smooth(const T& trajectory_in,
00158 T& trajectory_out) const
00159 {
00160 double discretization = discretization_;
00161 srand(time(NULL));
00162 if(!active_)
00163 {
00164 ROS_ERROR("Smoother is not active");
00165 return false;
00166 }
00167
00168 ROS_INFO("Got trajectory with %d points",(int)trajectory_in.trajectory.points.size());
00169 motion_planning_msgs::ArmNavigationErrorCodes error_code;
00170 std::vector<motion_planning_msgs::ArmNavigationErrorCodes> trajectory_error_codes;
00171 motion_planning_msgs::RobotState robot_state;
00172 spline_smoother::LinearTrajectory trajectory_solver;
00173 spline_smoother::SplineTrajectory spline, shortcut_spline;
00174 motion_planning_msgs::JointTrajectoryWithLimits shortcut, discretized_trajectory;
00175
00176 trajectory_out = trajectory_in;
00177
00178 if (!spline_smoother::checkTrajectoryConsistency(trajectory_out))
00179 return false;
00180
00181 shortcut.limits = trajectory_in.limits;
00182 shortcut.trajectory.joint_names = trajectory_in.trajectory.joint_names;
00183
00184 discretized_trajectory.limits = trajectory_in.limits;
00185 discretized_trajectory.trajectory.joint_names = trajectory_in.trajectory.joint_names;
00186
00187 ros::Time start_time = ros::Time::now();
00188 ros::Duration timeout = trajectory_in.allowed_time;
00189
00190 planning_monitor_->prepareForValidityChecks(trajectory_in.trajectory.joint_names,
00191 trajectory_in.ordered_collision_operations,
00192 trajectory_in.allowed_contacts,
00193 trajectory_in.path_constraints,
00194 trajectory_in.goal_constraints,
00195 trajectory_in.link_padding, error_code);
00196
00197
00198 planning_monitor_->getCurrentRobotState(robot_state);
00199
00200 if(error_code.val != error_code.SUCCESS)
00201 {
00202 ROS_ERROR("Could not set path constraints");
00203 return false;
00204 }
00205
00206 bool success = trajectory_solver.parameterize(trajectory_out.trajectory,trajectory_in.limits,spline);
00207 getWaypoints(spline,trajectory_out.trajectory);
00208 printTrajectory(trajectory_out.trajectory);
00209 std::vector<double> sample_times;
00210 sample_times.resize(2);
00211 bool first_try = true;
00212 while(ros::Time::now() - start_time < timeout)
00213 {
00214 double total_time = trajectory_out.trajectory.points.back().time_from_start.toSec();
00215 double segment_start_time = getRandomTimeStamp(0.0,total_time);
00216 double segment_end_time = getRandomTimeStamp(segment_start_time,total_time);
00217 if(segment_start_time == segment_end_time)
00218 continue;
00219 if(first_try)
00220 {
00221 segment_start_time = 0.0;
00222 segment_end_time = total_time;
00223 first_try = false;
00224 }
00225 sample_times[0] = segment_start_time;
00226 sample_times[1] = segment_end_time;
00227
00228 spline_smoother::sampleSplineTrajectory(spline,sample_times,shortcut.trajectory);
00229 ROS_DEBUG("Start time: %f, %f",segment_start_time,shortcut.trajectory.points[0].positions[0]);
00230 ROS_DEBUG("End time : %f, %f",segment_end_time,shortcut.trajectory.points[1].positions[0]);
00231 shortcut.trajectory.points[0].time_from_start = ros::Duration(0.0);
00232 shortcut.trajectory.points[1].time_from_start = ros::Duration(0.0);
00233
00234 if(!trajectory_solver.parameterize(shortcut.trajectory,trajectory_in.limits,shortcut_spline))
00235 return false;
00236 discretizeTrajectory(shortcut_spline,discretization,discretized_trajectory.trajectory);
00237 ROS_DEBUG("Succeeded in sampling trajectory with size: %d",(int)discretized_trajectory.trajectory.points.size());
00238
00239 if(planning_monitor_->isTrajectoryValid(discretized_trajectory.trajectory,
00240 robot_state,
00241 0,
00242 discretized_trajectory.trajectory.points.size(),
00243 planning_environment::PlanningMonitor::COLLISION_TEST | planning_environment::PlanningMonitor::PATH_CONSTRAINTS_TEST,
00244 false,
00245 error_code,
00246 trajectory_error_codes))
00247 {
00248 ros::Duration shortcut_duration = discretized_trajectory.trajectory.points.back().time_from_start - discretized_trajectory.trajectory.points.front().time_from_start;
00249 if(segment_end_time-segment_start_time <= shortcut_duration.toSec())
00250 continue;
00251 if(!trimTrajectory(trajectory_out.trajectory,segment_start_time,segment_end_time))
00252 continue;
00253 ROS_DEBUG("Trimmed trajectory has %u points",trajectory_out.trajectory.points.size());
00254
00255 ROS_DEBUG("Shortcut reduced duration from: %f to %f",
00256 segment_end_time-segment_start_time,
00257 shortcut_duration.toSec());
00258 shortcut.trajectory.points[0].time_from_start = ros::Duration(segment_start_time);
00259 shortcut.trajectory.points[1].time_from_start = ros::Duration(segment_start_time) + shortcut_duration;
00260 addToTrajectory(trajectory_out.trajectory,
00261 shortcut.trajectory.points[0],
00262 ros::Duration(0.0));
00263 addToTrajectory(trajectory_out.trajectory,
00264 shortcut.trajectory.points[1],
00265 shortcut_duration-ros::Duration(segment_end_time-segment_start_time));
00266 spline.segments.clear();
00267 if(!trajectory_solver.parameterize(trajectory_out.trajectory,trajectory_in.limits,spline))
00268 return false;
00269 if(!getWaypoints(spline,trajectory_out.trajectory))
00270 return false;
00271 printTrajectory(trajectory_out.trajectory);
00272 if(trajectory_out.trajectory.points.size() < 3)
00273 break;
00274 }
00275 else
00276 {
00277 ROS_DEBUG("Traj segment rejected with error code: %d",error_code.val);
00278 continue;
00279 }
00280 }
00281 ROS_INFO("Trajectory filter took %f seconds",(ros::Time::now() - start_time).toSec());
00282 for(unsigned int i=0; i < trajectory_out.trajectory.points.size(); i++)
00283 {
00284 trajectory_out.trajectory.points[i].accelerations.clear();
00285 trajectory_out.trajectory.points[i].velocities.clear();
00286 }
00287 printTrajectory(trajectory_out.trajectory);
00288
00289
00290
00291
00292
00293
00294
00295
00296 trajectory_out.limits = trajectory_in.limits;
00297 printTrajectory(trajectory_out.trajectory);
00298 planning_monitor_->revertToDefaultState();
00299
00300 ROS_DEBUG("Final trajectory has %d points and %f total time",(int)trajectory_out.trajectory.points.size(),
00301 trajectory_out.trajectory.points.back().time_from_start.toSec());
00302
00303
00304 return success;
00305 }
00306
00307 template <typename T>
00308 void LinearSplineShortCutter<T>::refineTrajectory(T &trajectory) const
00309 {
00310 if(trajectory.trajectory.points.size() < 3)
00311 return;
00312
00313 for(unsigned int i=1; i < trajectory.trajectory.points.size()-1; i++)
00314 {
00315 for(unsigned int j=0; j < trajectory.trajectory.points[i].positions.size(); j++)
00316 {
00317 double dq_first = trajectory.trajectory.points[i].positions[j] - trajectory.trajectory.points[i-1].positions[j];
00318 double dq_second = trajectory.trajectory.points[i+1].positions[j] - trajectory.trajectory.points[i].positions[j];
00319 double dq_dot = trajectory.trajectory.points[i].velocities[j];
00320 double dt_first = (trajectory.trajectory.points[i].time_from_start - trajectory.trajectory.points[i-1].time_from_start).toSec();
00321 double dt_second = (trajectory.trajectory.points[i+1].time_from_start - trajectory.trajectory.points[i].time_from_start).toSec();
00322 if( (dq_first > 0 && dq_second > 0) || (dq_first < 0 && dq_second < 0))
00323 {
00324 if(trajectory.trajectory.points[i].velocities[j] == 0.0)
00325 {
00326 trajectory.trajectory.points[i].velocities[j] = 0.5*(dq_first/dt_first + dq_second/dt_second);
00327 trajectory.trajectory.points[i].velocities[j] = std::max(std::min(trajectory.trajectory.points[i].velocities[j],
00328 trajectory.limits[j].max_velocity),
00329 -trajectory.limits[j].max_velocity);
00330 }
00331 }
00332 }
00333 }
00334 }
00335
00336 template <typename T>
00337 void LinearSplineShortCutter<T>::printTrajectory(const trajectory_msgs::JointTrajectory &trajectory) const
00338 {
00339 for(unsigned int i = 0; i < trajectory.points.size(); i++)
00340 {
00341 ROS_DEBUG("%f: %f %f %f %f %f %f %f %f %f %f %f %f %f %f",
00342 trajectory.points[i].time_from_start.toSec(),
00343 trajectory.points[i].positions[0],
00344 trajectory.points[i].positions[1],
00345 trajectory.points[i].positions[2],
00346 trajectory.points[i].positions[3],
00347 trajectory.points[i].positions[4],
00348 trajectory.points[i].positions[5],
00349 trajectory.points[i].positions[6],
00350 trajectory.points[i].velocities[0],
00351 trajectory.points[i].velocities[1],
00352 trajectory.points[i].velocities[2],
00353 trajectory.points[i].velocities[3],
00354 trajectory.points[i].velocities[4],
00355 trajectory.points[i].velocities[5],
00356 trajectory.points[i].velocities[6]);
00357 }
00358 ROS_DEBUG(" ");
00359 }
00360
00361
00362
00363
00364
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376
00377
00378
00379
00380 template <typename T>
00381 void LinearSplineShortCutter<T>::discretizeTrajectory(const spline_smoother::SplineTrajectory &spline,
00382 const double &discretization,
00383 trajectory_msgs::JointTrajectory &joint_trajectory) const
00384 {
00385 if(spline.segments.empty())
00386 return;
00387 joint_trajectory.points.clear();
00388 ros::Duration segment_start_time(0.0);
00389 for(unsigned int i=0; i < spline.segments.size(); i++)
00390 {
00391 if(i == spline.segments.size()-1)
00392 discretizeAndAppendSegment(spline.segments[i],discretization,joint_trajectory,segment_start_time,true);
00393 else
00394 discretizeAndAppendSegment(spline.segments[i],discretization,joint_trajectory,segment_start_time,false);
00395 segment_start_time += spline.segments[i].duration;
00396 ROS_DEBUG("Discretizing and appending segment %d",i);
00397 }
00398 }
00399
00400 template <typename T>
00401 void LinearSplineShortCutter<T>::discretizeAndAppendSegment(const spline_smoother::SplineTrajectorySegment &spline_segment,
00402 const double &discretization,
00403 trajectory_msgs::JointTrajectory &joint_trajectory,
00404 const ros::Duration &segment_start_time,
00405 const bool &include_segment_end) const
00406 {
00407 ros::Duration time_from_start = segment_start_time;
00408 double total_time = spline_segment.duration.toSec();
00409 double sample_time = 0.0;
00410 trajectory_msgs::JointTrajectoryPoint start,end;
00411 spline_smoother::sampleSplineTrajectory(spline_segment,0.0,start);
00412 if(joint_trajectory.points.empty())
00413 {
00414 start.time_from_start = ros::Duration(0.0);
00415 joint_trajectory.points.push_back(start);
00416 sample_time += 0.01;
00417 }
00418 start = joint_trajectory.points.back();
00419 while(sample_time < total_time)
00420 {
00421 ROS_DEBUG("Sample time is %f",sample_time);
00422 spline_smoother::sampleSplineTrajectory(spline_segment,sample_time,end);
00423 double max_diff = maxLInfDistance(start,end);
00424 if(sample_time > 0 && max_diff < discretization)
00425 {
00426 ROS_DEBUG("Max diff is %f. Skipping",max_diff);
00427 sample_time += 0.01;
00428 continue;
00429 }
00430 end.time_from_start = time_from_start + ros::Duration(sample_time);
00431 joint_trajectory.points.push_back(end);
00432 ROS_DEBUG("Pushing back point with time: %f",end.time_from_start.toSec());
00433 sample_time += 0.01;
00434 start = end;
00435 }
00436 if(include_segment_end)
00437 {
00438 spline_smoother::sampleSplineTrajectory(spline_segment,total_time,end);
00439 end.time_from_start = time_from_start + ros::Duration(total_time);
00440 joint_trajectory.points.push_back(end);
00441 }
00442 }
00443
00444 template <typename T>
00445 double LinearSplineShortCutter<T>::maxLInfDistance(const trajectory_msgs::JointTrajectoryPoint &start,
00446 const trajectory_msgs::JointTrajectoryPoint &end) const
00447 {
00448 double max_diff = 0.0;
00449 for(unsigned int i=0; i< start.positions.size(); i++)
00450 {
00451 double diff = fabs(end.positions[i]-start.positions[i]);
00452 if(diff > max_diff)
00453 max_diff = diff;
00454 }
00455 return max_diff;
00456 }
00457
00458
00459
00460 template <typename T>
00461 bool LinearSplineShortCutter<T>::trimTrajectory(trajectory_msgs::JointTrajectory &trajectory_out,
00462 const double &segment_start_time,
00463 const double &segment_end_time) const
00464 {
00465 int index1;
00466 int index2;
00467 if(findTrajectoryPointsInInterval(trajectory_out,segment_start_time,segment_end_time,index1,index2))
00468 {
00469 ROS_DEBUG("Trimming trajectory between segments: %d and %d",index1,index2);
00470 std::vector<trajectory_msgs::JointTrajectoryPoint>::iterator remove_start = trajectory_out.points.begin() + index1;
00471 std::vector<trajectory_msgs::JointTrajectoryPoint>::iterator remove_end;
00472 if((unsigned int) index2 >= trajectory_out.points.size())
00473 remove_end = trajectory_out.points.end();
00474 else
00475 remove_end = trajectory_out.points.begin()+index2;
00476
00477
00478 if(remove_start != remove_end)
00479 trajectory_out.points.erase(remove_start,remove_end);
00480 else
00481 trajectory_out.points.erase(remove_start);
00482 }
00483 else
00484 return false;
00485 return true;
00486 }
00487
00488 template <typename T>
00489 bool LinearSplineShortCutter<T>::findTrajectoryPointsInInterval(const trajectory_msgs::JointTrajectory &trajectory,
00490 const double &segment_start_time,
00491 const double &segment_end_time,
00492 int &index_1,
00493 int &index_2) const
00494 {
00495 index_1 = -1;
00496 index_2 = -1;
00497 if(segment_start_time > segment_end_time)
00498 return false;
00499 for(unsigned int i=0; i < trajectory.points.size(); i++)
00500 if(trajectory.points[i].time_from_start.toSec() >= segment_start_time)
00501 {
00502 index_1 = i;
00503 break;
00504 }
00505 ROS_DEBUG("First trim index: %d",index_1);
00506 if(index_1>=0)
00507 for(unsigned int i=index_1; i < trajectory.points.size(); i++)
00508 {
00509 if(trajectory.points[i].time_from_start.toSec() > segment_end_time)
00510 {
00511 index_2 = i;
00512 break;
00513 }
00514 if(trajectory.points[i].time_from_start.toSec() == segment_end_time)
00515 {
00516 index_2 = i+1;
00517 break;
00518 }
00519 }
00520 ROS_DEBUG("Second trim index: %d",index_2);
00521 if(index_1 >= index_2 || index_1 < 0 || index_2 < 0)
00522 return false;
00523 return true;
00524 }
00525
00526 template <typename T>
00527 bool LinearSplineShortCutter<T>::getWaypoints(const spline_smoother::SplineTrajectory &spline,
00528 trajectory_msgs::JointTrajectory &joint_trajectory) const
00529 {
00530 std::vector<double> waypoint_times_vector;
00531 double waypoint_time = 0.0;
00532 waypoint_times_vector.push_back(waypoint_time);
00533 for(unsigned int i=0; i < spline.segments.size(); i++)
00534 {
00535 waypoint_time = waypoint_time + spline.segments[i].duration.toSec();
00536 waypoint_times_vector.push_back(waypoint_time);
00537 ROS_DEBUG("Spline segment time: %f",spline.segments[i].duration.toSec());
00538 }
00539 if(!spline_smoother::sampleSplineTrajectory(spline,waypoint_times_vector,joint_trajectory))
00540 return false;
00541 return true;
00542 }
00543
00544 template <typename T>
00545 bool LinearSplineShortCutter<T>::addToTrajectory(trajectory_msgs::JointTrajectory &trajectory_out,
00546 const trajectory_msgs::JointTrajectoryPoint &trajectory_point,
00547 const ros::Duration &delta_time) const
00548 {
00549
00550 ROS_DEBUG("Inserting point at time: %f",trajectory_point.time_from_start.toSec());
00551 ROS_DEBUG("Old trajectory has %u points",trajectory_out.points.size());
00552
00553 if(trajectory_out.points.empty())
00554 {
00555 trajectory_out.points.push_back(trajectory_point);
00556 return true;
00557 }
00558
00559 unsigned int counter = 0;
00560 unsigned int old_size = trajectory_out.points.size();
00561 for(std::vector<trajectory_msgs::JointTrajectoryPoint>::iterator iter = trajectory_out.points.begin();
00562 iter != trajectory_out.points.end() ; iter++)
00563 {
00564 if(iter->time_from_start >= trajectory_point.time_from_start)
00565 {
00566 trajectory_out.points.insert(iter,trajectory_point);
00567 break;
00568 }
00569 counter++;
00570 }
00571
00572 if(delta_time == ros::Duration(0.0))
00573 return true;
00574
00575 if(counter == old_size)
00576 trajectory_out.points.push_back(trajectory_point);
00577 else
00578 if(counter+1 < trajectory_out.points.size())
00579 for(unsigned int i= counter+1; i < trajectory_out.points.size(); i++)
00580 {
00581 trajectory_out.points[i].time_from_start += delta_time;
00582 }
00583 return true;
00584 }
00585
00586 template <typename T>
00587 bool LinearSplineShortCutter<T>::setupCollisionEnvironment()
00588 {
00589 bool use_collision_map;
00590 node_handle_.param<bool>("use_collision_map", use_collision_map, true);
00591
00592
00593 collision_models_ = new planning_environment::CollisionModels("robot_description");
00594 planning_monitor_ = new planning_environment::PlanningMonitor(collision_models_, &tf_);
00595 planning_monitor_->setUseCollisionMap(use_collision_map);
00596 if(!collision_models_->loadedModels())
00597 return false;
00598 if (planning_monitor_->getExpectedJointStateUpdateInterval() > 1e-3)
00599 planning_monitor_->waitForState();
00600
00601 planning_monitor_->startEnvironmentMonitor();
00602
00603 if (planning_monitor_->getExpectedMapUpdateInterval() > 1e-3 && use_collision_map)
00604 planning_monitor_->waitForMap();
00605 return true;
00606 }
00607 }
00608
00609 #endif