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_DECLARE_CLASS(robot_mechanism_controllers, JointTrajectoryActionController, 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 pids_.resize(joints_.size());
00208 for (size_t i = 0; i < joints_.size(); ++i)
00209 if (!pids_[i].init(ros::NodeHandle(gains_ns + "/" + joints_[i]->joint_->name)))
00210 return false;
00211
00212
00213 default_trajectory_tolerance_.resize(joints_.size());
00214 default_goal_tolerance_.resize(joints_.size());
00215 node_.param("joint_trajectory_action_node/constraints/goal_time", default_goal_time_constraint_, 0.0);
00216 double stopped_velocity_tolerance;
00217 node_.param("joint_trajectory_action_node/constraints/stopped_velocity_tolerance", stopped_velocity_tolerance, 0.01);
00218 for (size_t i = 0; i < default_goal_tolerance_.size(); ++i)
00219 default_goal_tolerance_[i].velocity = stopped_velocity_tolerance;
00220 for (size_t i = 0; i < joints_.size(); ++i)
00221 {
00222 std::string ns = std::string("joint_trajectory_action_node/constraints") + joints_[i]->joint_->name;
00223 node_.param(ns + "/goal", default_goal_tolerance_[i].position, 0.0);
00224 node_.param(ns + "/trajectory", default_trajectory_tolerance_[i].position, 0.0);
00225 }
00226
00227
00228 output_filters_.resize(joints_.size());
00229 for (size_t i = 0; i < joints_.size(); ++i)
00230 {
00231 std::string p = "output_filters/" + joints_[i]->joint_->name;
00232 if (node_.hasParam(p))
00233 {
00234 output_filters_[i].reset(new filters::FilterChain<double>("double"));
00235 if (!output_filters_[i]->configure(node_.resolveName(p)))
00236 output_filters_[i].reset();
00237 }
00238 }
00239
00240
00241 boost::shared_ptr<SpecifiedTrajectory> traj_ptr(new SpecifiedTrajectory(1));
00242 SpecifiedTrajectory &traj = *traj_ptr;
00243 traj[0].start_time = robot_->getTime().toSec();
00244 traj[0].duration = 0.0;
00245 traj[0].splines.resize(joints_.size());
00246 for (size_t j = 0; j < joints_.size(); ++j)
00247 traj[0].splines[j].coef[0] = 0.0;
00248 current_trajectory_box_.set(traj_ptr);
00249
00250 sub_command_ = node_.subscribe("command", 1, &JointTrajectoryActionController::commandCB, this);
00251 serve_query_state_ = node_.advertiseService(
00252 "query_state", &JointTrajectoryActionController::queryStateService, this);
00253
00254 q.resize(joints_.size());
00255 qd.resize(joints_.size());
00256 qdd.resize(joints_.size());
00257
00258 controller_state_publisher_.reset(
00259 new realtime_tools::RealtimePublisher<pr2_controllers_msgs::JointTrajectoryControllerState>
00260 (node_, "state", 1));
00261 controller_state_publisher_->lock();
00262 for (size_t j = 0; j < joints_.size(); ++j)
00263 controller_state_publisher_->msg_.joint_names.push_back(joints_[j]->joint_->name);
00264 controller_state_publisher_->msg_.desired.positions.resize(joints_.size());
00265 controller_state_publisher_->msg_.desired.velocities.resize(joints_.size());
00266 controller_state_publisher_->msg_.desired.accelerations.resize(joints_.size());
00267 controller_state_publisher_->msg_.actual.positions.resize(joints_.size());
00268 controller_state_publisher_->msg_.actual.velocities.resize(joints_.size());
00269 controller_state_publisher_->msg_.error.positions.resize(joints_.size());
00270 controller_state_publisher_->msg_.error.velocities.resize(joints_.size());
00271 controller_state_publisher_->unlock();
00272
00273 action_server_.reset(new JTAS(node_, "joint_trajectory_action",
00274 boost::bind(&JointTrajectoryActionController::goalCB, this, _1),
00275 boost::bind(&JointTrajectoryActionController::cancelCB, this, _1)));
00276 action_server_follow_.reset(new FJTAS(node_, "follow_joint_trajectory",
00277 boost::bind(&JointTrajectoryActionController::goalCBFollow, this, _1),
00278 boost::bind(&JointTrajectoryActionController::cancelCBFollow, this, _1)));
00279
00280 return true;
00281 }
00282
00283 void JointTrajectoryActionController::starting()
00284 {
00285 last_time_ = robot_->getTime();
00286
00287 for (size_t i = 0; i < pids_.size(); ++i)
00288 pids_[i].reset();
00289
00290
00291 boost::shared_ptr<SpecifiedTrajectory> hold_ptr(new SpecifiedTrajectory(1));
00292 SpecifiedTrajectory &hold = *hold_ptr;
00293 hold[0].start_time = last_time_.toSec() - 0.001;
00294 hold[0].duration = 0.0;
00295 hold[0].splines.resize(joints_.size());
00296 for (size_t j = 0; j < joints_.size(); ++j)
00297 hold[0].splines[j].coef[0] = joints_[j]->position_;
00298
00299 current_trajectory_box_.set(hold_ptr);
00300 }
00301
00302 void JointTrajectoryActionController::update()
00303 {
00304 ros::Time time = robot_->getTime();
00305 ros::Duration dt = time - last_time_;
00306 last_time_ = time;
00307
00308 boost::shared_ptr<RTGoalHandle> current_active_goal(rt_active_goal_);
00309 boost::shared_ptr<RTGoalHandleFollow> current_active_goal_follow(rt_active_goal_follow_);
00310
00311 boost::shared_ptr<const SpecifiedTrajectory> traj_ptr;
00312 current_trajectory_box_.get(traj_ptr);
00313 if (!traj_ptr)
00314 ROS_FATAL("The current trajectory can never be null");
00315
00316
00317 const SpecifiedTrajectory &traj = *traj_ptr;
00318
00319
00320
00321
00322 int seg = -1;
00323 while (seg + 1 < (int)traj.size() &&
00324 traj[seg+1].start_time < time.toSec())
00325 {
00326 ++seg;
00327 }
00328
00329 if (seg == -1)
00330 {
00331 if (traj.size() == 0)
00332 ROS_ERROR("No segments in the trajectory");
00333 else
00334 ROS_ERROR("No earlier segments. First segment starts at %.3lf (now = %.3lf)", traj[0].start_time, time.toSec());
00335 return;
00336 }
00337
00338
00339
00340 for (size_t i = 0; i < q.size(); ++i)
00341 {
00342 sampleSplineWithTimeBounds(traj[seg].splines[i].coef, traj[seg].duration,
00343 time.toSec() - traj[seg].start_time,
00344 q[i], qd[i], qdd[i]);
00345 }
00346
00347
00348
00349 std::vector<double> error(joints_.size());
00350 std::vector<double> v_error(joints_.size());
00351 for (size_t i = 0; i < joints_.size(); ++i)
00352 {
00353 error[i] = joints_[i]->position_ - q[i];
00354 v_error[i] = joints_[i]->velocity_ - qd[i];
00355 double effort = pids_[i].updatePid(error[i], v_error[i], dt);
00356 double effort_filtered = effort;
00357 if (output_filters_[i])
00358 output_filters_[i]->update(effort, effort_filtered);
00359 joints_[i]->commanded_effort_ += effort_filtered;
00360 }
00361
00362
00363
00364 if ((traj[seg].gh && traj[seg].gh == current_active_goal) ||
00365 (traj[seg].gh_follow && traj[seg].gh_follow == current_active_goal_follow))
00366 {
00367 ros::Time end_time(traj[seg].start_time + traj[seg].duration);
00368 if (time <= end_time)
00369 {
00370
00371 for (size_t j = 0; j < joints_.size(); ++j)
00372 {
00373 if (traj[seg].trajectory_tolerance[j].violated(error[j], v_error[j]))
00374 {
00375 if (traj[seg].gh)
00376 traj[seg].gh->setAborted();
00377 else if (traj[seg].gh_follow) {
00378 traj[seg].gh_follow->preallocated_result_->error_code =
00379 control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
00380 traj[seg].gh_follow->setAborted(traj[seg].gh_follow->preallocated_result_);
00381 }
00382 break;
00383 }
00384 }
00385 }
00386 else if (seg == (int)traj.size() - 1)
00387 {
00388
00389 bool inside_goal_constraints = true;
00390 for (size_t i = 0; i < joints_.size() && inside_goal_constraints; ++i)
00391 {
00392 if (traj[seg].goal_tolerance[i].violated(error[i], v_error[i]))
00393 inside_goal_constraints = false;
00394 }
00395
00396 if (inside_goal_constraints)
00397 {
00398 rt_active_goal_.reset();
00399 rt_active_goal_follow_.reset();
00400 if (traj[seg].gh)
00401 traj[seg].gh->setSucceeded();
00402 else if (traj[seg].gh_follow) {
00403 traj[seg].gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::SUCCESSFUL;
00404 traj[seg].gh_follow->setSucceeded(traj[seg].gh_follow->preallocated_result_);
00405 }
00406
00407 }
00408 else if (time < end_time + ros::Duration(traj[seg].goal_time_tolerance))
00409 {
00410
00411 }
00412 else
00413 {
00414
00415 rt_active_goal_.reset();
00416 rt_active_goal_follow_.reset();
00417 if (traj[seg].gh)
00418 traj[seg].gh->setAborted();
00419 else if (traj[seg].gh_follow) {
00420 traj[seg].gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED;
00421 traj[seg].gh_follow->setAborted(traj[seg].gh_follow->preallocated_result_);
00422 }
00423 }
00424 }
00425 }
00426
00427
00428
00429 if (loop_count_ % 10 == 0)
00430 {
00431 if (controller_state_publisher_ && controller_state_publisher_->trylock())
00432 {
00433 controller_state_publisher_->msg_.header.stamp = time;
00434 for (size_t j = 0; j < joints_.size(); ++j)
00435 {
00436 controller_state_publisher_->msg_.desired.positions[j] = q[j];
00437 controller_state_publisher_->msg_.desired.velocities[j] = qd[j];
00438 controller_state_publisher_->msg_.desired.accelerations[j] = qdd[j];
00439 controller_state_publisher_->msg_.actual.positions[j] = joints_[j]->position_;
00440 controller_state_publisher_->msg_.actual.velocities[j] = joints_[j]->velocity_;
00441 controller_state_publisher_->msg_.error.positions[j] = error[j];
00442 controller_state_publisher_->msg_.error.velocities[j] = joints_[j]->velocity_ - qd[j];
00443 }
00444 controller_state_publisher_->unlockAndPublish();
00445 }
00446 }
00447
00448 ++loop_count_;
00449 }
00450
00451 void JointTrajectoryActionController::commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
00452 {
00453 preemptActiveGoal();
00454 commandTrajectory(msg);
00455 }
00456
00457 void JointTrajectoryActionController::commandTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &msg,
00458 boost::shared_ptr<RTGoalHandle> gh,
00459 boost::shared_ptr<RTGoalHandleFollow> gh_follow)
00460 {
00461 assert(!gh || !gh_follow);
00462 ros::Time time = last_time_ + ros::Duration(0.01);
00463 ROS_DEBUG("Figuring out new trajectory at %.3lf, with data from %.3lf",
00464 time.toSec(), msg->header.stamp.toSec());
00465
00466 boost::shared_ptr<SpecifiedTrajectory> new_traj_ptr(new SpecifiedTrajectory);
00467 SpecifiedTrajectory &new_traj = *new_traj_ptr;
00468
00469
00470
00471 if (msg->points.empty())
00472 {
00473 starting();
00474 return;
00475 }
00476
00477
00478
00479 std::vector<JointTolerance> trajectory_tolerance = default_trajectory_tolerance_;
00480 std::vector<JointTolerance> goal_tolerance = default_goal_tolerance_;
00481 double goal_time_tolerance = default_goal_time_constraint_;
00482
00483 if (gh_follow)
00484 {
00485 for (size_t j = 0; j < joints_.size(); ++j)
00486 {
00487
00488 for (size_t k = 0; k < gh_follow->gh_.getGoal()->path_tolerance.size(); ++k)
00489 {
00490 const control_msgs::JointTolerance &tol = gh_follow->gh_.getGoal()->path_tolerance[k];
00491 if (joints_[j]->joint_->name == tol.name)
00492 {
00493
00494
00495
00496
00497
00498 if (tol.position > 0)
00499 trajectory_tolerance[j].position = tol.position;
00500 else if (tol.position < 0)
00501 trajectory_tolerance[j].position = 0.0;
00502
00503 if (tol.velocity > 0)
00504 trajectory_tolerance[j].velocity = tol.velocity;
00505 else if (tol.velocity < 0)
00506 trajectory_tolerance[j].velocity = 0.0;
00507
00508 if (tol.acceleration > 0)
00509 trajectory_tolerance[j].acceleration = tol.acceleration;
00510 else if (tol.acceleration < 0)
00511 trajectory_tolerance[j].acceleration = 0.0;
00512
00513 break;
00514 }
00515 }
00516
00517
00518 for (size_t k = 0; k < gh_follow->gh_.getGoal()->goal_tolerance.size(); ++k)
00519 {
00520 const control_msgs::JointTolerance &tol = gh_follow->gh_.getGoal()->goal_tolerance[k];
00521 if (joints_[j]->joint_->name == tol.name)
00522 {
00523
00524
00525
00526
00527
00528 if (tol.position > 0)
00529 goal_tolerance[j].position = tol.position;
00530 else if (tol.position < 0)
00531 goal_tolerance[j].position = 0.0;
00532
00533 if (tol.velocity > 0)
00534 goal_tolerance[j].velocity = tol.velocity;
00535 else if (tol.velocity < 0)
00536 goal_tolerance[j].velocity = 0.0;
00537
00538 if (tol.acceleration > 0)
00539 goal_tolerance[j].acceleration = tol.acceleration;
00540 else if (tol.acceleration < 0)
00541 goal_tolerance[j].acceleration = 0.0;
00542
00543 break;
00544 }
00545 }
00546 }
00547
00548 const ros::Duration &tol = gh_follow->gh_.getGoal()->goal_time_tolerance;
00549 if (tol < ros::Duration(0.0))
00550 goal_time_tolerance = 0.0;
00551 else if (tol > ros::Duration(0.0))
00552 goal_time_tolerance = tol.toSec();
00553 }
00554
00555
00556
00557 std::vector<int> lookup(joints_.size(), -1);
00558 for (size_t j = 0; j < joints_.size(); ++j)
00559 {
00560 for (size_t k = 0; k < msg->joint_names.size(); ++k)
00561 {
00562 if (msg->joint_names[k] == joints_[j]->joint_->name)
00563 {
00564 lookup[j] = k;
00565 break;
00566 }
00567 }
00568
00569 if (lookup[j] == -1)
00570 {
00571 ROS_ERROR("Unable to locate joint %s in the commanded trajectory.", joints_[j]->joint_->name.c_str());
00572 if (gh)
00573 gh->setAborted();
00574 else if (gh_follow) {
00575 gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00576 gh_follow->setAborted(gh_follow->preallocated_result_);
00577 }
00578 return;
00579 }
00580 }
00581
00582
00583
00584 boost::shared_ptr<const SpecifiedTrajectory> prev_traj_ptr;
00585 current_trajectory_box_.get(prev_traj_ptr);
00586 if (!prev_traj_ptr)
00587 {
00588 ROS_FATAL("The current trajectory can never be null");
00589 return;
00590 }
00591 const SpecifiedTrajectory &prev_traj = *prev_traj_ptr;
00592
00593
00594
00595
00596 int first_useful = -1;
00597 while (first_useful + 1 < (int)prev_traj.size() &&
00598 prev_traj[first_useful + 1].start_time <= time.toSec())
00599 {
00600 ++first_useful;
00601 }
00602
00603
00604 int last_useful = -1;
00605 double msg_start_time;
00606 if (msg->header.stamp == ros::Time(0.0))
00607 msg_start_time = time.toSec();
00608 else
00609 msg_start_time = msg->header.stamp.toSec();
00610
00611
00612
00613
00614
00615 while (last_useful + 1 < (int)prev_traj.size() &&
00616 prev_traj[last_useful + 1].start_time < msg_start_time)
00617 {
00618 ++last_useful;
00619 }
00620
00621 if (last_useful < first_useful)
00622 first_useful = last_useful;
00623
00624
00625 for (int i = std::max(first_useful,0); i <= last_useful; ++i)
00626 {
00627 new_traj.push_back(prev_traj[i]);
00628 }
00629
00630
00631
00632 if (new_traj.size() == 0)
00633 new_traj.push_back(prev_traj[prev_traj.size() - 1]);
00634
00635
00636
00637
00638 Segment &last = new_traj[new_traj.size() - 1];
00639 std::vector<double> prev_positions(joints_.size());
00640 std::vector<double> prev_velocities(joints_.size());
00641 std::vector<double> prev_accelerations(joints_.size());
00642
00643 double t = (msg->header.stamp == ros::Time(0.0) ? time.toSec() : msg->header.stamp.toSec())
00644 - last.start_time;
00645 ROS_DEBUG("Initial conditions at %.3f for new set of splines:", t);
00646 for (size_t i = 0; i < joints_.size(); ++i)
00647 {
00648 sampleSplineWithTimeBounds(last.splines[i].coef, last.duration,
00649 t,
00650 prev_positions[i], prev_velocities[i], prev_accelerations[i]);
00651 ROS_DEBUG(" %.2lf, %.2lf, %.2lf (%s)", prev_positions[i], prev_velocities[i],
00652 prev_accelerations[i], joints_[i]->joint_->name.c_str());
00653 }
00654
00655
00656
00657 std::vector<double> positions;
00658 std::vector<double> velocities;
00659 std::vector<double> accelerations;
00660
00661 std::vector<double> durations(msg->points.size());
00662 if (msg->points.size() > 0)
00663 durations[0] = msg->points[0].time_from_start.toSec();
00664 for (size_t i = 1; i < msg->points.size(); ++i)
00665 durations[i] = (msg->points[i].time_from_start - msg->points[i-1].time_from_start).toSec();
00666
00667
00668 std::vector<double> wrap(joints_.size(), 0.0);
00669 assert(!msg->points[0].positions.empty());
00670 for (size_t j = 0; j < joints_.size(); ++j)
00671 {
00672 if (joints_[j]->joint_->type == urdf::Joint::CONTINUOUS)
00673 {
00674 double dist = angles::shortest_angular_distance(prev_positions[j], msg->points[0].positions[j]);
00675 wrap[j] = (prev_positions[j] + dist) - msg->points[0].positions[j];
00676 }
00677 }
00678
00679 for (size_t i = 0; i < msg->points.size(); ++i)
00680 {
00681 Segment seg;
00682
00683 if (msg->header.stamp == ros::Time(0.0))
00684 seg.start_time = (time + msg->points[i].time_from_start).toSec() - durations[i];
00685 else
00686 seg.start_time = (msg->header.stamp + msg->points[i].time_from_start).toSec() - durations[i];
00687 seg.duration = durations[i];
00688 seg.gh = gh;
00689 seg.gh_follow = gh_follow;
00690 seg.splines.resize(joints_.size());
00691
00692
00693
00694 if (msg->points[i].accelerations.size() != 0 && msg->points[i].accelerations.size() != joints_.size())
00695 {
00696 ROS_ERROR("Command point %d has %d elements for the accelerations", (int)i, (int)msg->points[i].accelerations.size());
00697 return;
00698 }
00699 if (msg->points[i].velocities.size() != 0 && msg->points[i].velocities.size() != joints_.size())
00700 {
00701 ROS_ERROR("Command point %d has %d elements for the velocities", (int)i, (int)msg->points[i].velocities.size());
00702 return;
00703 }
00704 if (msg->points[i].positions.size() != joints_.size())
00705 {
00706 ROS_ERROR("Command point %d has %d elements for the positions", (int)i, (int)msg->points[i].positions.size());
00707 return;
00708 }
00709
00710
00711
00712 accelerations.resize(msg->points[i].accelerations.size());
00713 velocities.resize(msg->points[i].velocities.size());
00714 positions.resize(msg->points[i].positions.size());
00715 for (size_t j = 0; j < joints_.size(); ++j)
00716 {
00717 if (!accelerations.empty()) accelerations[j] = msg->points[i].accelerations[lookup[j]];
00718 if (!velocities.empty()) velocities[j] = msg->points[i].velocities[lookup[j]];
00719 if (!positions.empty()) positions[j] = msg->points[i].positions[lookup[j]] + wrap[j];
00720 }
00721
00722
00723
00724 for (size_t j = 0; j < joints_.size(); ++j)
00725 {
00726 if (prev_accelerations.size() > 0 && accelerations.size() > 0)
00727 {
00728 getQuinticSplineCoefficients(
00729 prev_positions[j], prev_velocities[j], prev_accelerations[j],
00730 positions[j], velocities[j], accelerations[j],
00731 durations[i],
00732 seg.splines[j].coef);
00733 }
00734 else if (prev_velocities.size() > 0 && velocities.size() > 0)
00735 {
00736 getCubicSplineCoefficients(
00737 prev_positions[j], prev_velocities[j],
00738 positions[j], velocities[j],
00739 durations[i],
00740 seg.splines[j].coef);
00741 seg.splines[j].coef.resize(6, 0.0);
00742 }
00743 else
00744 {
00745 seg.splines[j].coef[0] = prev_positions[j];
00746 if (durations[i] == 0.0)
00747 seg.splines[j].coef[1] = 0.0;
00748 else
00749 seg.splines[j].coef[1] = (positions[j] - prev_positions[j]) / durations[i];
00750 seg.splines[j].coef[2] = 0.0;
00751 seg.splines[j].coef[3] = 0.0;
00752 seg.splines[j].coef[4] = 0.0;
00753 seg.splines[j].coef[5] = 0.0;
00754 }
00755 }
00756
00757
00758 seg.trajectory_tolerance = trajectory_tolerance;
00759 seg.goal_tolerance = goal_tolerance;
00760 seg.goal_time_tolerance = goal_time_tolerance;
00761
00762
00763
00764 new_traj.push_back(seg);
00765
00766
00767
00768 prev_positions = positions;
00769 prev_velocities = velocities;
00770 prev_accelerations = accelerations;
00771 }
00772
00773
00774
00775
00776
00777 if (!new_traj_ptr)
00778 {
00779 ROS_ERROR("The new trajectory was null!");
00780 return;
00781 }
00782
00783 current_trajectory_box_.set(new_traj_ptr);
00784 ROS_DEBUG("The new trajectory has %d segments", (int)new_traj.size());
00785 #if 0
00786 for (size_t i = 0; i < std::min((size_t)20,new_traj.size()); ++i)
00787 {
00788 ROS_DEBUG("Segment %2d: %.3lf for %.3lf", i, new_traj[i].start_time, new_traj[i].duration);
00789 for (size_t j = 0; j < new_traj[i].splines.size(); ++j)
00790 {
00791 ROS_DEBUG(" %.2lf %.2lf %.2lf %.2lf , %.2lf %.2lf(%s)",
00792 new_traj[i].splines[j].coef[0],
00793 new_traj[i].splines[j].coef[1],
00794 new_traj[i].splines[j].coef[2],
00795 new_traj[i].splines[j].coef[3],
00796 new_traj[i].splines[j].coef[4],
00797 new_traj[i].splines[j].coef[5],
00798 joints_[j]->joint_->name_.c_str());
00799 }
00800 }
00801 #endif
00802 }
00803
00804 bool JointTrajectoryActionController::queryStateService(
00805 pr2_controllers_msgs::QueryTrajectoryState::Request &req,
00806 pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
00807 {
00808 boost::shared_ptr<const SpecifiedTrajectory> traj_ptr;
00809 current_trajectory_box_.get(traj_ptr);
00810 if (!traj_ptr)
00811 {
00812 ROS_FATAL("The current trajectory can never be null");
00813 return false;
00814 }
00815 const SpecifiedTrajectory &traj = *traj_ptr;
00816
00817
00818 int seg = -1;
00819 while (seg + 1 < (int)traj.size() &&
00820 traj[seg+1].start_time < req.time.toSec())
00821 {
00822 ++seg;
00823 }
00824 if (seg == -1)
00825 return false;
00826
00827 for (size_t i = 0; i < q.size(); ++i)
00828 {
00829 }
00830
00831
00832 resp.name.resize(joints_.size());
00833 resp.position.resize(joints_.size());
00834 resp.velocity.resize(joints_.size());
00835 resp.acceleration.resize(joints_.size());
00836 for (size_t j = 0; j < joints_.size(); ++j)
00837 {
00838 resp.name[j] = joints_[j]->joint_->name;
00839 sampleSplineWithTimeBounds(traj[seg].splines[j].coef, traj[seg].duration,
00840 req.time.toSec() - traj[seg].start_time,
00841 resp.position[j], resp.velocity[j], resp.acceleration[j]);
00842 }
00843
00844 return true;
00845 }
00846
00847 void JointTrajectoryActionController::sampleSplineWithTimeBounds(
00848 const std::vector<double>& coefficients, double duration, double time,
00849 double& position, double& velocity, double& acceleration)
00850 {
00851 if (time < 0)
00852 {
00853 double _;
00854 sampleQuinticSpline(coefficients, 0.0, position, _, _);
00855 velocity = 0;
00856 acceleration = 0;
00857 }
00858 else if (time > duration)
00859 {
00860 double _;
00861 sampleQuinticSpline(coefficients, duration, position, _, _);
00862 velocity = 0;
00863 acceleration = 0;
00864 }
00865 else
00866 {
00867 sampleQuinticSpline(coefficients, time,
00868 position, velocity, acceleration);
00869 }
00870 }
00871
00872 static bool setsEqual(const std::vector<std::string> &a, const std::vector<std::string> &b)
00873 {
00874 if (a.size() != b.size())
00875 return false;
00876
00877 for (size_t i = 0; i < a.size(); ++i)
00878 {
00879 if (count(b.begin(), b.end(), a[i]) != 1)
00880 return false;
00881 }
00882 for (size_t i = 0; i < b.size(); ++i)
00883 {
00884 if (count(a.begin(), a.end(), b[i]) != 1)
00885 return false;
00886 }
00887
00888 return true;
00889 }
00890
00891 void JointTrajectoryActionController::preemptActiveGoal()
00892 {
00893 boost::shared_ptr<RTGoalHandle> current_active_goal(rt_active_goal_);
00894 boost::shared_ptr<RTGoalHandleFollow> current_active_goal_follow(rt_active_goal_follow_);
00895
00896
00897 if (current_active_goal)
00898 {
00899
00900 rt_active_goal_.reset();
00901 current_active_goal->gh_.setCanceled();
00902 }
00903 if (current_active_goal_follow)
00904 {
00905 rt_active_goal_follow_.reset();
00906 current_active_goal_follow->gh_.setCanceled();
00907 }
00908 }
00909
00910
00911 template <class Enclosure, class Member>
00912 static boost::shared_ptr<Member> share_member(boost::shared_ptr<Enclosure> enclosure, Member &member)
00913 {
00914 actionlib::EnclosureDeleter<Enclosure> d(enclosure);
00915 boost::shared_ptr<Member> p(&member, d);
00916 return p;
00917 }
00918
00919 void JointTrajectoryActionController::goalCB(GoalHandle gh)
00920 {
00921 std::vector<std::string> joint_names(joints_.size());
00922 for (size_t j = 0; j < joints_.size(); ++j)
00923 joint_names[j] = joints_[j]->joint_->name;
00924
00925
00926 if (!setsEqual(joint_names, gh.getGoal()->trajectory.joint_names))
00927 {
00928 ROS_ERROR("Joints on incoming goal don't match our joints");
00929 gh.setRejected();
00930 return;
00931 }
00932
00933 preemptActiveGoal();
00934
00935 gh.setAccepted();
00936 boost::shared_ptr<RTGoalHandle> rt_gh(new RTGoalHandle(gh));
00937
00938
00939 goal_handle_timer_ = node_.createTimer(ros::Duration(0.01), &RTGoalHandle::runNonRT, rt_gh);
00940 commandTrajectory(share_member(gh.getGoal(), gh.getGoal()->trajectory), rt_gh);
00941 rt_active_goal_ = rt_gh;
00942 goal_handle_timer_.start();
00943 }
00944
00945 void JointTrajectoryActionController::goalCBFollow(GoalHandleFollow gh)
00946 {
00947 std::vector<std::string> joint_names(joints_.size());
00948 for (size_t j = 0; j < joints_.size(); ++j)
00949 joint_names[j] = joints_[j]->joint_->name;
00950
00951
00952 if (!setsEqual(joint_names, gh.getGoal()->trajectory.joint_names))
00953 {
00954 ROS_ERROR("Joints on incoming goal don't match our joints");
00955 control_msgs::FollowJointTrajectoryResult result;
00956 result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00957 gh.setRejected(result);
00958 return;
00959 }
00960
00961 preemptActiveGoal();
00962
00963 gh.setAccepted();
00964 boost::shared_ptr<RTGoalHandleFollow> rt_gh(new RTGoalHandleFollow(gh));
00965
00966
00967 goal_handle_timer_ = node_.createTimer(ros::Duration(0.01), &RTGoalHandleFollow::runNonRT, rt_gh);
00968 commandTrajectory(share_member(gh.getGoal(), gh.getGoal()->trajectory),
00969 boost::shared_ptr<RTGoalHandle>((RTGoalHandle*)NULL),
00970 rt_gh);
00971 rt_active_goal_follow_ = rt_gh;
00972 goal_handle_timer_.start();
00973 }
00974
00975 void JointTrajectoryActionController::cancelCB(GoalHandle gh)
00976 {
00977 boost::shared_ptr<RTGoalHandle> current_active_goal(rt_active_goal_);
00978 if (current_active_goal && current_active_goal->gh_ == gh)
00979 {
00980 rt_active_goal_.reset();
00981
00982 trajectory_msgs::JointTrajectory::Ptr empty(new trajectory_msgs::JointTrajectory);
00983 empty->joint_names.resize(joints_.size());
00984 for (size_t j = 0; j < joints_.size(); ++j)
00985 empty->joint_names[j] = joints_[j]->joint_->name;
00986 commandTrajectory(empty);
00987
00988
00989 current_active_goal->gh_.setCanceled();
00990 }
00991 }
00992
00993 void JointTrajectoryActionController::cancelCBFollow(GoalHandleFollow gh)
00994 {
00995 boost::shared_ptr<RTGoalHandleFollow> current_active_goal(rt_active_goal_follow_);
00996 if (current_active_goal && current_active_goal->gh_ == gh)
00997 {
00998 rt_active_goal_follow_.reset();
00999
01000 trajectory_msgs::JointTrajectory::Ptr empty(new trajectory_msgs::JointTrajectory);
01001 empty->joint_names.resize(joints_.size());
01002 for (size_t j = 0; j < joints_.size(); ++j)
01003 empty->joint_names[j] = joints_[j]->joint_->name;
01004 commandTrajectory(empty);
01005
01006
01007 current_active_goal->gh_.setCanceled();
01008 }
01009 }
01010 }