joint_trajectory_controller_impl.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 // Copyright (c) 2008, Willow Garage, Inc.
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 // * Redistributions of source code must retain the above copyright notice,
8 // this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of PAL Robotics S.L. nor the names of its
13 // contributors may be used to endorse or promote products derived from
14 // this software without specific prior written permission.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 // POSSIBILITY OF SUCH DAMAGE.
28 
30 
31 #pragma once
32 
33 
35 {
36 
37 namespace internal
38 {
39 
40 template <class Enclosure, class Member>
42 {
44  boost::shared_ptr<Member> p(&member, d);
45  return p;
46 }
47 
48 std::vector<std::string> getStrings(const ros::NodeHandle& nh, const std::string& param_name)
49 {
50  using namespace XmlRpc;
51  XmlRpcValue xml_array;
52  if (!nh.getParam(param_name, xml_array))
53  {
54  ROS_ERROR_STREAM("Could not find '" << param_name << "' parameter (namespace: " << nh.getNamespace() << ").");
55  return std::vector<std::string>();
56  }
57  if (xml_array.getType() != XmlRpcValue::TypeArray)
58  {
59  ROS_ERROR_STREAM("The '" << param_name << "' parameter is not an array (namespace: " <<
60  nh.getNamespace() << ").");
61  return std::vector<std::string>();
62  }
63 
64  std::vector<std::string> out;
65  for (int i = 0; i < xml_array.size(); ++i)
66  {
67  XmlRpc::XmlRpcValue& elem = xml_array[i];
68  if (elem.getType() != XmlRpcValue::TypeString)
69  {
70  ROS_ERROR_STREAM("The '" << param_name << "' parameter contains a non-string element (namespace: " <<
71  nh.getNamespace() << ").");
72  return std::vector<std::string>();
73  }
74  out.push_back(static_cast<std::string>(elem));
75  }
76  return out;
77 }
78 
79 urdf::ModelSharedPtr getUrdf(const ros::NodeHandle& nh, const std::string& param_name)
80 {
81  urdf::ModelSharedPtr urdf(new urdf::Model);
82 
83  std::string urdf_str;
84  // Check for robot_description in proper namespace
85  if (nh.getParam(param_name, urdf_str))
86  {
87  if (!urdf->initString(urdf_str))
88  {
89  ROS_ERROR_STREAM("Failed to parse URDF contained in '" << param_name << "' parameter (namespace: " <<
90  nh.getNamespace() << ").");
91  return urdf::ModelSharedPtr();
92  }
93  }
94  // Check for robot_description in root
95  else if (!urdf->initParam("robot_description"))
96  {
97  ROS_ERROR_STREAM("Failed to parse URDF contained in '" << param_name << "' parameter");
98  return urdf::ModelSharedPtr();
99  }
100  return urdf;
101 }
102 
103 std::vector<urdf::JointConstSharedPtr> getUrdfJoints(const urdf::Model& urdf, const std::vector<std::string>& joint_names)
104 {
105  std::vector<urdf::JointConstSharedPtr> out;
106  for (const auto& joint_name : joint_names)
107  {
108  urdf::JointConstSharedPtr urdf_joint = urdf.getJoint(joint_name);
109  if (urdf_joint)
110  {
111  out.push_back(urdf_joint);
112  }
113  else
114  {
115  ROS_ERROR_STREAM("Could not find joint '" << joint_name << "' in URDF model.");
116  return std::vector<urdf::JointConstSharedPtr>();
117  }
118  }
119  return out;
120 }
121 
122 std::string getLeafNamespace(const ros::NodeHandle& nh)
123 {
124  const std::string complete_ns = nh.getNamespace();
125  std::size_t id = complete_ns.find_last_of("/");
126  return complete_ns.substr(id + 1);
127 }
128 
129 } // namespace
130 
131 template <class SegmentImpl, class HardwareInterface>
133 starting(const ros::Time& time)
134 {
135  // Update time data
136  TimeData time_data;
137  time_data.time = time;
138  time_data.uptime = ros::Time(0.0);
139  time_data_.initRT(time_data);
140 
141  // Initialize the desired_state with the current state on startup
142  for (unsigned int i = 0; i < getNumberOfJoints(); ++i)
143  {
144  desired_state_.position[i] = joints_[i].getPosition();
145  desired_state_.velocity[i] = joints_[i].getVelocity();
146  }
147 
148  // Hold current position
149  setHoldPosition(time_data.uptime);
150 
151  // Initialize last state update time
152  last_state_publish_time_ = time_data.uptime;
153 
154  // Hardware interface adapter
155  hw_iface_adapter_.starting(time_data.uptime);
156 }
157 
158 template <class SegmentImpl, class HardwareInterface>
160 stopping(const ros::Time& /*time*/)
161 {
162  preemptActiveGoal();
163 }
164 
165 template <class SegmentImpl, class HardwareInterface>
168 {
169  const bool update_ok = updateTrajectoryCommand(msg, RealtimeGoalHandlePtr());
170  if (update_ok) {preemptActiveGoal();}
171 }
172 
173 template <class SegmentImpl, class HardwareInterface>
176 {
177  RealtimeGoalHandlePtr current_active_goal(rt_active_goal_);
178 
179  // Cancels the currently active goal
180  if (current_active_goal)
181  {
182  // Marks the current goal as canceled
183  rt_active_goal_.reset();
184  current_active_goal->gh_.setCanceled();
185  }
186 }
187 
188 template <class SegmentImpl, class HardwareInterface>
191  : verbose_(false) // Set to true during debugging
192 {
193  // The verbose parameter is for advanced use as it breaks real-time safety
194  // by enabling ROS logging services
195  if (verbose_)
196  {
198  "The joint_trajectory_controller verbose flag is enabled. "
199  << "This flag breaks real-time safety and should only be "
200  << "used for debugging");
201  }
202 }
203 
204 template <class SegmentImpl, class HardwareInterface>
206  ros::NodeHandle& root_nh,
207  ros::NodeHandle& controller_nh)
208 {
209  using namespace internal;
210 
211  // Cache controller node handle
212  controller_nh_ = controller_nh;
213 
214  // Controller name
215  name_ = getLeafNamespace(controller_nh_);
216 
217  // State publish rate
218  double state_publish_rate = 50.0;
219  controller_nh_.getParam("state_publish_rate", state_publish_rate);
220  ROS_DEBUG_STREAM_NAMED(name_, "Controller state will be published at " << state_publish_rate << "Hz.");
221  state_publisher_period_ = ros::Duration(1.0 / state_publish_rate);
222 
223  // Action status checking update rate
224  double action_monitor_rate = 20.0;
225  controller_nh_.getParam("action_monitor_rate", action_monitor_rate);
226  action_monitor_period_ = ros::Duration(1.0 / action_monitor_rate);
227  ROS_DEBUG_STREAM_NAMED(name_, "Action status changes will be monitored at " << action_monitor_rate << "Hz.");
228 
229  // Stop trajectory duration
230  stop_trajectory_duration_ = 0.0;
231  controller_nh_.getParam("stop_trajectory_duration", stop_trajectory_duration_);
232  ROS_DEBUG_STREAM_NAMED(name_, "Stop trajectory has a duration of " << stop_trajectory_duration_ << "s.");
233 
234  // Checking if partial trajectories are allowed
235  controller_nh_.param<bool>("allow_partial_joints_goal", allow_partial_joints_goal_, false);
236  if (allow_partial_joints_goal_)
237  {
238  ROS_DEBUG_NAMED(name_, "Goals with partial set of joints are allowed");
239  }
240 
241  // List of controlled joints
242  joint_names_ = getStrings(controller_nh_, "joints");
243  if (joint_names_.empty()) {return false;}
244  const unsigned int n_joints = joint_names_.size();
245 
246  // URDF joints
247  urdf::ModelSharedPtr urdf = getUrdf(root_nh, "robot_description");
248  if (!urdf) {return false;}
249 
250  std::vector<urdf::JointConstSharedPtr> urdf_joints = getUrdfJoints(*urdf, joint_names_);
251  if (urdf_joints.empty()) {return false;}
252  assert(n_joints == urdf_joints.size());
253 
254  // Initialize members
255  joints_.resize(n_joints);
256  angle_wraparound_.resize(n_joints);
257  for (unsigned int i = 0; i < n_joints; ++i)
258  {
259  // Joint handle
260  try {joints_[i] = hw->getHandle(joint_names_[i]);}
261  catch (...)
262  {
263  ROS_ERROR_STREAM_NAMED(name_, "Could not find joint '" << joint_names_[i] << "' in '" <<
264  this->getHardwareInterfaceType() << "'.");
265  return false;
266  }
267 
268  // Whether a joint is continuous (ie. has angle wraparound)
269  angle_wraparound_[i] = urdf_joints[i]->type == urdf::Joint::CONTINUOUS;
270  const std::string not_if = angle_wraparound_[i] ? "" : "non-";
271 
272  ROS_DEBUG_STREAM_NAMED(name_, "Found " << not_if << "continuous joint '" << joint_names_[i] << "' in '" <<
273  this->getHardwareInterfaceType() << "'.");
274  }
275 
276  assert(joints_.size() == angle_wraparound_.size());
277  ROS_DEBUG_STREAM_NAMED(name_, "Initialized controller '" << name_ << "' with:" <<
278  "\n- Number of joints: " << getNumberOfJoints() <<
279  "\n- Hardware interface type: '" << this->getHardwareInterfaceType() << "'" <<
280  "\n- Trajectory segment type: '" << hardware_interface::internal::demangledTypeName<SegmentImpl>() << "'");
281 
282  // Default tolerances
283  ros::NodeHandle tol_nh(controller_nh_, "constraints");
284  default_tolerances_ = getSegmentTolerances<Scalar>(tol_nh, joint_names_);
285 
286  // Hardware interface adapter
287  hw_iface_adapter_.init(joints_, controller_nh_);
288 
289  // ROS API: Subscribed topics
290  trajectory_command_sub_ = controller_nh_.subscribe("command", 1, &JointTrajectoryController::trajectoryCommandCB, this);
291 
292  // ROS API: Published topics
293  state_publisher_.reset(new StatePublisher(controller_nh_, "state", 1));
294 
295  // ROS API: Action interface
296  action_server_.reset(
297  new ActionServer(controller_nh_, "follow_joint_trajectory",
298  std::bind(&JointTrajectoryController::goalCB, this, std::placeholders::_1),
299  std::bind(&JointTrajectoryController::cancelCB, this, std::placeholders::_1), false));
300  action_server_->start();
301 
302  // ROS API: Provided services
303  query_state_service_ = controller_nh_.advertiseService("query_state",
305  this);
306 
307  // Preeallocate resources
308  current_state_ = typename Segment::State(n_joints);
309  old_desired_state_ = typename Segment::State(n_joints);
310  desired_state_ = typename Segment::State(n_joints);
311  state_error_ = typename Segment::State(n_joints);
312  desired_joint_state_ = typename Segment::State(1);
313  state_joint_error_ = typename Segment::State(1);
314 
315  successful_joint_traj_ = boost::dynamic_bitset<>(getNumberOfJoints());
316 
317  hold_trajectory_ptr_ = createHoldTrajectory(n_joints);
318  assert(joint_names_.size() == hold_trajectory_ptr_->size());
319 
320  if (stop_trajectory_duration_ == 0.0)
321  {
322  hold_traj_builder_ = std::unique_ptr<TrajectoryBuilder<SegmentImpl> >(new HoldTrajectoryBuilder<SegmentImpl, HardwareInterface>(joints_));
323  }
324  else
325  {
326  hold_traj_builder_ = std::unique_ptr<TrajectoryBuilder<SegmentImpl> >(new StopTrajectoryBuilder<SegmentImpl>(stop_trajectory_duration_, desired_state_));
327  }
328 
329  {
330  state_publisher_->lock();
331  state_publisher_->msg_.joint_names = joint_names_;
332  state_publisher_->msg_.desired.positions.resize(n_joints);
333  state_publisher_->msg_.desired.velocities.resize(n_joints);
334  state_publisher_->msg_.desired.accelerations.resize(n_joints);
335  state_publisher_->msg_.actual.positions.resize(n_joints);
336  state_publisher_->msg_.actual.velocities.resize(n_joints);
337  state_publisher_->msg_.error.positions.resize(n_joints);
338  state_publisher_->msg_.error.velocities.resize(n_joints);
339  state_publisher_->unlock();
340  }
341 
342  return true;
343 }
344 
345 template <class SegmentImpl, class HardwareInterface>
347 update(const ros::Time& time, const ros::Duration& period)
348 {
349  // Get currently followed trajectory
350  TrajectoryPtr curr_traj_ptr;
351  curr_trajectory_box_.get(curr_traj_ptr);
352  Trajectory& curr_traj = *curr_traj_ptr;
353 
354  old_time_data_ = *(time_data_.readFromRT());
355 
356  // Update time data
357  TimeData time_data;
358  time_data.time = time; // Cache current time
359  time_data.period = period; // Cache current control period
360  time_data.uptime = old_time_data_.uptime + period; // Update controller uptime
361  time_data_.writeFromNonRT(time_data); // TODO: Grrr, we need a lock-free data structure here!
362 
363  // NOTE: It is very important to execute the two above code blocks in the specified sequence: first get current
364  // trajectory, then update time data. Hopefully the following paragraph sheds a bit of light on the rationale.
365  // The non-rt thread responsible for processing new commands enqueues trajectories that can start at the _next_
366  // control cycle (eg. zero start time) or later (eg. when we explicitly request a start time in the future).
367  // If we reverse the order of the two blocks above, and update the time data first; it's possible that by the time we
368  // fetch the currently followed trajectory, it has been updated by the non-rt thread with something that starts in the
369  // next control cycle, leaving the current cycle without a valid trajectory.
370 
371  updateStates(time_data.uptime, curr_traj_ptr.get());
372 
373  // Update current state and state error
374  for (unsigned int i = 0; i < getNumberOfJoints(); ++i)
375  {
376  typename TrajectoryPerJoint::const_iterator segment_it = sample(curr_traj[i], time_data.uptime.toSec(), desired_joint_state_);
377  if (curr_traj[i].end() == segment_it)
378  {
379  // Non-realtime safe, but should never happen under normal operation
380  ROS_ERROR_NAMED(name_,
381  "Unexpected error: No trajectory defined at current time. Please contact the package maintainer.");
382  return;
383  }
384 
385  // Get state error for current joint
386  state_joint_error_.position[0] = state_error_.position[i];
387  state_joint_error_.velocity[0] = state_error_.velocity[i];
388  state_joint_error_.acceleration[0] = state_error_.acceleration[i];
389 
390  //Check tolerances
391  const RealtimeGoalHandlePtr rt_segment_goal = segment_it->getGoalHandle();
392  if (rt_segment_goal && rt_segment_goal == rt_active_goal_)
393  {
394  // Check tolerances
395  if (time_data.uptime.toSec() < segment_it->endTime())
396  {
397  // Currently executing a segment: check path tolerances
398  const SegmentTolerancesPerJoint<Scalar>& joint_tolerances = segment_it->getTolerances();
399  if (!checkStateTolerancePerJoint(state_joint_error_, joint_tolerances.state_tolerance))
400  {
401  if (verbose_)
402  {
403  ROS_ERROR_STREAM_NAMED(name_,"Path tolerances failed for joint: " << joint_names_[i]);
404  checkStateTolerancePerJoint(state_joint_error_, joint_tolerances.state_tolerance, true);
405  }
406  rt_segment_goal->preallocated_result_->error_code =
407  control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
408  rt_segment_goal->preallocated_result_->error_string = joint_names_[i] + " path error " + std::to_string( state_joint_error_.position[0] );
409  rt_segment_goal->setAborted(rt_segment_goal->preallocated_result_);
410  // Force this to run before destroying rt_active_goal_ so results message is returned
411  rt_active_goal_->runNonRealtime(ros::TimerEvent());
412  rt_active_goal_.reset();
413  successful_joint_traj_.reset();
414  }
415  }
416  else if (segment_it == --curr_traj[i].end())
417  {
418  if (verbose_)
419  ROS_DEBUG_STREAM_THROTTLE_NAMED(1,name_,"Finished executing last segment, checking goal tolerances");
420 
421  // Controller uptime
422  const ros::Time uptime = time_data_.readFromRT()->uptime;
423 
424  // Checks that we have ended inside the goal tolerances
425  const SegmentTolerancesPerJoint<Scalar>& tolerances = segment_it->getTolerances();
426  const bool inside_goal_tolerances = checkStateTolerancePerJoint(state_joint_error_, tolerances.goal_state_tolerance);
427 
428  if (inside_goal_tolerances)
429  {
430  successful_joint_traj_[i] = 1;
431  }
432  else if (uptime.toSec() < segment_it->endTime() + tolerances.goal_time_tolerance)
433  {
434  // Still have some time left to meet the goal state tolerances
435  }
436  else
437  {
438  if (verbose_)
439  {
440  ROS_ERROR_STREAM_NAMED(name_,"Goal tolerances failed for joint: "<< joint_names_[i]);
441  // Check the tolerances one more time to output the errors that occurs
442  checkStateTolerancePerJoint(state_joint_error_, tolerances.goal_state_tolerance, true);
443  }
444 
445  rt_segment_goal->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED;
446  rt_segment_goal->preallocated_result_->error_string = joint_names_[i] + " goal error " + std::to_string( state_joint_error_.position[0] );
447  rt_segment_goal->setAborted(rt_segment_goal->preallocated_result_);
448  // Force this to run before destroying rt_active_goal_ so results message is returned
449  rt_active_goal_->runNonRealtime(ros::TimerEvent());
450  rt_active_goal_.reset();
451  successful_joint_traj_.reset();
452  }
453  }
454  }
455  }
456 
457  //If there is an active goal and all segments finished successfully then set goal as succeeded
458  RealtimeGoalHandlePtr current_active_goal(rt_active_goal_);
459  if (current_active_goal && successful_joint_traj_.count() == getNumberOfJoints())
460  {
461  current_active_goal->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::SUCCESSFUL;
462  current_active_goal->setSucceeded(current_active_goal->preallocated_result_);
463  current_active_goal.reset(); // do not publish feedback
464  rt_active_goal_.reset();
465  successful_joint_traj_.reset();
466  }
467 
468  updateFuncExtensionPoint(curr_traj, time_data);
469 
470  // Hardware interface adapter: Generate and send commands
471  hw_iface_adapter_.updateCommand(time_data.uptime, time_data.period,
472  desired_state_, state_error_);
473 
474  setActionFeedback();
475 
476  publishState(time_data.uptime);
477 }
478 
479 template <class SegmentImpl, class HardwareInterface>
482 {
484  Options options;
485  options.error_string = error_string;
486  std::string error_string_tmp;
487 
488  // Preconditions
489  if (!this->isRunning())
490  {
491  error_string_tmp = "Can't accept new commands. Controller is not running.";
492  ROS_ERROR_STREAM_NAMED(name_, error_string_tmp);
493  options.setErrorString(error_string_tmp);
494  return false;
495  }
496 
497  if (!msg)
498  {
499  error_string_tmp = "Received null-pointer trajectory message, skipping.";
500  ROS_WARN_STREAM_NAMED(name_, error_string_tmp);
501  options.setErrorString(error_string_tmp);
502  return false;
503  }
504 
505  // Time data
506  TimeData* time_data = time_data_.readFromRT(); // TODO: Grrr, we need a lock-free data structure here!
507 
508  // Time of the next update
509  const ros::Time next_update_time = time_data->time + time_data->period;
510 
511  // Uptime of the next update
512  ros::Time next_update_uptime = time_data->uptime + time_data->period;
513 
514  // Hold current position if trajectory is empty
515  if (msg->points.empty())
516  {
517  setHoldPosition(time_data->uptime, gh);
518  ROS_DEBUG_NAMED(name_, "Empty trajectory command, stopping.");
519  return true;
520  }
521 
522  // Trajectory initialization options
523  TrajectoryPtr curr_traj_ptr;
524  curr_trajectory_box_.get(curr_traj_ptr);
525 
526  options.other_time_base = &next_update_uptime;
527  options.current_trajectory = curr_traj_ptr.get();
528  options.joint_names = &joint_names_;
529  options.angle_wraparound = &angle_wraparound_;
530  options.rt_goal_handle = gh;
531  options.default_tolerances = &default_tolerances_;
532  options.allow_partial_joints_goal = allow_partial_joints_goal_;
533 
534  // Update currently executing trajectory
535  try
536  {
537  TrajectoryPtr traj_ptr(new Trajectory);
538  *traj_ptr = initJointTrajectory<Trajectory>(*msg, next_update_time, options);
539  if (!traj_ptr->empty())
540  {
541  curr_trajectory_box_.set(traj_ptr);
542  }
543  else
544  {
545  return false;
546  }
547  }
548  catch(const std::exception& ex)
549  {
550  ROS_ERROR_STREAM_NAMED(name_, ex.what());
551  options.setErrorString(ex.what());
552  return false;
553  }
554  catch(...)
555  {
556  error_string_tmp = "Unexpected exception caught when initializing trajectory from ROS message data.";
557  ROS_ERROR_STREAM_NAMED(name_, error_string_tmp);
558  options.setErrorString(error_string_tmp);
559  return false;
560  }
561 
562  return true;
563 }
564 
565 template <class SegmentImpl, class HardwareInterface>
568 {
569  ROS_DEBUG_STREAM_NAMED(name_,"Received new action goal");
570 
571  // Precondition: Running controller
572  if (!this->isRunning())
573  {
574  ROS_ERROR_NAMED(name_, "Can't accept new action goals. Controller is not running.");
575  control_msgs::FollowJointTrajectoryResult result;
576  result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_GOAL; // TODO: Add better error status to msg?
577  gh.setRejected(result);
578  return;
579  }
580 
581  // If partial joints goals are not allowed, goal should specify all controller joints
582  if (!allow_partial_joints_goal_)
583  {
584  if (gh.getGoal()->trajectory.joint_names.size() != joint_names_.size())
585  {
586  ROS_ERROR_NAMED(name_, "Joints on incoming goal don't match the controller joints.");
587  control_msgs::FollowJointTrajectoryResult result;
588  result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
589  gh.setRejected(result);
590  return;
591  }
592  }
593 
594  // Goal should specify valid controller joints (they can be ordered differently). Reject if this is not the case
595  using internal::mapping;
596  std::vector<unsigned int> mapping_vector = mapping(gh.getGoal()->trajectory.joint_names, joint_names_);
597 
598  if (mapping_vector.empty())
599  {
600  ROS_ERROR_NAMED(name_, "Joints on incoming goal don't match the controller joints.");
601  control_msgs::FollowJointTrajectoryResult result;
602  result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
603  gh.setRejected(result);
604  return;
605  }
606 
607  // Try to update new trajectory
608  RealtimeGoalHandlePtr rt_goal(new RealtimeGoalHandle(gh));
609  std::string error_string;
610  const bool update_ok = updateTrajectoryCommand(internal::share_member(gh.getGoal(), gh.getGoal()->trajectory),
611  rt_goal,
612  &error_string);
613  rt_goal->preallocated_feedback_->joint_names = joint_names_;
614 
615  if (update_ok)
616  {
617  // Accept new goal
618  preemptActiveGoal();
619  gh.setAccepted();
620  rt_active_goal_ = rt_goal;
621 
622  // Setup goal status checking timer
623  goal_handle_timer_ = controller_nh_.createTimer(action_monitor_period_,
624  &RealtimeGoalHandle::runNonRealtime,
625  rt_goal);
626  goal_handle_timer_.start();
627  }
628  else
629  {
630  // Reject invalid goal
631  control_msgs::FollowJointTrajectoryResult result;
632  result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_GOAL;
633  result.error_string = error_string;
634  gh.setRejected(result);
635  }
636 }
637 
638 template <class SegmentImpl, class HardwareInterface>
641 {
642  RealtimeGoalHandlePtr current_active_goal(rt_active_goal_);
643 
644  // Check that cancel request refers to currently active goal (if any)
645  if (current_active_goal && current_active_goal->gh_ == gh)
646  {
647  // Reset current goal
648  rt_active_goal_.reset();
649 
650  // Controller uptime
651  const ros::Time uptime = time_data_.readFromRT()->uptime;
652 
653  // Enter hold current position mode
654  setHoldPosition(uptime);
655  ROS_DEBUG_NAMED(name_, "Canceling active action goal because cancel callback recieved from actionlib.");
656 
657  // Mark the current goal as canceled
658  current_active_goal->gh_.setCanceled();
659  }
660 }
661 
662 template <class SegmentImpl, class HardwareInterface>
664 queryStateService(control_msgs::QueryTrajectoryState::Request& req,
665  control_msgs::QueryTrajectoryState::Response& resp)
666 {
667  // Preconditions
668  if (!this->isRunning())
669  {
670  ROS_ERROR_NAMED(name_, "Can't sample trajectory. Controller is not running.");
671  return false;
672  }
673 
674  // Convert request time to internal monotonic representation
675  TimeData* time_data = time_data_.readFromRT();
676  const ros::Duration time_offset = req.time - time_data->time;
677  const ros::Time sample_time = time_data->uptime + time_offset;
678 
679  // Sample trajectory at requested time
680  TrajectoryPtr curr_traj_ptr;
681  curr_trajectory_box_.get(curr_traj_ptr);
682  Trajectory& curr_traj = *curr_traj_ptr;
683 
684  typename Segment::State response_point = typename Segment::State(joint_names_.size());
685 
686  for (unsigned int i = 0; i < getNumberOfJoints(); ++i)
687  {
688  typename Segment::State state;
689  typename TrajectoryPerJoint::const_iterator segment_it = sample(curr_traj[i], sample_time.toSec(), state);
690  if (curr_traj[i].end() == segment_it)
691  {
692  ROS_ERROR_STREAM_NAMED(name_, "Requested sample time precedes trajectory start time.");
693  return false;
694  }
695 
696  response_point.position[i] = state.position[0];
697  response_point.velocity[i] = state.velocity[0];
698  response_point.acceleration[i] = state.acceleration[0];
699  }
700 
701  // Populate response
702  resp.name = joint_names_;
703  resp.position = response_point.position;
704  resp.velocity = response_point.velocity;
705  resp.acceleration = response_point.acceleration;
706 
707  return true;
708 }
709 
710 template <class SegmentImpl, class HardwareInterface>
713 {
714  // Check if it's time to publish
715  if (!state_publisher_period_.isZero() && last_state_publish_time_ + state_publisher_period_ < time)
716  {
717  if (state_publisher_ && state_publisher_->trylock())
718  {
719  last_state_publish_time_ += state_publisher_period_;
720 
721  state_publisher_->msg_.header.stamp = time_data_.readFromRT()->time;
722  state_publisher_->msg_.desired.positions = desired_state_.position;
723  state_publisher_->msg_.desired.velocities = desired_state_.velocity;
724  state_publisher_->msg_.desired.accelerations = desired_state_.acceleration;
725  state_publisher_->msg_.desired.time_from_start = ros::Duration(desired_state_.time_from_start);
726  state_publisher_->msg_.actual.positions = current_state_.position;
727  state_publisher_->msg_.actual.velocities = current_state_.velocity;
728  state_publisher_->msg_.actual.time_from_start = ros::Duration(current_state_.time_from_start);
729  state_publisher_->msg_.error.positions = state_error_.position;
730  state_publisher_->msg_.error.velocities = state_error_.velocity;
731  state_publisher_->msg_.error.time_from_start = ros::Duration(state_error_.time_from_start);
732 
733  state_publisher_->unlockAndPublish();
734  }
735  }
736 }
737 
738 template <class SegmentImpl, class HardwareInterface>
741 {
742  hold_traj_builder_
743  ->setStartTime(time.toSec())
744  ->setGoalHandle(gh)
745  ->buildTrajectory(hold_trajectory_ptr_.get());
746  hold_traj_builder_->reset();
747  curr_trajectory_box_.set(hold_trajectory_ptr_);
748 }
749 
750 template <class SegmentImpl, class HardwareInterface>
752 updateFuncExtensionPoint(const Trajectory& curr_traj, const TimeData& time_data)
753 {
754  // To be implemented by derived class
755 }
756 
757 template <class SegmentImpl, class HardwareInterface>
760 {
761  return joints_.size();
762 }
763 
764 template <class SegmentImpl, class HardwareInterface>
766 updateStates(const ros::Time& sample_time, const Trajectory* const traj)
767 {
768  old_desired_state_ = desired_state_;
769 
770  for (unsigned int joint_index = 0; joint_index < getNumberOfJoints(); ++joint_index)
771  {
772  const auto segment = sample( (*traj)[joint_index], sample_time.toSec(), desired_joint_state_);
773 
774  current_state_.position[joint_index] = joints_[joint_index].getPosition();
775  current_state_.velocity[joint_index] = joints_[joint_index].getVelocity();
776  // There's no acceleration data available in a joint handle
777 
778  desired_state_.position[joint_index] = desired_joint_state_.position[0];
779  desired_state_.velocity[joint_index] = desired_joint_state_.velocity[0];
780  desired_state_.acceleration[joint_index] = desired_joint_state_.acceleration[0];
781 
782  state_error_.position[joint_index] = angles::shortest_angular_distance(current_state_.position[joint_index],desired_joint_state_.position[0]);
783  state_error_.velocity[joint_index] = desired_joint_state_.velocity[0] - current_state_.velocity[joint_index];
784  state_error_.acceleration[joint_index] = 0.0;
785 
786  if (joint_index == 0)
787  {
788  const auto time_from_start = segment->timeFromStart();
789  current_state_.time_from_start = sample_time.toSec() - segment->startTime() + time_from_start;
790  desired_state_.time_from_start = time_from_start;
791  state_error_.time_from_start = desired_state_.time_from_start - current_state_.time_from_start;
792  }
793  }
794 }
795 
796 template <class SegmentImpl, class HardwareInterface>
799 {
800  RealtimeGoalHandlePtr current_active_goal(rt_active_goal_);
801  if (!current_active_goal)
802  {
803  return;
804  }
805 
806  current_active_goal->preallocated_feedback_->header.stamp = time_data_.readFromRT()->time;
807  current_active_goal->preallocated_feedback_->desired.positions = desired_state_.position;
808  current_active_goal->preallocated_feedback_->desired.velocities = desired_state_.velocity;
809  current_active_goal->preallocated_feedback_->desired.accelerations = desired_state_.acceleration;
810  current_active_goal->preallocated_feedback_->desired.time_from_start = ros::Duration(desired_state_.time_from_start);
811  current_active_goal->preallocated_feedback_->actual.positions = current_state_.position;
812  current_active_goal->preallocated_feedback_->actual.velocities = current_state_.velocity;
813  current_active_goal->preallocated_feedback_->actual.time_from_start = ros::Duration(current_state_.time_from_start);
814  current_active_goal->preallocated_feedback_->error.positions = state_error_.position;
815  current_active_goal->preallocated_feedback_->error.velocities = state_error_.velocity;
816  current_active_goal->preallocated_feedback_->error.time_from_start = ros::Duration(state_error_.time_from_start);
817  current_active_goal->setFeedback( current_active_goal->preallocated_feedback_ );
818 
819 }
820 
821 template <class SegmentImpl, class HardwareInterface>
824 {
825  TrajectoryPtr hold_traj {new Trajectory()};
826 
827  typename Segment::State default_state = typename Segment::State(number_of_joints);
828  typename Segment::State default_joint_state = typename Segment::State(1);
829  for (unsigned int i = 0; i < number_of_joints; ++i)
830  {
831  default_joint_state.position[0]= default_state.position[i];
832  default_joint_state.velocity[0]= default_state.velocity[i];
833  Segment hold_segment(0.0, default_joint_state, 0.0, default_joint_state);
834 
835  TrajectoryPerJoint joint_segment;
836  joint_segment.resize(1, hold_segment);
837  hold_traj->push_back(joint_segment);
838  }
839 
840  return hold_traj;
841 }
842 
843 } // namespace
XmlRpc::XmlRpcValue::size
int size() const
angles::shortest_angular_distance
static double shortest_angular_distance(double from, double to)
joint_trajectory_controller::JointTrajectoryController::TrajectoryPerJoint
std::vector< Segment > TrajectoryPerJoint
Definition: joint_trajectory_controller.h:171
joint_trajectory_controller::HoldTrajectoryBuilder
Builder creating a trajectory "simply" holding (without motion) the specified position.
Definition: hold_trajectory_builder.h:43
joint_trajectory_controller::InitJointTrajectoryOptions
Options used when initializing a joint trajectory from ROS message data.
Definition: init_joint_trajectory.h:94
joint_trajectory_controller::JointTrajectoryController::JointTrajectoryConstPtr
trajectory_msgs::JointTrajectory::ConstPtr JointTrajectoryConstPtr
Definition: joint_trajectory_controller.h:166
actionlib::ServerGoalHandle::getGoal
boost::shared_ptr< const Goal > getGoal() const
joint_trajectory_controller::JointTrajectoryController::goalCB
virtual void goalCB(GoalHandle gh)
Definition: joint_trajectory_controller_impl.h:567
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
actionlib::ServerGoalHandle
joint_trajectory_controller::JointTrajectoryController::setActionFeedback
void setActionFeedback()
Updates the pre-allocated feedback of the current active goal (if any) based on the current state val...
Definition: joint_trajectory_controller_impl.h:798
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
actionlib::ActionServer
joint_trajectory_controller::internal::getLeafNamespace
std::string getLeafNamespace(const ros::NodeHandle &nh)
Definition: joint_trajectory_controller_impl.h:122
joint_trajectory_controller::internal::mapping
std::vector< unsigned int > mapping(const T &t1, const T &t2)
Definition: init_joint_trajectory.h:65
TimeBase< Time, Duration >::toSec
double toSec() const
joint_trajectory_controller::JointTrajectoryController::TimeData::time
ros::Time time
Time of last update cycle.
Definition: joint_trajectory_controller.h:156
trajectory_interface::sample
Trajectory::const_iterator sample(const Trajectory &trajectory, const typename Trajectory::value_type::Time &time, typename Trajectory::value_type::State &state)
Sample a trajectory at a specified time.
Definition: trajectory_interface.h:138
XmlRpc
ROS_DEBUG_STREAM_THROTTLE_NAMED
#define ROS_DEBUG_STREAM_THROTTLE_NAMED(period, name, args)
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
urdf::Model
joint_trajectory_controller::JointTrajectoryController::TimeData::uptime
ros::Time uptime
Controller uptime. Set to zero at every restart.
Definition: joint_trajectory_controller.h:158
actionlib::ServerGoalHandle::setRejected
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
joint_trajectory_controller::JointTrajectoryController::queryStateService
virtual bool queryStateService(control_msgs::QueryTrajectoryState::Request &req, control_msgs::QueryTrajectoryState::Response &resp)
Definition: joint_trajectory_controller_impl.h:664
joint_trajectory_controller::SegmentTolerancesPerJoint
Trajectory segment tolerances per Joint.
Definition: tolerances.h:95
joint_trajectory_controller::JointTrajectoryController::starting
void starting(const ros::Time &time)
Holds the current position.
Definition: joint_trajectory_controller_impl.h:133
realtime_tools::RealtimePublisher
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
joint_trajectory_controller
Definition: hold_trajectory_builder.h:35
joint_trajectory_controller::JointTrajectorySegment::State
Definition: joint_trajectory_segment.h:79
joint_trajectory_controller::JointTrajectoryController::setHoldPosition
void setHoldPosition(const ros::Time &time, RealtimeGoalHandlePtr gh=RealtimeGoalHandlePtr())
Hold the current position.
Definition: joint_trajectory_controller_impl.h:740
joint_trajectory_controller::checkStateTolerancePerJoint
bool checkStateTolerancePerJoint(const State &state_error, const StateTolerances< typename State::Scalar > &state_tolerance, bool show_errors=false)
Definition: tolerances.h:168
actionlib::ServerGoalHandle::setAccepted
void setAccepted(const std::string &text=std::string(""))
joint_trajectory_controller::JointTrajectoryController::updateStates
void updateStates(const ros::Time &sample_time, const Trajectory *const traj)
Updates the states by sampling the specified trajectory for each joint at the specified sampling time...
Definition: joint_trajectory_controller_impl.h:766
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
joint_trajectory_controller::JointTrajectorySegment
Class representing a multi-dimensional quintic spline segment with a start and end time.
Definition: joint_trajectory_segment.h:70
joint_trajectory_controller::JointTrajectoryController::TrajectoryPtr
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: joint_trajectory_controller.h:173
joint_trajectory_controller::internal::getUrdfJoints
std::vector< urdf::JointConstSharedPtr > getUrdfJoints(const urdf::Model &urdf, const std::vector< std::string > &joint_names)
Definition: joint_trajectory_controller_impl.h:103
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
joint_trajectory_controller::JointTrajectoryController::TimeData
Definition: joint_trajectory_controller.h:152
joint_trajectory_controller::SegmentTolerancesPerJoint::goal_time_tolerance
Scalar goal_time_tolerance
Definition: tolerances.h:110
joint_trajectory_controller::JointTrajectoryController::publishState
void publishState(const ros::Time &time)
Publish current controller state at a throttled frequency.
Definition: joint_trajectory_controller_impl.h:712
joint_trajectory_controller::JointTrajectoryController::TimeData::period
ros::Duration period
Period of last update cycle.
Definition: joint_trajectory_controller.h:157
joint_trajectory_controller::JointTrajectoryController::update
void update(const ros::Time &time, const ros::Duration &period)
Definition: joint_trajectory_controller_impl.h:347
joint_trajectory_controller::JointTrajectoryController::trajectoryCommandCB
virtual void trajectoryCommandCB(const JointTrajectoryConstPtr &msg)
Definition: joint_trajectory_controller_impl.h:167
d
d
joint_trajectory_controller::JointTrajectoryController::Trajectory
std::vector< TrajectoryPerJoint > Trajectory
Definition: joint_trajectory_controller.h:172
ros::TimerEvent
joint_trajectory_controller::SegmentTolerancesPerJoint::goal_state_tolerance
StateTolerances< Scalar > goal_state_tolerance
Definition: tolerances.h:107
joint_trajectory_controller::JointTrajectoryController::init
bool init(HardwareInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Definition: joint_trajectory_controller_impl.h:205
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
joint_trajectory_controller::internal::getStrings
std::vector< std::string > getStrings(const ros::NodeHandle &nh, const std::string &param_name)
Definition: joint_trajectory_controller_impl.h:48
joint_trajectory_controller::JointTrajectoryController::updateTrajectoryCommand
virtual bool updateTrajectoryCommand(const JointTrajectoryConstPtr &msg, RealtimeGoalHandlePtr gh, std::string *error_string=nullptr)
Definition: joint_trajectory_controller_impl.h:481
joint_trajectory_controller::StopTrajectoryBuilder
Builder creating a trajectory stopping the robot.
Definition: stop_trajectory_builder.h:42
joint_trajectory_controller::JointTrajectoryController::stopping
void stopping(const ros::Time &)
Cancels the active action goal, if any.
Definition: joint_trajectory_controller_impl.h:160
realtime_tools::RealtimeServerGoalHandle
ros::Time
joint_trajectory_controller::JointTrajectoryController::createHoldTrajectory
static TrajectoryPtr createHoldTrajectory(const unsigned int &number_of_joints)
Returns a trajectory consisting of joint trajectories with one pre-allocated segment.
Definition: joint_trajectory_controller_impl.h:823
urdf
joint_trajectory_controller::JointTrajectoryController::preemptActiveGoal
virtual void preemptActiveGoal()
Definition: joint_trajectory_controller_impl.h:175
joint_trajectory_controller::internal::getUrdf
urdf::ModelSharedPtr getUrdf(const ros::NodeHandle &nh, const std::string &param_name)
Definition: joint_trajectory_controller_impl.h:79
joint_trajectory_controller::JointTrajectoryController::JointTrajectoryController
JointTrajectoryController()
Definition: joint_trajectory_controller_impl.h:190
joint_trajectory_controller::JointTrajectoryController::cancelCB
virtual void cancelCB(GoalHandle gh)
Definition: joint_trajectory_controller_impl.h:640
joint_trajectory_controller::JointTrajectoryController::getNumberOfJoints
unsigned int getNumberOfJoints() const
Returns the number of joints of the robot.
Definition: joint_trajectory_controller_impl.h:759
joint_trajectory_controller::JointTrajectoryController::updateFuncExtensionPoint
virtual void updateFuncExtensionPoint(const Trajectory &curr_traj, const TimeData &time_data)
Allows derived classes to perform additional checks and to e.g. replace the newly calculated desired ...
Definition: joint_trajectory_controller_impl.h:752
actionlib::EnclosureDeleter
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ros::Duration
joint_trajectory_controller::InitJointTrajectoryOptions::error_string
std::string * error_string
Definition: init_joint_trajectory.h:120
joint_trajectory_controller::internal::share_member
boost::shared_ptr< Member > share_member(boost::shared_ptr< Enclosure > enclosure, Member &member)
Definition: joint_trajectory_controller_impl.h:41
joint_trajectory_controller::SegmentTolerancesPerJoint::state_tolerance
StateTolerances< Scalar > state_tolerance
Definition: tolerances.h:104
XmlRpc::XmlRpcValue
ros::NodeHandle
joint_trajectory_controller::JointTrajectoryController::verbose_
bool verbose_
Hard coded verbose flag to help in debugging.
Definition: joint_trajectory_controller.h:181


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri May 24 2024 02:41:24