joint_trajectory_action_controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Stuart Glaser
32  */
33 
34 #include <boost/bind.hpp>
35 #include <boost/shared_ptr.hpp>
36 
38 #include <sstream>
39 #include "angles/angles.h"
41 
43 
44 namespace controller {
45 
46 // These functions are pulled from the spline_smoother package.
47 // They've been moved here to avoid depending on packages that aren't
48 // mature yet.
49 
50 
51 static inline void generatePowers(int n, double x, double* powers)
52 {
53  powers[0] = 1.0;
54  for (int i=1; i<=n; i++)
55  {
56  powers[i] = powers[i-1]*x;
57  }
58 }
59 
60 static void getQuinticSplineCoefficients(double start_pos, double start_vel, double start_acc,
61  double end_pos, double end_vel, double end_acc, double time, std::vector<double>& coefficients)
62 {
63  coefficients.resize(6);
64 
65  if (time == 0.0)
66  {
67  coefficients[0] = end_pos;
68  coefficients[1] = end_vel;
69  coefficients[2] = 0.5*end_acc;
70  coefficients[3] = 0.0;
71  coefficients[4] = 0.0;
72  coefficients[5] = 0.0;
73  }
74  else
75  {
76  double T[6];
77  generatePowers(5, time, T);
78 
79  coefficients[0] = start_pos;
80  coefficients[1] = start_vel;
81  coefficients[2] = 0.5*start_acc;
82  coefficients[3] = (-20.0*start_pos + 20.0*end_pos - 3.0*start_acc*T[2] + end_acc*T[2] -
83  12.0*start_vel*T[1] - 8.0*end_vel*T[1]) / (2.0*T[3]);
84  coefficients[4] = (30.0*start_pos - 30.0*end_pos + 3.0*start_acc*T[2] - 2.0*end_acc*T[2] +
85  16.0*start_vel*T[1] + 14.0*end_vel*T[1]) / (2.0*T[4]);
86  coefficients[5] = (-12.0*start_pos + 12.0*end_pos - start_acc*T[2] + end_acc*T[2] -
87  6.0*start_vel*T[1] - 6.0*end_vel*T[1]) / (2.0*T[5]);
88  }
89 }
90 
94 static void sampleQuinticSpline(const std::vector<double>& coefficients, double time,
95  double& position, double& velocity, double& acceleration)
96 {
97  // create powers of time:
98  double t[6];
99  generatePowers(5, time, t);
100 
101  position = t[0]*coefficients[0] +
102  t[1]*coefficients[1] +
103  t[2]*coefficients[2] +
104  t[3]*coefficients[3] +
105  t[4]*coefficients[4] +
106  t[5]*coefficients[5];
107 
108  velocity = t[0]*coefficients[1] +
109  2.0*t[1]*coefficients[2] +
110  3.0*t[2]*coefficients[3] +
111  4.0*t[3]*coefficients[4] +
112  5.0*t[4]*coefficients[5];
113 
114  acceleration = 2.0*t[0]*coefficients[2] +
115  6.0*t[1]*coefficients[3] +
116  12.0*t[2]*coefficients[4] +
117  20.0*t[3]*coefficients[5];
118 }
119 
120 static void getCubicSplineCoefficients(double start_pos, double start_vel,
121  double end_pos, double end_vel, double time, std::vector<double>& coefficients)
122 {
123  coefficients.resize(4);
124 
125  if (time == 0.0)
126  {
127  coefficients[0] = end_pos;
128  coefficients[1] = end_vel;
129  coefficients[2] = 0.0;
130  coefficients[3] = 0.0;
131  }
132  else
133  {
134  double T[4];
135  generatePowers(3, time, T);
136 
137  coefficients[0] = start_pos;
138  coefficients[1] = start_vel;
139  coefficients[2] = (-3.0*start_pos + 3.0*end_pos - 2.0*start_vel*T[1] - end_vel*T[1]) / T[2];
140  coefficients[3] = (2.0*start_pos - 2.0*end_pos + start_vel*T[1] + end_vel*T[1]) / T[3];
141  }
142 }
143 
144 
146  : loop_count_(0), robot_(NULL)
147 {
148 }
149 
151 {
154  action_server_.reset();
155  action_server_follow_.reset();
156 }
157 
159 {
160  using namespace XmlRpc;
161  node_ = n;
162  robot_ = robot;
163 
164  // Gets all of the joints
165  XmlRpc::XmlRpcValue joint_names;
166  if (!node_.getParam("joints", joint_names))
167  {
168  ROS_ERROR("No joints given. (namespace: %s)", node_.getNamespace().c_str());
169  return false;
170  }
171  if (joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray)
172  {
173  ROS_ERROR("Malformed joint specification. (namespace: %s)", node_.getNamespace().c_str());
174  return false;
175  }
176  for (int i = 0; i < joint_names.size(); ++i)
177  {
178  XmlRpcValue &name_value = joint_names[i];
179  if (name_value.getType() != XmlRpcValue::TypeString)
180  {
181  ROS_ERROR("Array of joint names should contain all strings. (namespace: %s)",
182  node_.getNamespace().c_str());
183  return false;
184  }
185 
186  pr2_mechanism_model::JointState *j = robot->getJointState((std::string)name_value);
187  if (!j) {
188  ROS_ERROR("Joint not found: %s. (namespace: %s)",
189  ((std::string)name_value).c_str(), node_.getNamespace().c_str());
190  return false;
191  }
192  joints_.push_back(j);
193  }
194 
195  // Ensures that all the joints are calibrated.
196  for (size_t i = 0; i < joints_.size(); ++i)
197  {
198  if (!joints_[i]->calibrated_)
199  {
200  ROS_ERROR("Joint %s was not calibrated (namespace: %s)",
201  joints_[i]->joint_->name.c_str(), node_.getNamespace().c_str());
202  return false;
203  }
204  }
205 
206  // Sets up pid controllers for all of the joints
207  std::string gains_ns;
208  if (!node_.getParam("gains", gains_ns))
209  gains_ns = node_.getNamespace() + "/gains";
210  masses_.resize(joints_.size());
211  pids_.resize(joints_.size());
212  for (size_t i = 0; i < joints_.size(); ++i)
213  {
214  ros::NodeHandle joint_nh(gains_ns + "/" + joints_[i]->joint_->name);
215  joint_nh.param("mass", masses_[i], 0.0);
216  if (!pids_[i].init(joint_nh))
217  return false;
218  }
219 
220  // Sets up the proxy controllers for each joint
221  proxies_enabled_.resize(joints_.size());
222  proxies_.resize(joints_.size());
223  for (size_t i = 0; i < joints_.size(); ++i)
224  {
225  ros::NodeHandle joint_nh(gains_ns + "/" + joints_[i]->joint_->name);
226  if (joint_nh.hasParam("proxy")) {
227  proxies_enabled_[i] = true;
228  joint_nh.param("proxy/lambda", proxies_[i].lambda_proxy_, 1.0);
229  joint_nh.param("proxy/acc_converge", proxies_[i].acc_converge_, 0.0);
230  joint_nh.param("proxy/vel_limit", proxies_[i].vel_limit_, 0.0);
231  joint_nh.param("proxy/effort_limit", proxies_[i].effort_limit_, 0.0);
232  proxies_[i].mass_ = masses_[i];
233  double _;
234  pids_[i].getGains(proxies_[i].Kp_, proxies_[i].Ki_, proxies_[i].Kd_, proxies_[i].Ficl_, _);
235  }
236  else {
237  proxies_enabled_[i] = false;
238  }
239  }
240 
241  // Trajectory and goal tolerances
242  default_trajectory_tolerance_.resize(joints_.size());
243  default_goal_tolerance_.resize(joints_.size());
244  node_.param("joint_trajectory_action_node/constraints/goal_time", default_goal_time_constraint_, 0.0);
245  double stopped_velocity_tolerance;
246  node_.param("joint_trajectory_action_node/constraints/stopped_velocity_tolerance", stopped_velocity_tolerance, 0.01);
247  for (size_t i = 0; i < default_goal_tolerance_.size(); ++i)
248  default_goal_tolerance_[i].velocity = stopped_velocity_tolerance;
249  for (size_t i = 0; i < joints_.size(); ++i)
250  {
251  std::string ns = std::string("joint_trajectory_action_node/constraints/") + joints_[i]->joint_->name;
252  node_.param(ns + "/goal", default_goal_tolerance_[i].position, 0.0);
253  node_.param(ns + "/trajectory", default_trajectory_tolerance_[i].position, 0.0);
254  }
255 
256  // Output filters
257  output_filters_.resize(joints_.size());
258  for (size_t i = 0; i < joints_.size(); ++i)
259  {
260  std::string p = "output_filters/" + joints_[i]->joint_->name;
261  if (node_.hasParam(p))
262  {
263  output_filters_[i].reset(new filters::FilterChain<double>("double"));
264  if (!output_filters_[i]->configure(node_.resolveName(p)))
265  output_filters_[i].reset();
266  }
267  }
268 
269  // Creates a dummy trajectory
271  SpecifiedTrajectory &traj = *traj_ptr;
272  traj[0].start_time = robot_->getTime().toSec();
273  traj[0].duration = 0.0;
274  traj[0].splines.resize(joints_.size());
275  for (size_t j = 0; j < joints_.size(); ++j)
276  traj[0].splines[j].coef[0] = 0.0;
277  current_trajectory_box_.set(traj_ptr);
278 
282 
283  q.resize(joints_.size());
284  qd.resize(joints_.size());
285  qdd.resize(joints_.size());
286 
289  (node_, "state", 1));
291  for (size_t j = 0; j < joints_.size(); ++j)
292  controller_state_publisher_->msg_.joint_names.push_back(joints_[j]->joint_->name);
293  controller_state_publisher_->msg_.desired.positions.resize(joints_.size());
294  controller_state_publisher_->msg_.desired.velocities.resize(joints_.size());
295  controller_state_publisher_->msg_.desired.accelerations.resize(joints_.size());
296  controller_state_publisher_->msg_.desired.effort.resize(joints_.size());
297  controller_state_publisher_->msg_.actual.positions.resize(joints_.size());
298  controller_state_publisher_->msg_.actual.velocities.resize(joints_.size());
299  controller_state_publisher_->msg_.actual.effort.resize(joints_.size());
300  controller_state_publisher_->msg_.error.positions.resize(joints_.size());
301  controller_state_publisher_->msg_.error.velocities.resize(joints_.size());
302  controller_state_publisher_->msg_.error.effort.resize(joints_.size());
303  controller_state_publisher_->unlock();
304 
305  action_server_.reset(new JTAS(node_, "joint_trajectory_action",
306  boost::bind(&JointTrajectoryActionController::goalCB, this, _1),
307  boost::bind(&JointTrajectoryActionController::cancelCB, this, _1),
308  false));
309  action_server_follow_.reset(new FJTAS(node_, "follow_joint_trajectory",
310  boost::bind(&JointTrajectoryActionController::goalCBFollow, this, _1),
311  boost::bind(&JointTrajectoryActionController::cancelCBFollow, this, _1),
312  false));
313  action_server_->start();
314  action_server_follow_->start();
315 
316  return true;
317 }
318 
320 {
322 
323  for (size_t i = 0; i < pids_.size(); ++i) {
324  pids_[i].reset();
325  proxies_[i].reset(joints_[i]->position_, joints_[i]->velocity_);
326  }
327 
328  // Creates a "hold current position" trajectory.
330  SpecifiedTrajectory &hold = *hold_ptr;
331  hold[0].start_time = last_time_.toSec() - 0.001;
332  hold[0].duration = 0.0;
333  hold[0].splines.resize(joints_.size());
334  for (size_t j = 0; j < joints_.size(); ++j)
335  hold[0].splines[j].coef[0] = joints_[j]->position_;
336 
337  current_trajectory_box_.set(hold_ptr);
338 }
339 
341 {
342  ros::Time time = robot_->getTime();
343  ros::Duration dt = time - last_time_;
344  last_time_ = time;
345 
348 
350  current_trajectory_box_.get(traj_ptr);
351  if (!traj_ptr)
352  ROS_FATAL("The current trajectory can never be null");
353 
354  // Only because this is what the code originally looked like.
355  const SpecifiedTrajectory &traj = *traj_ptr;
356 
357  // ------ Finds the current segment
358 
359  // Determines which segment of the trajectory to use. (Not particularly realtime friendly).
360  int seg = -1;
361  while (seg + 1 < (int)traj.size() &&
362  traj[seg+1].start_time < time.toSec())
363  {
364  ++seg;
365  }
366 
367  if (seg == -1)
368  {
369  if (traj.size() == 0)
370  ROS_ERROR("No segments in the trajectory");
371  else
372  ROS_ERROR("No earlier segments. First segment starts at %.3lf (now = %.3lf)", traj[0].start_time, time.toSec());
373  return;
374  }
375 
376  // ------ Trajectory Sampling
377 
378  for (size_t i = 0; i < q.size(); ++i)
379  {
380  sampleSplineWithTimeBounds(traj[seg].splines[i].coef, traj[seg].duration,
381  time.toSec() - traj[seg].start_time,
382  q[i], qd[i], qdd[i]);
383  }
384 
385  // ------ Trajectory Following
386 
387  std::vector<double> error(joints_.size());
388  std::vector<double> v_error(joints_.size());
389  for (size_t i = 0; i < joints_.size(); ++i)
390  {
391  double effort;
392 
393  // Compute the errors with respect to the desired trajectory
394  // (whether or not using the proxy controller). They are also
395  // used later to determine reaching the goal.
396  error[i] = q[i] - joints_[i]->position_;
397  v_error[i] = qd[i] - joints_[i]->velocity_;
398 
399  // Use the proxy controller (if enabled)
400  if (proxies_enabled_[i]) {
401  effort = proxies_[i].update(q[i], qd[i], qdd[i],
402  joints_[i]->position_, joints_[i]->velocity_,
403  dt.toSec());
404  }
405  else {
406  effort = pids_[i].computeCommand(error[i], v_error[i], dt);
407 
408  double effort_unfiltered = effort;
409  if (output_filters_[i])
410  output_filters_[i]->update(effort_unfiltered, effort);
411  }
412 
413  // Apply the effort. WHY IS THIS ADDITIVE?
414  joints_[i]->commanded_effort_ = effort;
415  }
416 
417  // ------ Determines if the goal has failed or succeeded
418 
419  if ((traj[seg].gh && traj[seg].gh == current_active_goal) ||
420  (traj[seg].gh_follow && traj[seg].gh_follow == current_active_goal_follow))
421  {
422  ros::Time end_time(traj[seg].start_time + traj[seg].duration);
423  if (time <= end_time)
424  {
425  // Verifies trajectory tolerances
426  for (size_t j = 0; j < joints_.size(); ++j)
427  {
428  if (traj[seg].trajectory_tolerance[j].violated(error[j], v_error[j]))
429  {
430  if (traj[seg].gh)
431  traj[seg].gh->setAborted();
432  else if (traj[seg].gh_follow) {
433  traj[seg].gh_follow->preallocated_result_->error_code =
434  control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
435  traj[seg].gh_follow->setAborted(traj[seg].gh_follow->preallocated_result_);
436  }
437  break;
438  }
439  }
440  }
441  else if (seg == (int)traj.size() - 1)
442  {
443  // Checks that we have ended inside the goal tolerances
444  bool inside_goal_constraints = true;
445  for (size_t i = 0; i < joints_.size() && inside_goal_constraints; ++i)
446  {
447  if (traj[seg].goal_tolerance[i].violated(error[i], v_error[i]))
448  inside_goal_constraints = false;
449  }
450 
451  if (inside_goal_constraints)
452  {
453  rt_active_goal_.reset();
454  rt_active_goal_follow_.reset();
455  if (traj[seg].gh)
456  traj[seg].gh->setSucceeded();
457  else if (traj[seg].gh_follow) {
458  traj[seg].gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::SUCCESSFUL;
459  traj[seg].gh_follow->setSucceeded(traj[seg].gh_follow->preallocated_result_);
460  }
461  //ROS_ERROR("Success! (%s)", traj[seg].gh->gh_.getGoalID().id.c_str());
462  }
463  else if (time < end_time + ros::Duration(traj[seg].goal_time_tolerance))
464  {
465  // Still have some time left to make it.
466  }
467  else
468  {
469  //ROS_WARN("Aborting because we wound up outside the goal constraints");
470  rt_active_goal_.reset();
471  rt_active_goal_follow_.reset();
472  if (traj[seg].gh)
473  traj[seg].gh->setAborted();
474  else if (traj[seg].gh_follow) {
475  traj[seg].gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED;
476  traj[seg].gh_follow->setAborted(traj[seg].gh_follow->preallocated_result_);
477  }
478  }
479  }
480  }
481 
482  // ------ State publishing
483 
484  if (loop_count_ % 10 == 0)
485  {
487  {
488  controller_state_publisher_->msg_.header.stamp = time;
489  for (size_t j = 0; j < joints_.size(); ++j)
490  {
491  controller_state_publisher_->msg_.desired.positions[j] = q[j];
492  controller_state_publisher_->msg_.desired.velocities[j] = qd[j];
493  controller_state_publisher_->msg_.desired.accelerations[j] = qdd[j];
494  controller_state_publisher_->msg_.desired.effort[j] = joints_[j]->commanded_effort_;
495  controller_state_publisher_->msg_.actual.positions[j] = joints_[j]->position_;
496  controller_state_publisher_->msg_.actual.velocities[j] = joints_[j]->velocity_;
497  controller_state_publisher_->msg_.actual.effort[j] = joints_[j]->measured_effort_;
498  controller_state_publisher_->msg_.error.positions[j] = error[j];
499  controller_state_publisher_->msg_.error.velocities[j] = joints_[j]->velocity_ - qd[j];
500  controller_state_publisher_->msg_.error.effort[j] = joints_[j]->measured_effort_ - joints_[j]->commanded_effort_;
501  }
502  controller_state_publisher_->unlockAndPublish();
503  }
504  if (current_active_goal_follow)
505  {
506  current_active_goal_follow->preallocated_feedback_->header.stamp = time;
507  current_active_goal_follow->preallocated_feedback_->joint_names.resize(joints_.size());
508  current_active_goal_follow->preallocated_feedback_->desired.positions.resize(joints_.size());
509  current_active_goal_follow->preallocated_feedback_->desired.velocities.resize(joints_.size());
510  current_active_goal_follow->preallocated_feedback_->desired.accelerations.resize(joints_.size());
511  current_active_goal_follow->preallocated_feedback_->desired.effort.resize(joints_.size());
512  current_active_goal_follow->preallocated_feedback_->actual.positions.resize(joints_.size());
513  current_active_goal_follow->preallocated_feedback_->actual.velocities.resize(joints_.size());
514  current_active_goal_follow->preallocated_feedback_->actual.effort.resize(joints_.size());
515  current_active_goal_follow->preallocated_feedback_->error.positions.resize(joints_.size());
516  current_active_goal_follow->preallocated_feedback_->error.velocities.resize(joints_.size());
517  current_active_goal_follow->preallocated_feedback_->error.effort.resize(joints_.size());
518  for (size_t j = 0; j < joints_.size(); ++j)
519  {
520  current_active_goal_follow->preallocated_feedback_->joint_names[j] = joints_[j]->joint_->name;
521  current_active_goal_follow->preallocated_feedback_->desired.positions[j] = q[j];
522  current_active_goal_follow->preallocated_feedback_->desired.velocities[j] = qd[j];
523  current_active_goal_follow->preallocated_feedback_->desired.accelerations[j] = qdd[j];
524  current_active_goal_follow->preallocated_feedback_->desired.effort[j] = joints_[j]->commanded_effort_;
525  current_active_goal_follow->preallocated_feedback_->actual.positions[j] = joints_[j]->position_;
526  current_active_goal_follow->preallocated_feedback_->actual.velocities[j] = joints_[j]->velocity_;
527  current_active_goal_follow->preallocated_feedback_->actual.effort[j] = joints_[j]->measured_effort_;
528  current_active_goal_follow->preallocated_feedback_->error.positions[j] = error[j];
529  current_active_goal_follow->preallocated_feedback_->error.velocities[j] = joints_[j]->velocity_ - qd[j];
530  current_active_goal_follow->preallocated_feedback_->error.effort[j] = joints_[j]->measured_effort_ - joints_[j]->commanded_effort_;
531  }
532  const actionlib_msgs::GoalID goalID = current_active_goal_follow->gh_.getGoalID();
533  ros::Duration time_from_start = time - goalID.stamp;
534  current_active_goal_follow->preallocated_feedback_->desired.time_from_start = time_from_start;
535  current_active_goal_follow->preallocated_feedback_->actual.time_from_start = time_from_start;
536  current_active_goal_follow->preallocated_feedback_->error.time_from_start = time_from_start;
537  current_active_goal_follow->gh_.publishFeedback(*current_active_goal_follow->preallocated_feedback_);
538 
539  }
540  }
541 
542  ++loop_count_;
543 }
544 
545 void JointTrajectoryActionController::commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
546 {
549 }
550 
551 void JointTrajectoryActionController::commandTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &msg,
554 {
555  assert(!gh || !gh_follow);
556  ros::Time time = last_time_ + ros::Duration(0.01);
557  ROS_DEBUG("Figuring out new trajectory at %.3lf, with data from %.3lf",
558  time.toSec(), msg->header.stamp.toSec());
559 
561  SpecifiedTrajectory &new_traj = *new_traj_ptr;
562 
563  // ------ If requested, performs a stop
564 
565  if (msg->points.empty())
566  {
567  starting();
568  return;
569  }
570 
571  // ------ Computes the tolerances for following the trajectory
572 
573  std::vector<JointTolerance> trajectory_tolerance = default_trajectory_tolerance_;
574  std::vector<JointTolerance> goal_tolerance = default_goal_tolerance_;
575  double goal_time_tolerance = default_goal_time_constraint_;
576 
577  if (gh_follow)
578  {
579  for (size_t j = 0; j < joints_.size(); ++j)
580  {
581  // Extracts the path tolerance from the command
582  for (size_t k = 0; k < gh_follow->gh_.getGoal()->path_tolerance.size(); ++k)
583  {
584  const control_msgs::JointTolerance &tol = gh_follow->gh_.getGoal()->path_tolerance[k];
585  if (joints_[j]->joint_->name == tol.name)
586  {
587  // If the commanded tolerances are positive, overwrite the
588  // existing tolerances. If they are -1, remove any existing
589  // tolerance. If they are 0, leave the default tolerance in
590  // place.
591 
592  if (tol.position > 0)
593  trajectory_tolerance[j].position = tol.position;
594  else if (tol.position < 0)
595  trajectory_tolerance[j].position = 0.0;
596 
597  if (tol.velocity > 0)
598  trajectory_tolerance[j].velocity = tol.velocity;
599  else if (tol.velocity < 0)
600  trajectory_tolerance[j].velocity = 0.0;
601 
602  if (tol.acceleration > 0)
603  trajectory_tolerance[j].acceleration = tol.acceleration;
604  else if (tol.acceleration < 0)
605  trajectory_tolerance[j].acceleration = 0.0;
606 
607  break;
608  }
609  }
610 
611  // Extracts the goal tolerance from the command
612  for (size_t k = 0; k < gh_follow->gh_.getGoal()->goal_tolerance.size(); ++k)
613  {
614  const control_msgs::JointTolerance &tol = gh_follow->gh_.getGoal()->goal_tolerance[k];
615  if (joints_[j]->joint_->name == tol.name)
616  {
617  // If the commanded tolerances are positive, overwrite the
618  // existing tolerances. If they are -1, remove any existing
619  // tolerance. If they are 0, leave the default tolerance in
620  // place.
621 
622  if (tol.position > 0)
623  goal_tolerance[j].position = tol.position;
624  else if (tol.position < 0)
625  goal_tolerance[j].position = 0.0;
626 
627  if (tol.velocity > 0)
628  goal_tolerance[j].velocity = tol.velocity;
629  else if (tol.velocity < 0)
630  goal_tolerance[j].velocity = 0.0;
631 
632  if (tol.acceleration > 0)
633  goal_tolerance[j].acceleration = tol.acceleration;
634  else if (tol.acceleration < 0)
635  goal_tolerance[j].acceleration = 0.0;
636 
637  break;
638  }
639  }
640  }
641 
642  const ros::Duration &tol = gh_follow->gh_.getGoal()->goal_time_tolerance;
643  if (tol < ros::Duration(0.0))
644  goal_time_tolerance = 0.0;
645  else if (tol > ros::Duration(0.0))
646  goal_time_tolerance = tol.toSec();
647  }
648 
649  // ------ Correlates the joints we're commanding to the joints in the message
650 
651  std::vector<int> lookup(joints_.size(), -1); // Maps from an index in joints_ to an index in the msg
652  for (size_t j = 0; j < joints_.size(); ++j)
653  {
654  for (size_t k = 0; k < msg->joint_names.size(); ++k)
655  {
656  if (msg->joint_names[k] == joints_[j]->joint_->name)
657  {
658  lookup[j] = k;
659  break;
660  }
661  }
662 
663  if (lookup[j] == -1)
664  {
665  ROS_ERROR("Unable to locate joint %s in the commanded trajectory.", joints_[j]->joint_->name.c_str());
666  if (gh)
667  gh->setAborted();
668  else if (gh_follow) {
669  gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
670  gh_follow->setAborted(gh_follow->preallocated_result_);
671  }
672  return;
673  }
674  }
675 
676  // ------ Grabs the trajectory that we're currently following.
677 
679  current_trajectory_box_.get(prev_traj_ptr);
680  if (!prev_traj_ptr)
681  {
682  ROS_FATAL("The current trajectory can never be null");
683  return;
684  }
685  const SpecifiedTrajectory &prev_traj = *prev_traj_ptr;
686 
687  // ------ Copies over the segments from the previous trajectory that are still useful.
688 
689  // Useful segments are still relevant after the current time.
690  int first_useful = -1;
691  while (first_useful + 1 < (int)prev_traj.size() &&
692  prev_traj[first_useful + 1].start_time <= time.toSec())
693  {
694  ++first_useful;
695  }
696 
697  // Useful segments are not going to be completely overwritten by the message's splines.
698  int last_useful = -1;
699  double msg_start_time;
700  if (msg->header.stamp == ros::Time(0.0))
701  msg_start_time = time.toSec();
702  else
703  msg_start_time = msg->header.stamp.toSec();
704  /*
705  if (msg->points.size() > 0)
706  msg_start_time += msg->points[0].time_from_start.toSec();
707  */
708 
709  while (last_useful + 1 < (int)prev_traj.size() &&
710  prev_traj[last_useful + 1].start_time < msg_start_time)
711  {
712  ++last_useful;
713  }
714 
715  if (last_useful < first_useful)
716  first_useful = last_useful;
717 
718  // Copies over the old segments that were determined to be useful.
719  for (int i = std::max(first_useful,0); i <= last_useful; ++i)
720  {
721  new_traj.push_back(prev_traj[i]);
722  }
723 
724  // We always save the last segment so that we know where to stop if
725  // there are no new segments.
726  if (new_traj.size() == 0)
727  new_traj.push_back(prev_traj[prev_traj.size() - 1]);
728 
729  // ------ Determines when and where the new segments start
730 
731  // Finds the end conditions of the final segment
732  Segment &last = new_traj[new_traj.size() - 1];
733  std::vector<double> prev_positions(joints_.size());
734  std::vector<double> prev_velocities(joints_.size());
735  std::vector<double> prev_accelerations(joints_.size());
736 
737  double t = (msg->header.stamp == ros::Time(0.0) ? time.toSec() : msg->header.stamp.toSec())
738  - last.start_time;
739  ROS_DEBUG("Initial conditions at %.3f for new set of splines:", t);
740  for (size_t i = 0; i < joints_.size(); ++i)
741  {
742  sampleSplineWithTimeBounds(last.splines[i].coef, last.duration,
743  t,
744  prev_positions[i], prev_velocities[i], prev_accelerations[i]);
745  ROS_DEBUG(" %.2lf, %.2lf, %.2lf (%s)", prev_positions[i], prev_velocities[i],
746  prev_accelerations[i], joints_[i]->joint_->name.c_str());
747  }
748 
749  // ------ Tacks on the new segments
750 
751  std::vector<double> positions;
752  std::vector<double> velocities;
753  std::vector<double> accelerations;
754 
755  std::vector<double> durations(msg->points.size());
756  if (msg->points.size() > 0)
757  durations[0] = msg->points[0].time_from_start.toSec();
758  for (size_t i = 1; i < msg->points.size(); ++i)
759  durations[i] = (msg->points[i].time_from_start - msg->points[i-1].time_from_start).toSec();
760 
761  // Checks if we should wrap
762  std::vector<double> wrap(joints_.size(), 0.0);
763  assert(!msg->points[0].positions.empty());
764  for (size_t j = 0; j < joints_.size(); ++j)
765  {
766  if (joints_[j]->joint_->type == urdf::Joint::CONTINUOUS)
767  {
768  double dist = angles::shortest_angular_distance(prev_positions[j], msg->points[0].positions[lookup[j]]);
769  wrap[j] = (prev_positions[j] + dist) - msg->points[0].positions[lookup[j]];
770  }
771  }
772 
773  for (size_t i = 0; i < msg->points.size(); ++i)
774  {
775  Segment seg;
776 
777  if (msg->header.stamp == ros::Time(0.0))
778  seg.start_time = (time + msg->points[i].time_from_start).toSec() - durations[i];
779  else
780  seg.start_time = (msg->header.stamp + msg->points[i].time_from_start).toSec() - durations[i];
781  seg.duration = durations[i];
782  seg.gh = gh;
783  seg.gh_follow = gh_follow;
784  seg.splines.resize(joints_.size());
785 
786  // Checks that the incoming segment has the right number of elements.
787 
788  if (msg->points[i].accelerations.size() != 0 && msg->points[i].accelerations.size() != joints_.size())
789  {
790  ROS_ERROR("Command point %d has %d elements for the accelerations", (int)i, (int)msg->points[i].accelerations.size());
791  return;
792  }
793  if (msg->points[i].velocities.size() != 0 && msg->points[i].velocities.size() != joints_.size())
794  {
795  ROS_ERROR("Command point %d has %d elements for the velocities", (int)i, (int)msg->points[i].velocities.size());
796  return;
797  }
798  if (msg->points[i].positions.size() != joints_.size())
799  {
800  ROS_ERROR("Command point %d has %d elements for the positions", (int)i, (int)msg->points[i].positions.size());
801  return;
802  }
803 
804  // Re-orders the joints in the command to match the internal joint order.
805 
806  accelerations.resize(msg->points[i].accelerations.size());
807  velocities.resize(msg->points[i].velocities.size());
808  positions.resize(msg->points[i].positions.size());
809  for (size_t j = 0; j < joints_.size(); ++j)
810  {
811  if (!accelerations.empty()) accelerations[j] = msg->points[i].accelerations[lookup[j]];
812  if (!velocities.empty()) velocities[j] = msg->points[i].velocities[lookup[j]];
813  if (!positions.empty()) positions[j] = msg->points[i].positions[lookup[j]] + wrap[j];
814  }
815 
816  // Converts the boundary conditions to splines.
817 
818  for (size_t j = 0; j < joints_.size(); ++j)
819  {
820  if (prev_accelerations.size() > 0 && accelerations.size() > 0)
821  {
823  prev_positions[j], prev_velocities[j], prev_accelerations[j],
824  positions[j], velocities[j], accelerations[j],
825  durations[i],
826  seg.splines[j].coef);
827  }
828  else if (prev_velocities.size() > 0 && velocities.size() > 0)
829  {
831  prev_positions[j], prev_velocities[j],
832  positions[j], velocities[j],
833  durations[i],
834  seg.splines[j].coef);
835  seg.splines[j].coef.resize(6, 0.0);
836  }
837  else
838  {
839  seg.splines[j].coef[0] = prev_positions[j];
840  if (durations[i] == 0.0)
841  seg.splines[j].coef[1] = 0.0;
842  else
843  seg.splines[j].coef[1] = (positions[j] - prev_positions[j]) / durations[i];
844  seg.splines[j].coef[2] = 0.0;
845  seg.splines[j].coef[3] = 0.0;
846  seg.splines[j].coef[4] = 0.0;
847  seg.splines[j].coef[5] = 0.0;
848  }
849  }
850 
851  // Writes the tolerances into the segment
852  seg.trajectory_tolerance = trajectory_tolerance;
853  seg.goal_tolerance = goal_tolerance;
854  seg.goal_time_tolerance = goal_time_tolerance;
855 
856  // Pushes the splines onto the end of the new trajectory.
857 
858  new_traj.push_back(seg);
859 
860  // Computes the starting conditions for the next segment
861 
862  prev_positions = positions;
863  prev_velocities = velocities;
864  prev_accelerations = accelerations;
865  }
866 
867  //ROS_ERROR("Last segment goal id: %s", new_traj[new_traj.size()-1].gh->gh_.getGoalID().id.c_str());
868 
869  // ------ Commits the new trajectory
870 
871  if (!new_traj_ptr)
872  {
873  ROS_ERROR("The new trajectory was null!");
874  return;
875  }
876 
877  current_trajectory_box_.set(new_traj_ptr);
878  ROS_DEBUG("The new trajectory has %d segments", (int)new_traj.size());
879 #if 0
880  for (size_t i = 0; i < std::min((size_t)20,new_traj.size()); ++i)
881  {
882  ROS_DEBUG("Segment %2d: %.3lf for %.3lf", i, new_traj[i].start_time, new_traj[i].duration);
883  for (size_t j = 0; j < new_traj[i].splines.size(); ++j)
884  {
885  ROS_DEBUG(" %.2lf %.2lf %.2lf %.2lf , %.2lf %.2lf(%s)",
886  new_traj[i].splines[j].coef[0],
887  new_traj[i].splines[j].coef[1],
888  new_traj[i].splines[j].coef[2],
889  new_traj[i].splines[j].coef[3],
890  new_traj[i].splines[j].coef[4],
891  new_traj[i].splines[j].coef[5],
892  joints_[j]->joint_->name_.c_str());
893  }
894  }
895 #endif
896 }
897 
899  pr2_controllers_msgs::QueryTrajectoryState::Request &req,
900  pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
901 {
903  current_trajectory_box_.get(traj_ptr);
904  if (!traj_ptr)
905  {
906  ROS_FATAL("The current trajectory can never be null");
907  return false;
908  }
909  const SpecifiedTrajectory &traj = *traj_ptr;
910 
911  // Determines which segment of the trajectory to use
912  int seg = -1;
913  while (seg + 1 < (int)traj.size() &&
914  traj[seg+1].start_time < req.time.toSec())
915  {
916  ++seg;
917  }
918  if (seg == -1)
919  return false;
920 
921  for (size_t i = 0; i < q.size(); ++i)
922  {
923  }
924 
925 
926  resp.name.resize(joints_.size());
927  resp.position.resize(joints_.size());
928  resp.velocity.resize(joints_.size());
929  resp.acceleration.resize(joints_.size());
930  for (size_t j = 0; j < joints_.size(); ++j)
931  {
932  resp.name[j] = joints_[j]->joint_->name;
933  sampleSplineWithTimeBounds(traj[seg].splines[j].coef, traj[seg].duration,
934  req.time.toSec() - traj[seg].start_time,
935  resp.position[j], resp.velocity[j], resp.acceleration[j]);
936  }
937 
938  return true;
939 }
940 
942  const std::vector<double>& coefficients, double duration, double time,
943  double& position, double& velocity, double& acceleration)
944 {
945  if (time < 0)
946  {
947  double _;
948  sampleQuinticSpline(coefficients, 0.0, position, _, _);
949  velocity = 0;
950  acceleration = 0;
951  }
952  else if (time > duration)
953  {
954  double _;
955  sampleQuinticSpline(coefficients, duration, position, _, _);
956  velocity = 0;
957  acceleration = 0;
958  }
959  else
960  {
961  sampleQuinticSpline(coefficients, time,
962  position, velocity, acceleration);
963  }
964 }
965 
966 static bool setsEqual(const std::vector<std::string> &a, const std::vector<std::string> &b)
967 {
968  if (a.size() != b.size())
969  return false;
970 
971  for (size_t i = 0; i < a.size(); ++i)
972  {
973  if (count(b.begin(), b.end(), a[i]) != 1)
974  return false;
975  }
976  for (size_t i = 0; i < b.size(); ++i)
977  {
978  if (count(a.begin(), a.end(), b[i]) != 1)
979  return false;
980  }
981 
982  return true;
983 }
984 
986 {
989 
990  // Cancels the currently active goal.
991  if (current_active_goal)
992  {
993  // Marks the current goal as canceled.
994  rt_active_goal_.reset();
995  current_active_goal->gh_.setCanceled();
996  }
997  if (current_active_goal_follow)
998  {
999  rt_active_goal_follow_.reset();
1000  current_active_goal_follow->gh_.setCanceled();
1001  }
1002 }
1003 
1004 
1005 template <class Enclosure, class Member>
1007 {
1009  boost::shared_ptr<Member> p(&member, d);
1010  return p;
1011 }
1012 
1014 {
1015  std::vector<std::string> joint_names(joints_.size());
1016  for (size_t j = 0; j < joints_.size(); ++j)
1017  joint_names[j] = joints_[j]->joint_->name;
1018 
1019  // Ensures that the joints in the goal match the joints we are commanding.
1020  if (!setsEqual(joint_names, gh.getGoal()->trajectory.joint_names))
1021  {
1022  ROS_ERROR("Joints on incoming goal don't match our joints");
1023  gh.setRejected();
1024  return;
1025  }
1026 
1028 
1029  gh.setAccepted();
1031 
1032  // Sends the trajectory along to the controller
1034  commandTrajectory(share_member(gh.getGoal(), gh.getGoal()->trajectory), rt_gh);
1035  rt_active_goal_ = rt_gh;
1037 }
1038 
1040 {
1041  std::vector<std::string> joint_names(joints_.size());
1042  for (size_t j = 0; j < joints_.size(); ++j)
1043  joint_names[j] = joints_[j]->joint_->name;
1044 
1045  // Ensures that the joints in the goal match the joints we are commanding.
1046  if (!setsEqual(joint_names, gh.getGoal()->trajectory.joint_names))
1047  {
1048  ROS_ERROR("Joints on incoming goal don't match our joints");
1049  control_msgs::FollowJointTrajectoryResult result;
1050  result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
1051  gh.setRejected(result);
1052  return;
1053  }
1054 
1056 
1057  gh.setAccepted();
1059 
1060  // Sends the trajectory along to the controller
1062  commandTrajectory(share_member(gh.getGoal(), gh.getGoal()->trajectory),
1064  rt_gh);
1065  rt_active_goal_follow_ = rt_gh;
1067 }
1068 
1070 {
1071  boost::shared_ptr<RTGoalHandle> current_active_goal(rt_active_goal_);
1072  if (current_active_goal && current_active_goal->gh_ == gh)
1073  {
1074  rt_active_goal_.reset();
1075 
1076  trajectory_msgs::JointTrajectory::Ptr empty(new trajectory_msgs::JointTrajectory);
1077  empty->joint_names.resize(joints_.size());
1078  for (size_t j = 0; j < joints_.size(); ++j)
1079  empty->joint_names[j] = joints_[j]->joint_->name;
1080  commandTrajectory(empty);
1081 
1082  // Marks the current goal as canceled.
1083  current_active_goal->gh_.setCanceled();
1084  }
1085 }
1086 
1088 {
1090  if (current_active_goal && current_active_goal->gh_ == gh)
1091  {
1092  rt_active_goal_follow_.reset();
1093 
1094  trajectory_msgs::JointTrajectory::Ptr empty(new trajectory_msgs::JointTrajectory);
1095  empty->joint_names.resize(joints_.size());
1096  for (size_t j = 0; j < joints_.size(); ++j)
1097  empty->joint_names[j] = joints_[j]->joint_->name;
1098  commandTrajectory(empty);
1099 
1100  // Marks the current goal as canceled.
1101  current_active_goal->gh_.setCanceled();
1102  }
1103 }
1104 }
XmlRpc::XmlRpcValue::size
int size() const
controller::JointTrajectoryActionController::Segment::duration
double duration
Definition: joint_trajectory_action_controller.h:253
pr2_mechanism_model::JointState
angles::shortest_angular_distance
static double shortest_angular_distance(double from, double to)
controller::JointTrajectoryActionController::output_filters_
std::vector< boost::shared_ptr< filters::FilterChain< double > > > output_filters_
Definition: joint_trajectory_action_controller.h:208
actionlib::ServerGoalHandle::getGoal
boost::shared_ptr< const Goal > getGoal() const
msg
msg
controller::JointTrajectoryActionController::pids_
std::vector< control_toolbox::Pid > pids_
Definition: joint_trajectory_action_controller.h:194
controller::JointTrajectoryActionController::rt_active_goal_
boost::shared_ptr< RTGoalHandle > rt_active_goal_
Definition: joint_trajectory_action_controller.h:231
controller::JointTrajectoryActionController::Segment
Definition: joint_trajectory_action_controller.h:250
boost::shared_ptr
controller::JointTrajectoryActionController::init
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: joint_trajectory_action_controller.cpp:158
i
int i
actionlib::ServerGoalHandle
controller::RTServerGoalHandle::runNonRT
void runNonRT(const ros::TimerEvent &te)
Definition: joint_trajectory_action_controller.h:120
controller::JointTrajectoryActionController::FJTAS
actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > FJTAS
Definition: joint_trajectory_action_controller.h:174
controller::JointTrajectoryActionController::Segment::start_time
double start_time
Definition: joint_trajectory_action_controller.h:252
controller::JointTrajectoryActionController::qdd
std::vector< double > qdd
Definition: joint_trajectory_action_controller.h:274
controller::JointTrajectoryActionController::default_goal_time_constraint_
double default_goal_time_constraint_
Definition: joint_trajectory_action_controller.h:200
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
controller::JointTrajectoryActionController::sub_command_
ros::Subscriber sub_command_
Definition: joint_trajectory_action_controller.h:213
controller::share_member
static boost::shared_ptr< Member > share_member(boost::shared_ptr< Enclosure > enclosure, Member &member)
Definition: joint_trajectory_action_controller.cpp:1006
controller::JointTrajectoryActionController::commandCB
void commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
Definition: joint_trajectory_action_controller.cpp:545
realtime_tools::RealtimeBox::get
void get(T &ref)
controller::getCubicSplineCoefficients
static void getCubicSplineCoefficients(double start_pos, double start_vel, double end_pos, double end_vel, double time, std::vector< double > &coefficients)
Definition: joint_spline_trajectory_controller.cpp:119
ROS_DEBUG
#define ROS_DEBUG(...)
TimeBase< Time, Duration >::toSec
double toSec() const
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
controller::JointTrajectoryActionController::proxies_
std::vector< control_toolbox::LimitedProxy > proxies_
Definition: joint_trajectory_action_controller.h:196
XmlRpc
ros::Subscriber::shutdown
void shutdown()
controller::RTServerGoalHandle
Definition: joint_trajectory_action_controller.h:65
controller::JointTrajectoryActionController::RTGoalHandleFollow
RTServerGoalHandle< control_msgs::FollowJointTrajectoryAction > RTGoalHandleFollow
Definition: joint_trajectory_action_controller.h:176
controller::JointTrajectoryActionController::goalCB
void goalCB(GoalHandle gh)
Definition: joint_trajectory_action_controller.cpp:1013
actionlib::ServerGoalHandle::setRejected
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
controller::JointTrajectoryActionController::q
std::vector< double > q
Definition: joint_trajectory_action_controller.h:274
controller::JointTrajectoryActionController::preemptActiveGoal
void preemptActiveGoal()
Definition: joint_trajectory_action_controller.cpp:985
controller::JointTrajectoryActionController::qd
std::vector< double > qd
Definition: joint_trajectory_action_controller.h:274
controller::JointTrajectoryActionController::cancelCB
void cancelCB(GoalHandle gh)
Definition: joint_trajectory_action_controller.cpp:1069
controller::generatePowers
static void generatePowers(int n, double x, double *powers)
Definition: joint_spline_trajectory_controller.cpp:50
filters::FilterChain
controller::JointTrajectoryActionController::queryStateService
bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req, pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
Definition: joint_trajectory_action_controller.cpp:898
controller::JointTrajectoryActionController
Definition: joint_trajectory_action_controller.h:166
realtime_tools::RealtimePublisher
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
joint_trajectory_action_controller.h
controller
effort
Definition: effort.py:1
actionlib::ServerGoalHandle::setAccepted
void setAccepted(const std::string &text=std::string(""))
pr2_mechanism_model::RobotState
controller::JointTrajectoryActionController::goalCBFollow
void goalCBFollow(GoalHandleFollow gh)
Definition: joint_trajectory_action_controller.cpp:1039
k
int k
pr2_mechanism_model::RobotState::getJointState
JointState * getJointState(const std::string &name)
controller::JointTrajectoryActionController::~JointTrajectoryActionController
~JointTrajectoryActionController()
Definition: joint_trajectory_action_controller.cpp:150
controller::JointTrajectoryActionController::masses_
std::vector< double > masses_
Definition: joint_trajectory_action_controller.h:193
ROS_ERROR
#define ROS_ERROR(...)
controller::JointTrajectoryActionController::RTGoalHandle
RTServerGoalHandle< pr2_controllers_msgs::JointTrajectoryAction > RTGoalHandle
Definition: joint_trajectory_action_controller.h:171
controller::JointTrajectoryActionController::goal_handle_timer_
ros::Timer goal_handle_timer_
Definition: joint_trajectory_action_controller.h:229
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
d
d
controller::JointTrajectoryActionController::current_trajectory_box_
realtime_tools::RealtimeBox< boost::shared_ptr< const SpecifiedTrajectory > > current_trajectory_box_
Definition: joint_trajectory_action_controller.h:266
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
controller::JointTrajectoryActionController::update
void update()
Definition: joint_trajectory_action_controller.cpp:340
controller::JointTrajectoryActionController::starting
void starting()
Definition: joint_trajectory_action_controller.cpp:319
controller::JointTrajectoryActionController::node_
ros::NodeHandle node_
Definition: joint_trajectory_action_controller.h:210
controller::getQuinticSplineCoefficients
static void getQuinticSplineCoefficients(double start_pos, double start_vel, double start_acc, double end_pos, double end_vel, double end_acc, double time, std::vector< double > &coefficients)
Definition: joint_spline_trajectory_controller.cpp:59
controller::JointTrajectoryActionController::default_goal_tolerance_
std::vector< JointTolerance > default_goal_tolerance_
Definition: joint_trajectory_action_controller.h:199
controller::JointTrajectoryActionController::action_server_follow_
boost::scoped_ptr< FJTAS > action_server_follow_
Definition: joint_trajectory_action_controller.h:224
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_FATAL
#define ROS_FATAL(...)
controller::JointTrajectoryActionController::SpecifiedTrajectory
std::vector< Segment > SpecifiedTrajectory
Definition: joint_trajectory_action_controller.h:263
pr2_controller_interface::Controller
controller::JointTrajectoryActionController::loop_count_
int loop_count_
Definition: joint_trajectory_action_controller.h:189
XmlRpc::XmlRpcValue::TypeArray
TypeArray
controller::JointTrajectoryActionController::Segment::splines
std::vector< Spline > splines
Definition: joint_trajectory_action_controller.h:254
controller::setsEqual
static bool setsEqual(const std::vector< std::string > &a, const std::vector< std::string > &b)
Definition: joint_trajectory_action_controller.cpp:966
controller::JointTrajectoryActionController::proxies_enabled_
std::vector< bool > proxies_enabled_
Definition: joint_trajectory_action_controller.h:195
controller::JointTrajectoryActionController::default_trajectory_tolerance_
std::vector< JointTolerance > default_trajectory_tolerance_
Definition: joint_trajectory_action_controller.h:198
controller::JointTrajectoryActionController::rt_active_goal_follow_
boost::shared_ptr< RTGoalHandleFollow > rt_active_goal_follow_
Definition: joint_trajectory_action_controller.h:232
controller::JointTrajectoryActionController::Segment::gh
boost::shared_ptr< RTGoalHandle > gh
Definition: joint_trajectory_action_controller.h:260
pr2_mechanism_model::RobotState::getTime
ros::Time getTime()
controller::JointTrajectoryActionController::sampleSplineWithTimeBounds
static void sampleSplineWithTimeBounds(const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration)
Definition: joint_trajectory_action_controller.cpp:941
ros::Time
controller::JointTrajectoryActionController::robot_
pr2_mechanism_model::RobotState * robot_
Definition: joint_trajectory_action_controller.h:190
controller::JointTrajectoryActionController::cancelCBFollow
void cancelCBFollow(GoalHandleFollow gh)
Definition: joint_trajectory_action_controller.cpp:1087
controller::JointTrajectoryActionController::Segment::gh_follow
boost::shared_ptr< RTGoalHandleFollow > gh_follow
Definition: joint_trajectory_action_controller.h:261
controller::sampleQuinticSpline
static void sampleQuinticSpline(const std::vector< double > &coefficients, double time, double &position, double &velocity, double &acceleration)
Samples a quintic spline segment at a particular time.
Definition: joint_spline_trajectory_controller.cpp:93
controller::JointTrajectoryActionController::joints_
std::vector< pr2_mechanism_model::JointState * > joints_
Definition: joint_trajectory_action_controller.h:192
class_list_macros.hpp
controller::JointTrajectoryActionController::Segment::goal_time_tolerance
double goal_time_tolerance
Definition: joint_trajectory_action_controller.h:258
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
controller::JointTrajectoryActionController::last_time_
ros::Time last_time_
Definition: joint_trajectory_action_controller.h:191
if
if((endptr==val_str)||(endptr<(val_str+strlen(val_str))))
controller::JointTrajectoryActionController::action_server_
boost::scoped_ptr< JTAS > action_server_
Definition: joint_trajectory_action_controller.h:223
controller::JointTrajectoryActionController::Segment::trajectory_tolerance
std::vector< JointTolerance > trajectory_tolerance
Definition: joint_trajectory_action_controller.h:256
ros::ServiceServer::shutdown
void shutdown()
actionlib::EnclosureDeleter
controller::JointTrajectoryActionController::JointTrajectoryActionController
JointTrajectoryActionController()
Definition: joint_trajectory_action_controller.cpp:145
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
DurationBase< Duration >::toSec
double toSec() const
controller::JointTrajectoryActionController::controller_state_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointTrajectoryControllerState > > controller_state_publisher_
Definition: joint_trajectory_action_controller.h:221
controller::JointTrajectoryActionController::JTAS
actionlib::ActionServer< pr2_controllers_msgs::JointTrajectoryAction > JTAS
Definition: joint_trajectory_action_controller.h:169
ros::Timer::start
void start()
realtime_tools::RealtimeBox::set
void set(const T &value)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
XmlRpc::XmlRpcValue
ros::NodeHandle
angles.h
controller::JointTrajectoryActionController::commandTrajectory
void commandTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &traj, boost::shared_ptr< RTGoalHandle > gh=boost::shared_ptr< RTGoalHandle >((RTGoalHandle *) NULL), boost::shared_ptr< RTGoalHandleFollow > gh_follow=boost::shared_ptr< RTGoalHandleFollow >((RTGoalHandleFollow *) NULL))
Definition: joint_trajectory_action_controller.cpp:551
controller::JointTrajectoryActionController::serve_query_state_
ros::ServiceServer serve_query_state_
Definition: joint_trajectory_action_controller.h:217
error
def error(*args, **kwargs)
controller::JointTrajectoryActionController::Segment::goal_tolerance
std::vector< JointTolerance > goal_tolerance
Definition: joint_trajectory_action_controller.h:257


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:22