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 #include "robot_mechanism_controllers/joint_trajectory_action_controller.h"
00035 #include <sstream>
00036 #include "angles/angles.h"
00037 #include "pluginlib/class_list_macros.h"
00038
00039 PLUGINLIB_EXPORT_CLASS( controller::JointTrajectoryActionController, pr2_controller_interface::Controller)
00040
00041 namespace controller {
00042
00043
00044
00045
00046
00047
00048 static inline void generatePowers(int n, double x, double* powers)
00049 {
00050 powers[0] = 1.0;
00051 for (int i=1; i<=n; i++)
00052 {
00053 powers[i] = powers[i-1]*x;
00054 }
00055 }
00056
00057 static void getQuinticSplineCoefficients(double start_pos, double start_vel, double start_acc,
00058 double end_pos, double end_vel, double end_acc, double time, std::vector<double>& coefficients)
00059 {
00060 coefficients.resize(6);
00061
00062 if (time == 0.0)
00063 {
00064 coefficients[0] = end_pos;
00065 coefficients[1] = end_vel;
00066 coefficients[2] = 0.5*end_acc;
00067 coefficients[3] = 0.0;
00068 coefficients[4] = 0.0;
00069 coefficients[5] = 0.0;
00070 }
00071 else
00072 {
00073 double T[6];
00074 generatePowers(5, time, T);
00075
00076 coefficients[0] = start_pos;
00077 coefficients[1] = start_vel;
00078 coefficients[2] = 0.5*start_acc;
00079 coefficients[3] = (-20.0*start_pos + 20.0*end_pos - 3.0*start_acc*T[2] + end_acc*T[2] -
00080 12.0*start_vel*T[1] - 8.0*end_vel*T[1]) / (2.0*T[3]);
00081 coefficients[4] = (30.0*start_pos - 30.0*end_pos + 3.0*start_acc*T[2] - 2.0*end_acc*T[2] +
00082 16.0*start_vel*T[1] + 14.0*end_vel*T[1]) / (2.0*T[4]);
00083 coefficients[5] = (-12.0*start_pos + 12.0*end_pos - start_acc*T[2] + end_acc*T[2] -
00084 6.0*start_vel*T[1] - 6.0*end_vel*T[1]) / (2.0*T[5]);
00085 }
00086 }
00087
00091 static void sampleQuinticSpline(const std::vector<double>& coefficients, double time,
00092 double& position, double& velocity, double& acceleration)
00093 {
00094
00095 double t[6];
00096 generatePowers(5, time, t);
00097
00098 position = t[0]*coefficients[0] +
00099 t[1]*coefficients[1] +
00100 t[2]*coefficients[2] +
00101 t[3]*coefficients[3] +
00102 t[4]*coefficients[4] +
00103 t[5]*coefficients[5];
00104
00105 velocity = t[0]*coefficients[1] +
00106 2.0*t[1]*coefficients[2] +
00107 3.0*t[2]*coefficients[3] +
00108 4.0*t[3]*coefficients[4] +
00109 5.0*t[4]*coefficients[5];
00110
00111 acceleration = 2.0*t[0]*coefficients[2] +
00112 6.0*t[1]*coefficients[3] +
00113 12.0*t[2]*coefficients[4] +
00114 20.0*t[3]*coefficients[5];
00115 }
00116
00117 static void getCubicSplineCoefficients(double start_pos, double start_vel,
00118 double end_pos, double end_vel, double time, std::vector<double>& coefficients)
00119 {
00120 coefficients.resize(4);
00121
00122 if (time == 0.0)
00123 {
00124 coefficients[0] = end_pos;
00125 coefficients[1] = end_vel;
00126 coefficients[2] = 0.0;
00127 coefficients[3] = 0.0;
00128 }
00129 else
00130 {
00131 double T[4];
00132 generatePowers(3, time, T);
00133
00134 coefficients[0] = start_pos;
00135 coefficients[1] = start_vel;
00136 coefficients[2] = (-3.0*start_pos + 3.0*end_pos - 2.0*start_vel*T[1] - end_vel*T[1]) / T[2];
00137 coefficients[3] = (2.0*start_pos - 2.0*end_pos + start_vel*T[1] + end_vel*T[1]) / T[3];
00138 }
00139 }
00140
00141
00142 JointTrajectoryActionController::JointTrajectoryActionController()
00143 : loop_count_(0), robot_(NULL)
00144 {
00145 }
00146
00147 JointTrajectoryActionController::~JointTrajectoryActionController()
00148 {
00149 sub_command_.shutdown();
00150 serve_query_state_.shutdown();
00151 action_server_.reset();
00152 action_server_follow_.reset();
00153 }
00154
00155 bool JointTrajectoryActionController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00156 {
00157 using namespace XmlRpc;
00158 node_ = n;
00159 robot_ = robot;
00160
00161
00162 XmlRpc::XmlRpcValue joint_names;
00163 if (!node_.getParam("joints", joint_names))
00164 {
00165 ROS_ERROR("No joints given. (namespace: %s)", node_.getNamespace().c_str());
00166 return false;
00167 }
00168 if (joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray)
00169 {
00170 ROS_ERROR("Malformed joint specification. (namespace: %s)", node_.getNamespace().c_str());
00171 return false;
00172 }
00173 for (int i = 0; i < joint_names.size(); ++i)
00174 {
00175 XmlRpcValue &name_value = joint_names[i];
00176 if (name_value.getType() != XmlRpcValue::TypeString)
00177 {
00178 ROS_ERROR("Array of joint names should contain all strings. (namespace: %s)",
00179 node_.getNamespace().c_str());
00180 return false;
00181 }
00182
00183 pr2_mechanism_model::JointState *j = robot->getJointState((std::string)name_value);
00184 if (!j) {
00185 ROS_ERROR("Joint not found: %s. (namespace: %s)",
00186 ((std::string)name_value).c_str(), node_.getNamespace().c_str());
00187 return false;
00188 }
00189 joints_.push_back(j);
00190 }
00191
00192
00193 for (size_t i = 0; i < joints_.size(); ++i)
00194 {
00195 if (!joints_[i]->calibrated_)
00196 {
00197 ROS_ERROR("Joint %s was not calibrated (namespace: %s)",
00198 joints_[i]->joint_->name.c_str(), node_.getNamespace().c_str());
00199 return false;
00200 }
00201 }
00202
00203
00204 std::string gains_ns;
00205 if (!node_.getParam("gains", gains_ns))
00206 gains_ns = node_.getNamespace() + "/gains";
00207 masses_.resize(joints_.size());
00208 pids_.resize(joints_.size());
00209 for (size_t i = 0; i < joints_.size(); ++i)
00210 {
00211 ros::NodeHandle joint_nh(gains_ns + "/" + joints_[i]->joint_->name);
00212 joint_nh.param("mass", masses_[i], 0.0);
00213 if (!pids_[i].init(joint_nh))
00214 return false;
00215 }
00216
00217
00218 proxies_enabled_.resize(joints_.size());
00219 proxies_.resize(joints_.size());
00220 for (size_t i = 0; i < joints_.size(); ++i)
00221 {
00222 ros::NodeHandle joint_nh(gains_ns + "/" + joints_[i]->joint_->name);
00223 if (joint_nh.hasParam("proxy")) {
00224 proxies_enabled_[i] = true;
00225 joint_nh.param("proxy/lambda", proxies_[i].lambda_proxy_, 1.0);
00226 joint_nh.param("proxy/acc_converge", proxies_[i].acc_converge_, 0.0);
00227 joint_nh.param("proxy/vel_limit", proxies_[i].vel_limit_, 0.0);
00228 joint_nh.param("proxy/effort_limit", proxies_[i].effort_limit_, 0.0);
00229 proxies_[i].mass_ = masses_[i];
00230 double _;
00231 pids_[i].getGains(proxies_[i].Kp_, proxies_[i].Ki_, proxies_[i].Kd_, proxies_[i].Ficl_, _);
00232 }
00233 else {
00234 proxies_enabled_[i] = false;
00235 }
00236 }
00237
00238
00239 default_trajectory_tolerance_.resize(joints_.size());
00240 default_goal_tolerance_.resize(joints_.size());
00241 node_.param("joint_trajectory_action_node/constraints/goal_time", default_goal_time_constraint_, 0.0);
00242 double stopped_velocity_tolerance;
00243 node_.param("joint_trajectory_action_node/constraints/stopped_velocity_tolerance", stopped_velocity_tolerance, 0.01);
00244 for (size_t i = 0; i < default_goal_tolerance_.size(); ++i)
00245 default_goal_tolerance_[i].velocity = stopped_velocity_tolerance;
00246 for (size_t i = 0; i < joints_.size(); ++i)
00247 {
00248 std::string ns = std::string("joint_trajectory_action_node/constraints") + joints_[i]->joint_->name;
00249 node_.param(ns + "/goal", default_goal_tolerance_[i].position, 0.0);
00250 node_.param(ns + "/trajectory", default_trajectory_tolerance_[i].position, 0.0);
00251 }
00252
00253
00254 output_filters_.resize(joints_.size());
00255 for (size_t i = 0; i < joints_.size(); ++i)
00256 {
00257 std::string p = "output_filters/" + joints_[i]->joint_->name;
00258 if (node_.hasParam(p))
00259 {
00260 output_filters_[i].reset(new filters::FilterChain<double>("double"));
00261 if (!output_filters_[i]->configure(node_.resolveName(p)))
00262 output_filters_[i].reset();
00263 }
00264 }
00265
00266
00267 boost::shared_ptr<SpecifiedTrajectory> traj_ptr(new SpecifiedTrajectory(1));
00268 SpecifiedTrajectory &traj = *traj_ptr;
00269 traj[0].start_time = robot_->getTime().toSec();
00270 traj[0].duration = 0.0;
00271 traj[0].splines.resize(joints_.size());
00272 for (size_t j = 0; j < joints_.size(); ++j)
00273 traj[0].splines[j].coef[0] = 0.0;
00274 current_trajectory_box_.set(traj_ptr);
00275
00276 sub_command_ = node_.subscribe("command", 1, &JointTrajectoryActionController::commandCB, this);
00277 serve_query_state_ = node_.advertiseService(
00278 "query_state", &JointTrajectoryActionController::queryStateService, this);
00279
00280 q.resize(joints_.size());
00281 qd.resize(joints_.size());
00282 qdd.resize(joints_.size());
00283
00284 controller_state_publisher_.reset(
00285 new realtime_tools::RealtimePublisher<pr2_controllers_msgs::JointTrajectoryControllerState>
00286 (node_, "state", 1));
00287 controller_state_publisher_->lock();
00288 for (size_t j = 0; j < joints_.size(); ++j)
00289 controller_state_publisher_->msg_.joint_names.push_back(joints_[j]->joint_->name);
00290 controller_state_publisher_->msg_.desired.positions.resize(joints_.size());
00291 controller_state_publisher_->msg_.desired.velocities.resize(joints_.size());
00292 controller_state_publisher_->msg_.desired.accelerations.resize(joints_.size());
00293 controller_state_publisher_->msg_.actual.positions.resize(joints_.size());
00294 controller_state_publisher_->msg_.actual.velocities.resize(joints_.size());
00295 controller_state_publisher_->msg_.error.positions.resize(joints_.size());
00296 controller_state_publisher_->msg_.error.velocities.resize(joints_.size());
00297 controller_state_publisher_->unlock();
00298
00299 action_server_.reset(new JTAS(node_, "joint_trajectory_action",
00300 boost::bind(&JointTrajectoryActionController::goalCB, this, _1),
00301 boost::bind(&JointTrajectoryActionController::cancelCB, this, _1),
00302 false));
00303 action_server_follow_.reset(new FJTAS(node_, "follow_joint_trajectory",
00304 boost::bind(&JointTrajectoryActionController::goalCBFollow, this, _1),
00305 boost::bind(&JointTrajectoryActionController::cancelCBFollow, this, _1),
00306 false));
00307 action_server_->start();
00308 action_server_follow_->start();
00309
00310 return true;
00311 }
00312
00313 void JointTrajectoryActionController::starting()
00314 {
00315 last_time_ = robot_->getTime();
00316
00317 for (size_t i = 0; i < pids_.size(); ++i) {
00318 pids_[i].reset();
00319 proxies_[i].reset(joints_[i]->position_, joints_[i]->velocity_);
00320 }
00321
00322
00323 boost::shared_ptr<SpecifiedTrajectory> hold_ptr(new SpecifiedTrajectory(1));
00324 SpecifiedTrajectory &hold = *hold_ptr;
00325 hold[0].start_time = last_time_.toSec() - 0.001;
00326 hold[0].duration = 0.0;
00327 hold[0].splines.resize(joints_.size());
00328 for (size_t j = 0; j < joints_.size(); ++j)
00329 hold[0].splines[j].coef[0] = joints_[j]->position_;
00330
00331 current_trajectory_box_.set(hold_ptr);
00332 }
00333
00334 void JointTrajectoryActionController::update()
00335 {
00336 ros::Time time = robot_->getTime();
00337 ros::Duration dt = time - last_time_;
00338 last_time_ = time;
00339
00340 boost::shared_ptr<RTGoalHandle> current_active_goal(rt_active_goal_);
00341 boost::shared_ptr<RTGoalHandleFollow> current_active_goal_follow(rt_active_goal_follow_);
00342
00343 boost::shared_ptr<const SpecifiedTrajectory> traj_ptr;
00344 current_trajectory_box_.get(traj_ptr);
00345 if (!traj_ptr)
00346 ROS_FATAL("The current trajectory can never be null");
00347
00348
00349 const SpecifiedTrajectory &traj = *traj_ptr;
00350
00351
00352
00353
00354 int seg = -1;
00355 while (seg + 1 < (int)traj.size() &&
00356 traj[seg+1].start_time < time.toSec())
00357 {
00358 ++seg;
00359 }
00360
00361 if (seg == -1)
00362 {
00363 if (traj.size() == 0)
00364 ROS_ERROR("No segments in the trajectory");
00365 else
00366 ROS_ERROR("No earlier segments. First segment starts at %.3lf (now = %.3lf)", traj[0].start_time, time.toSec());
00367 return;
00368 }
00369
00370
00371
00372 for (size_t i = 0; i < q.size(); ++i)
00373 {
00374 sampleSplineWithTimeBounds(traj[seg].splines[i].coef, traj[seg].duration,
00375 time.toSec() - traj[seg].start_time,
00376 q[i], qd[i], qdd[i]);
00377 }
00378
00379
00380
00381 std::vector<double> error(joints_.size());
00382 std::vector<double> v_error(joints_.size());
00383 for (size_t i = 0; i < joints_.size(); ++i)
00384 {
00385 double effort;
00386
00387
00388
00389
00390 error[i] = joints_[i]->position_ - q[i];
00391 v_error[i] = joints_[i]->velocity_ - qd[i];
00392
00393
00394 if (proxies_enabled_[i]) {
00395 effort = proxies_[i].update(q[i], qd[i], qdd[i],
00396 joints_[i]->position_, joints_[i]->velocity_,
00397 dt.toSec());
00398 }
00399 else {
00400 effort = pids_[i].updatePid(error[i], v_error[i], dt);
00401
00402 double effort_unfiltered = effort;
00403 if (output_filters_[i])
00404 output_filters_[i]->update(effort_unfiltered, effort);
00405 }
00406
00407
00408 joints_[i]->commanded_effort_ = effort;
00409 }
00410
00411
00412
00413 if ((traj[seg].gh && traj[seg].gh == current_active_goal) ||
00414 (traj[seg].gh_follow && traj[seg].gh_follow == current_active_goal_follow))
00415 {
00416 ros::Time end_time(traj[seg].start_time + traj[seg].duration);
00417 if (time <= end_time)
00418 {
00419
00420 for (size_t j = 0; j < joints_.size(); ++j)
00421 {
00422 if (traj[seg].trajectory_tolerance[j].violated(error[j], v_error[j]))
00423 {
00424 if (traj[seg].gh)
00425 traj[seg].gh->setAborted();
00426 else if (traj[seg].gh_follow) {
00427 traj[seg].gh_follow->preallocated_result_->error_code =
00428 control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
00429 traj[seg].gh_follow->setAborted(traj[seg].gh_follow->preallocated_result_);
00430 }
00431 break;
00432 }
00433 }
00434 }
00435 else if (seg == (int)traj.size() - 1)
00436 {
00437
00438 bool inside_goal_constraints = true;
00439 for (size_t i = 0; i < joints_.size() && inside_goal_constraints; ++i)
00440 {
00441 if (traj[seg].goal_tolerance[i].violated(error[i], v_error[i]))
00442 inside_goal_constraints = false;
00443 }
00444
00445 if (inside_goal_constraints)
00446 {
00447 rt_active_goal_.reset();
00448 rt_active_goal_follow_.reset();
00449 if (traj[seg].gh)
00450 traj[seg].gh->setSucceeded();
00451 else if (traj[seg].gh_follow) {
00452 traj[seg].gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::SUCCESSFUL;
00453 traj[seg].gh_follow->setSucceeded(traj[seg].gh_follow->preallocated_result_);
00454 }
00455
00456 }
00457 else if (time < end_time + ros::Duration(traj[seg].goal_time_tolerance))
00458 {
00459
00460 }
00461 else
00462 {
00463
00464 rt_active_goal_.reset();
00465 rt_active_goal_follow_.reset();
00466 if (traj[seg].gh)
00467 traj[seg].gh->setAborted();
00468 else if (traj[seg].gh_follow) {
00469 traj[seg].gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED;
00470 traj[seg].gh_follow->setAborted(traj[seg].gh_follow->preallocated_result_);
00471 }
00472 }
00473 }
00474 }
00475
00476
00477
00478 if (loop_count_ % 10 == 0)
00479 {
00480 if (controller_state_publisher_ && controller_state_publisher_->trylock())
00481 {
00482 controller_state_publisher_->msg_.header.stamp = time;
00483 for (size_t j = 0; j < joints_.size(); ++j)
00484 {
00485 controller_state_publisher_->msg_.desired.positions[j] = q[j];
00486 controller_state_publisher_->msg_.desired.velocities[j] = qd[j];
00487 controller_state_publisher_->msg_.desired.accelerations[j] = qdd[j];
00488 controller_state_publisher_->msg_.actual.positions[j] = joints_[j]->position_;
00489 controller_state_publisher_->msg_.actual.velocities[j] = joints_[j]->velocity_;
00490 controller_state_publisher_->msg_.error.positions[j] = error[j];
00491 controller_state_publisher_->msg_.error.velocities[j] = joints_[j]->velocity_ - qd[j];
00492 }
00493 controller_state_publisher_->unlockAndPublish();
00494 }
00495 }
00496
00497 ++loop_count_;
00498 }
00499
00500 void JointTrajectoryActionController::commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
00501 {
00502 preemptActiveGoal();
00503 commandTrajectory(msg);
00504 }
00505
00506 void JointTrajectoryActionController::commandTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &msg,
00507 boost::shared_ptr<RTGoalHandle> gh,
00508 boost::shared_ptr<RTGoalHandleFollow> gh_follow)
00509 {
00510 assert(!gh || !gh_follow);
00511 ros::Time time = last_time_ + ros::Duration(0.01);
00512 ROS_DEBUG("Figuring out new trajectory at %.3lf, with data from %.3lf",
00513 time.toSec(), msg->header.stamp.toSec());
00514
00515 boost::shared_ptr<SpecifiedTrajectory> new_traj_ptr(new SpecifiedTrajectory);
00516 SpecifiedTrajectory &new_traj = *new_traj_ptr;
00517
00518
00519
00520 if (msg->points.empty())
00521 {
00522 starting();
00523 return;
00524 }
00525
00526
00527
00528 std::vector<JointTolerance> trajectory_tolerance = default_trajectory_tolerance_;
00529 std::vector<JointTolerance> goal_tolerance = default_goal_tolerance_;
00530 double goal_time_tolerance = default_goal_time_constraint_;
00531
00532 if (gh_follow)
00533 {
00534 for (size_t j = 0; j < joints_.size(); ++j)
00535 {
00536
00537 for (size_t k = 0; k < gh_follow->gh_.getGoal()->path_tolerance.size(); ++k)
00538 {
00539 const control_msgs::JointTolerance &tol = gh_follow->gh_.getGoal()->path_tolerance[k];
00540 if (joints_[j]->joint_->name == tol.name)
00541 {
00542
00543
00544
00545
00546
00547 if (tol.position > 0)
00548 trajectory_tolerance[j].position = tol.position;
00549 else if (tol.position < 0)
00550 trajectory_tolerance[j].position = 0.0;
00551
00552 if (tol.velocity > 0)
00553 trajectory_tolerance[j].velocity = tol.velocity;
00554 else if (tol.velocity < 0)
00555 trajectory_tolerance[j].velocity = 0.0;
00556
00557 if (tol.acceleration > 0)
00558 trajectory_tolerance[j].acceleration = tol.acceleration;
00559 else if (tol.acceleration < 0)
00560 trajectory_tolerance[j].acceleration = 0.0;
00561
00562 break;
00563 }
00564 }
00565
00566
00567 for (size_t k = 0; k < gh_follow->gh_.getGoal()->goal_tolerance.size(); ++k)
00568 {
00569 const control_msgs::JointTolerance &tol = gh_follow->gh_.getGoal()->goal_tolerance[k];
00570 if (joints_[j]->joint_->name == tol.name)
00571 {
00572
00573
00574
00575
00576
00577 if (tol.position > 0)
00578 goal_tolerance[j].position = tol.position;
00579 else if (tol.position < 0)
00580 goal_tolerance[j].position = 0.0;
00581
00582 if (tol.velocity > 0)
00583 goal_tolerance[j].velocity = tol.velocity;
00584 else if (tol.velocity < 0)
00585 goal_tolerance[j].velocity = 0.0;
00586
00587 if (tol.acceleration > 0)
00588 goal_tolerance[j].acceleration = tol.acceleration;
00589 else if (tol.acceleration < 0)
00590 goal_tolerance[j].acceleration = 0.0;
00591
00592 break;
00593 }
00594 }
00595 }
00596
00597 const ros::Duration &tol = gh_follow->gh_.getGoal()->goal_time_tolerance;
00598 if (tol < ros::Duration(0.0))
00599 goal_time_tolerance = 0.0;
00600 else if (tol > ros::Duration(0.0))
00601 goal_time_tolerance = tol.toSec();
00602 }
00603
00604
00605
00606 std::vector<int> lookup(joints_.size(), -1);
00607 for (size_t j = 0; j < joints_.size(); ++j)
00608 {
00609 for (size_t k = 0; k < msg->joint_names.size(); ++k)
00610 {
00611 if (msg->joint_names[k] == joints_[j]->joint_->name)
00612 {
00613 lookup[j] = k;
00614 break;
00615 }
00616 }
00617
00618 if (lookup[j] == -1)
00619 {
00620 ROS_ERROR("Unable to locate joint %s in the commanded trajectory.", joints_[j]->joint_->name.c_str());
00621 if (gh)
00622 gh->setAborted();
00623 else if (gh_follow) {
00624 gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00625 gh_follow->setAborted(gh_follow->preallocated_result_);
00626 }
00627 return;
00628 }
00629 }
00630
00631
00632
00633 boost::shared_ptr<const SpecifiedTrajectory> prev_traj_ptr;
00634 current_trajectory_box_.get(prev_traj_ptr);
00635 if (!prev_traj_ptr)
00636 {
00637 ROS_FATAL("The current trajectory can never be null");
00638 return;
00639 }
00640 const SpecifiedTrajectory &prev_traj = *prev_traj_ptr;
00641
00642
00643
00644
00645 int first_useful = -1;
00646 while (first_useful + 1 < (int)prev_traj.size() &&
00647 prev_traj[first_useful + 1].start_time <= time.toSec())
00648 {
00649 ++first_useful;
00650 }
00651
00652
00653 int last_useful = -1;
00654 double msg_start_time;
00655 if (msg->header.stamp == ros::Time(0.0))
00656 msg_start_time = time.toSec();
00657 else
00658 msg_start_time = msg->header.stamp.toSec();
00659
00660
00661
00662
00663
00664 while (last_useful + 1 < (int)prev_traj.size() &&
00665 prev_traj[last_useful + 1].start_time < msg_start_time)
00666 {
00667 ++last_useful;
00668 }
00669
00670 if (last_useful < first_useful)
00671 first_useful = last_useful;
00672
00673
00674 for (int i = std::max(first_useful,0); i <= last_useful; ++i)
00675 {
00676 new_traj.push_back(prev_traj[i]);
00677 }
00678
00679
00680
00681 if (new_traj.size() == 0)
00682 new_traj.push_back(prev_traj[prev_traj.size() - 1]);
00683
00684
00685
00686
00687 Segment &last = new_traj[new_traj.size() - 1];
00688 std::vector<double> prev_positions(joints_.size());
00689 std::vector<double> prev_velocities(joints_.size());
00690 std::vector<double> prev_accelerations(joints_.size());
00691
00692 double t = (msg->header.stamp == ros::Time(0.0) ? time.toSec() : msg->header.stamp.toSec())
00693 - last.start_time;
00694 ROS_DEBUG("Initial conditions at %.3f for new set of splines:", t);
00695 for (size_t i = 0; i < joints_.size(); ++i)
00696 {
00697 sampleSplineWithTimeBounds(last.splines[i].coef, last.duration,
00698 t,
00699 prev_positions[i], prev_velocities[i], prev_accelerations[i]);
00700 ROS_DEBUG(" %.2lf, %.2lf, %.2lf (%s)", prev_positions[i], prev_velocities[i],
00701 prev_accelerations[i], joints_[i]->joint_->name.c_str());
00702 }
00703
00704
00705
00706 std::vector<double> positions;
00707 std::vector<double> velocities;
00708 std::vector<double> accelerations;
00709
00710 std::vector<double> durations(msg->points.size());
00711 if (msg->points.size() > 0)
00712 durations[0] = msg->points[0].time_from_start.toSec();
00713 for (size_t i = 1; i < msg->points.size(); ++i)
00714 durations[i] = (msg->points[i].time_from_start - msg->points[i-1].time_from_start).toSec();
00715
00716
00717 std::vector<double> wrap(joints_.size(), 0.0);
00718 assert(!msg->points[0].positions.empty());
00719 for (size_t j = 0; j < joints_.size(); ++j)
00720 {
00721 if (joints_[j]->joint_->type == urdf::Joint::CONTINUOUS)
00722 {
00723 double dist = angles::shortest_angular_distance(prev_positions[j], msg->points[0].positions[lookup[j]]);
00724 wrap[j] = (prev_positions[j] + dist) - msg->points[0].positions[lookup[j]];
00725 }
00726 }
00727
00728 for (size_t i = 0; i < msg->points.size(); ++i)
00729 {
00730 Segment seg;
00731
00732 if (msg->header.stamp == ros::Time(0.0))
00733 seg.start_time = (time + msg->points[i].time_from_start).toSec() - durations[i];
00734 else
00735 seg.start_time = (msg->header.stamp + msg->points[i].time_from_start).toSec() - durations[i];
00736 seg.duration = durations[i];
00737 seg.gh = gh;
00738 seg.gh_follow = gh_follow;
00739 seg.splines.resize(joints_.size());
00740
00741
00742
00743 if (msg->points[i].accelerations.size() != 0 && msg->points[i].accelerations.size() != joints_.size())
00744 {
00745 ROS_ERROR("Command point %d has %d elements for the accelerations", (int)i, (int)msg->points[i].accelerations.size());
00746 return;
00747 }
00748 if (msg->points[i].velocities.size() != 0 && msg->points[i].velocities.size() != joints_.size())
00749 {
00750 ROS_ERROR("Command point %d has %d elements for the velocities", (int)i, (int)msg->points[i].velocities.size());
00751 return;
00752 }
00753 if (msg->points[i].positions.size() != joints_.size())
00754 {
00755 ROS_ERROR("Command point %d has %d elements for the positions", (int)i, (int)msg->points[i].positions.size());
00756 return;
00757 }
00758
00759
00760
00761 accelerations.resize(msg->points[i].accelerations.size());
00762 velocities.resize(msg->points[i].velocities.size());
00763 positions.resize(msg->points[i].positions.size());
00764 for (size_t j = 0; j < joints_.size(); ++j)
00765 {
00766 if (!accelerations.empty()) accelerations[j] = msg->points[i].accelerations[lookup[j]];
00767 if (!velocities.empty()) velocities[j] = msg->points[i].velocities[lookup[j]];
00768 if (!positions.empty()) positions[j] = msg->points[i].positions[lookup[j]] + wrap[j];
00769 }
00770
00771
00772
00773 for (size_t j = 0; j < joints_.size(); ++j)
00774 {
00775 if (prev_accelerations.size() > 0 && accelerations.size() > 0)
00776 {
00777 getQuinticSplineCoefficients(
00778 prev_positions[j], prev_velocities[j], prev_accelerations[j],
00779 positions[j], velocities[j], accelerations[j],
00780 durations[i],
00781 seg.splines[j].coef);
00782 }
00783 else if (prev_velocities.size() > 0 && velocities.size() > 0)
00784 {
00785 getCubicSplineCoefficients(
00786 prev_positions[j], prev_velocities[j],
00787 positions[j], velocities[j],
00788 durations[i],
00789 seg.splines[j].coef);
00790 seg.splines[j].coef.resize(6, 0.0);
00791 }
00792 else
00793 {
00794 seg.splines[j].coef[0] = prev_positions[j];
00795 if (durations[i] == 0.0)
00796 seg.splines[j].coef[1] = 0.0;
00797 else
00798 seg.splines[j].coef[1] = (positions[j] - prev_positions[j]) / durations[i];
00799 seg.splines[j].coef[2] = 0.0;
00800 seg.splines[j].coef[3] = 0.0;
00801 seg.splines[j].coef[4] = 0.0;
00802 seg.splines[j].coef[5] = 0.0;
00803 }
00804 }
00805
00806
00807 seg.trajectory_tolerance = trajectory_tolerance;
00808 seg.goal_tolerance = goal_tolerance;
00809 seg.goal_time_tolerance = goal_time_tolerance;
00810
00811
00812
00813 new_traj.push_back(seg);
00814
00815
00816
00817 prev_positions = positions;
00818 prev_velocities = velocities;
00819 prev_accelerations = accelerations;
00820 }
00821
00822
00823
00824
00825
00826 if (!new_traj_ptr)
00827 {
00828 ROS_ERROR("The new trajectory was null!");
00829 return;
00830 }
00831
00832 current_trajectory_box_.set(new_traj_ptr);
00833 ROS_DEBUG("The new trajectory has %d segments", (int)new_traj.size());
00834 #if 0
00835 for (size_t i = 0; i < std::min((size_t)20,new_traj.size()); ++i)
00836 {
00837 ROS_DEBUG("Segment %2d: %.3lf for %.3lf", i, new_traj[i].start_time, new_traj[i].duration);
00838 for (size_t j = 0; j < new_traj[i].splines.size(); ++j)
00839 {
00840 ROS_DEBUG(" %.2lf %.2lf %.2lf %.2lf , %.2lf %.2lf(%s)",
00841 new_traj[i].splines[j].coef[0],
00842 new_traj[i].splines[j].coef[1],
00843 new_traj[i].splines[j].coef[2],
00844 new_traj[i].splines[j].coef[3],
00845 new_traj[i].splines[j].coef[4],
00846 new_traj[i].splines[j].coef[5],
00847 joints_[j]->joint_->name_.c_str());
00848 }
00849 }
00850 #endif
00851 }
00852
00853 bool JointTrajectoryActionController::queryStateService(
00854 pr2_controllers_msgs::QueryTrajectoryState::Request &req,
00855 pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
00856 {
00857 boost::shared_ptr<const SpecifiedTrajectory> traj_ptr;
00858 current_trajectory_box_.get(traj_ptr);
00859 if (!traj_ptr)
00860 {
00861 ROS_FATAL("The current trajectory can never be null");
00862 return false;
00863 }
00864 const SpecifiedTrajectory &traj = *traj_ptr;
00865
00866
00867 int seg = -1;
00868 while (seg + 1 < (int)traj.size() &&
00869 traj[seg+1].start_time < req.time.toSec())
00870 {
00871 ++seg;
00872 }
00873 if (seg == -1)
00874 return false;
00875
00876 for (size_t i = 0; i < q.size(); ++i)
00877 {
00878 }
00879
00880
00881 resp.name.resize(joints_.size());
00882 resp.position.resize(joints_.size());
00883 resp.velocity.resize(joints_.size());
00884 resp.acceleration.resize(joints_.size());
00885 for (size_t j = 0; j < joints_.size(); ++j)
00886 {
00887 resp.name[j] = joints_[j]->joint_->name;
00888 sampleSplineWithTimeBounds(traj[seg].splines[j].coef, traj[seg].duration,
00889 req.time.toSec() - traj[seg].start_time,
00890 resp.position[j], resp.velocity[j], resp.acceleration[j]);
00891 }
00892
00893 return true;
00894 }
00895
00896 void JointTrajectoryActionController::sampleSplineWithTimeBounds(
00897 const std::vector<double>& coefficients, double duration, double time,
00898 double& position, double& velocity, double& acceleration)
00899 {
00900 if (time < 0)
00901 {
00902 double _;
00903 sampleQuinticSpline(coefficients, 0.0, position, _, _);
00904 velocity = 0;
00905 acceleration = 0;
00906 }
00907 else if (time > duration)
00908 {
00909 double _;
00910 sampleQuinticSpline(coefficients, duration, position, _, _);
00911 velocity = 0;
00912 acceleration = 0;
00913 }
00914 else
00915 {
00916 sampleQuinticSpline(coefficients, time,
00917 position, velocity, acceleration);
00918 }
00919 }
00920
00921 static bool setsEqual(const std::vector<std::string> &a, const std::vector<std::string> &b)
00922 {
00923 if (a.size() != b.size())
00924 return false;
00925
00926 for (size_t i = 0; i < a.size(); ++i)
00927 {
00928 if (count(b.begin(), b.end(), a[i]) != 1)
00929 return false;
00930 }
00931 for (size_t i = 0; i < b.size(); ++i)
00932 {
00933 if (count(a.begin(), a.end(), b[i]) != 1)
00934 return false;
00935 }
00936
00937 return true;
00938 }
00939
00940 void JointTrajectoryActionController::preemptActiveGoal()
00941 {
00942 boost::shared_ptr<RTGoalHandle> current_active_goal(rt_active_goal_);
00943 boost::shared_ptr<RTGoalHandleFollow> current_active_goal_follow(rt_active_goal_follow_);
00944
00945
00946 if (current_active_goal)
00947 {
00948
00949 rt_active_goal_.reset();
00950 current_active_goal->gh_.setCanceled();
00951 }
00952 if (current_active_goal_follow)
00953 {
00954 rt_active_goal_follow_.reset();
00955 current_active_goal_follow->gh_.setCanceled();
00956 }
00957 }
00958
00959
00960 template <class Enclosure, class Member>
00961 static boost::shared_ptr<Member> share_member(boost::shared_ptr<Enclosure> enclosure, Member &member)
00962 {
00963 actionlib::EnclosureDeleter<Enclosure> d(enclosure);
00964 boost::shared_ptr<Member> p(&member, d);
00965 return p;
00966 }
00967
00968 void JointTrajectoryActionController::goalCB(GoalHandle gh)
00969 {
00970 std::vector<std::string> joint_names(joints_.size());
00971 for (size_t j = 0; j < joints_.size(); ++j)
00972 joint_names[j] = joints_[j]->joint_->name;
00973
00974
00975 if (!setsEqual(joint_names, gh.getGoal()->trajectory.joint_names))
00976 {
00977 ROS_ERROR("Joints on incoming goal don't match our joints");
00978 gh.setRejected();
00979 return;
00980 }
00981
00982 preemptActiveGoal();
00983
00984 gh.setAccepted();
00985 boost::shared_ptr<RTGoalHandle> rt_gh(new RTGoalHandle(gh));
00986
00987
00988 goal_handle_timer_ = node_.createTimer(ros::Duration(0.01), &RTGoalHandle::runNonRT, rt_gh);
00989 commandTrajectory(share_member(gh.getGoal(), gh.getGoal()->trajectory), rt_gh);
00990 rt_active_goal_ = rt_gh;
00991 goal_handle_timer_.start();
00992 }
00993
00994 void JointTrajectoryActionController::goalCBFollow(GoalHandleFollow gh)
00995 {
00996 std::vector<std::string> joint_names(joints_.size());
00997 for (size_t j = 0; j < joints_.size(); ++j)
00998 joint_names[j] = joints_[j]->joint_->name;
00999
01000
01001 if (!setsEqual(joint_names, gh.getGoal()->trajectory.joint_names))
01002 {
01003 ROS_ERROR("Joints on incoming goal don't match our joints");
01004 control_msgs::FollowJointTrajectoryResult result;
01005 result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
01006 gh.setRejected(result);
01007 return;
01008 }
01009
01010 preemptActiveGoal();
01011
01012 gh.setAccepted();
01013 boost::shared_ptr<RTGoalHandleFollow> rt_gh(new RTGoalHandleFollow(gh));
01014
01015
01016 goal_handle_timer_ = node_.createTimer(ros::Duration(0.01), &RTGoalHandleFollow::runNonRT, rt_gh);
01017 commandTrajectory(share_member(gh.getGoal(), gh.getGoal()->trajectory),
01018 boost::shared_ptr<RTGoalHandle>((RTGoalHandle*)NULL),
01019 rt_gh);
01020 rt_active_goal_follow_ = rt_gh;
01021 goal_handle_timer_.start();
01022 }
01023
01024 void JointTrajectoryActionController::cancelCB(GoalHandle gh)
01025 {
01026 boost::shared_ptr<RTGoalHandle> current_active_goal(rt_active_goal_);
01027 if (current_active_goal && current_active_goal->gh_ == gh)
01028 {
01029 rt_active_goal_.reset();
01030
01031 trajectory_msgs::JointTrajectory::Ptr empty(new trajectory_msgs::JointTrajectory);
01032 empty->joint_names.resize(joints_.size());
01033 for (size_t j = 0; j < joints_.size(); ++j)
01034 empty->joint_names[j] = joints_[j]->joint_->name;
01035 commandTrajectory(empty);
01036
01037
01038 current_active_goal->gh_.setCanceled();
01039 }
01040 }
01041
01042 void JointTrajectoryActionController::cancelCBFollow(GoalHandleFollow gh)
01043 {
01044 boost::shared_ptr<RTGoalHandleFollow> current_active_goal(rt_active_goal_follow_);
01045 if (current_active_goal && current_active_goal->gh_ == gh)
01046 {
01047 rt_active_goal_follow_.reset();
01048
01049 trajectory_msgs::JointTrajectory::Ptr empty(new trajectory_msgs::JointTrajectory);
01050 empty->joint_names.resize(joints_.size());
01051 for (size_t j = 0; j < joints_.size(); ++j)
01052 empty->joint_names[j] = joints_[j]->joint_->name;
01053 commandTrajectory(empty);
01054
01055
01056 current_active_goal->gh_.setCanceled();
01057 }
01058 }
01059 }