trajectory_interface.h
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2020 FZI Forschungszentrum Informatik
3 // Created on behalf of Universal Robots A/S
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 // -- END LICENSE BLOCK ------------------------------------------------
17 
18 //-----------------------------------------------------------------------------
25 //-----------------------------------------------------------------------------
26 
27 #pragma once
28 
29 #include <functional>
30 #include <cartesian_control_msgs/FollowCartesianTrajectoryGoal.h>
31 #include <cartesian_control_msgs/FollowCartesianTrajectoryResult.h>
32 #include <cartesian_control_msgs/FollowCartesianTrajectoryFeedback.h>
33 #include <control_msgs/FollowJointTrajectoryGoal.h>
34 #include <control_msgs/FollowJointTrajectoryFeedback.h>
35 #include <vector>
37 #include <ros/ros.h>
38 
39 namespace hardware_interface
40 {
48 enum class ExecutionState
49 {
50  SUCCESS = 0,
51  PREEMPTED = -1,
52  ABORTED = -2,
53 };
54 
58 using JointTrajectory = control_msgs::FollowJointTrajectoryGoal;
59 
63 using CartesianTrajectory = cartesian_control_msgs::FollowCartesianTrajectoryGoal;
64 
68 using JointTrajectoryFeedback = control_msgs::FollowJointTrajectoryFeedback;
69 
73 using CartesianTrajectoryFeedback = cartesian_control_msgs::FollowCartesianTrajectoryFeedback;
74 
103 template <class TrajectoryType, class FeedbackType>
105 {
106 public:
116  void registerGoalCallback(std::function<void(const TrajectoryType&)> f)
117  {
118  goal_callback_ = f;
119  }
120 
126  void registerCancelCallback(std::function<void()> f)
127  {
129  }
130 
139  void registerDoneCallback(std::function<void(const ExecutionState&)> f)
140  {
141  done_callback_ = f;
142  }
143 
155  bool setGoal(TrajectoryType goal);
156 
162  void setCancel()
163  {
164  if (cancel_callback_ != nullptr)
166  };
167 
178  void setDone(const ExecutionState& state)
179  {
180  if (done_callback_ != nullptr)
181  done_callback_(state);
182  }
183 
192  void setFeedback(FeedbackType feedback)
193  {
194  feedback_ = feedback;
195  }
196 
205  FeedbackType getFeedback() const
206  {
207  return feedback_;
208  }
209 
215  std::vector<std::string> getJointNames() const
216  {
217  return joint_names_;
218  }
219 
228  void setResources(std::vector<std::string> resources)
229  {
230  for (const std::string& joint : resources)
231  {
233  }
234  joint_names_ = resources;
235  }
236 
237 private:
238  std::function<void(const TrajectoryType&)> goal_callback_;
239  std::function<void()> cancel_callback_;
240  std::function<void(const ExecutionState&)> done_callback_;
241  FeedbackType feedback_;
242  std::vector<std::string> joint_names_;
243 };
244 
245 // Full spezialization for JointTrajectory
246 template <>
248 {
249  control_msgs::FollowJointTrajectoryGoal tmp = goal;
250 
251  // Respect joint order by computing the map between msg indices to expected indices.
252  // If msg is {A, C, D, B} and expected is {A, B, C, D}, the associated mapping vector is {0, 2, 3, 1}
253  auto msg = goal.trajectory.joint_names;
254  auto expected = joint_names_;
255  std::vector<size_t> msg_joints(msg.size());
256  if (msg.size() != expected.size())
257  {
258  // msg must contain all joint names.
259  ROS_WARN("Not forwarding trajectory. It contains wrong number of joints");
260  return false;
261  }
262  for (auto msg_it = msg.begin(); msg_it != msg.end(); ++msg_it)
263  {
264  auto expected_it = std::find(expected.begin(), expected.end(), *msg_it);
265  if (expected.end() == expected_it)
266  {
267  ROS_WARN_STREAM("Not forwarding trajectory. It contains at least one unexpected joint name: " << *msg_it);
268  return false;
269  }
270  else
271  {
272  const size_t msg_dist = std::distance(msg.begin(), msg_it);
273  const size_t expected_dist = std::distance(expected.begin(), expected_it);
274  msg_joints[msg_dist] = expected_dist;
275  }
276  }
277 
278  // Reorder the joint names and data fields in all trajectory points
279  tmp.trajectory.joint_names = expected;
280  tmp.trajectory.points.clear();
281 
282  for (auto point : goal.trajectory.points)
283  {
284  trajectory_msgs::JointTrajectoryPoint p{ point }; // init for equal data size
285 
286  for (size_t i = 0; i < expected.size(); ++i)
287  {
288  auto jnt_id = msg_joints[i];
289 
290  if (point.positions.size() == expected.size())
291  p.positions[jnt_id] = point.positions[i];
292  if (point.velocities.size() == expected.size())
293  p.velocities[jnt_id] = point.velocities[i];
294  if (point.accelerations.size() == expected.size())
295  p.accelerations[jnt_id] = point.accelerations[i];
296  if (point.effort.size() == expected.size())
297  p.effort[jnt_id] = point.effort[i];
298  }
299  tmp.trajectory.points.push_back(p);
300  }
301 
302  if (goal_callback_ != nullptr)
303  {
304  goal_callback_(tmp);
305  return true;
306  }
307  return false;
308 }
309 
310 // Full spezialization for CartesianTrajectory
311 template <>
313 {
314  if (goal_callback_ != nullptr)
315  {
316  goal_callback_(goal);
317  return true;
318  }
319  return false;
320 }
321 
326 
331 
332 } // namespace hardware_interface
hardware_interface::ExecutionState::SUCCESS
@ SUCCESS
hardware_interface::TrajectoryInterface::feedback_
FeedbackType feedback_
Definition: trajectory_interface.h:241
hardware_interface::CartesianTrajectoryFeedback
cartesian_control_msgs::FollowCartesianTrajectoryFeedback CartesianTrajectoryFeedback
FeedbackType for Cartesian trajectories.
Definition: trajectory_interface.h:73
hardware_interface::TrajectoryInterface::registerCancelCallback
void registerCancelCallback(std::function< void()> f)
Register a RobotHW-side callback for canceling requests.
Definition: trajectory_interface.h:126
hardware_interface::TrajectoryInterface::cancel_callback_
std::function< void()> cancel_callback_
Definition: trajectory_interface.h:239
ros.h
hardware_interface::HardwareInterface
hardware_interface::TrajectoryInterface
Hardware interface for forwarding trajectories.
Definition: trajectory_interface.h:104
hardware_interface::TrajectoryInterface::joint_names_
std::vector< std::string > joint_names_
Definition: trajectory_interface.h:242
hardware_interface::TrajectoryInterface::goal_callback_
std::function< void(const TrajectoryType &)> goal_callback_
Definition: trajectory_interface.h:238
hardware_interface.h
f
f
hardware_interface::TrajectoryInterface::setDone
void setDone(const ExecutionState &state)
RobotHW-side method to mark the execution of a trajectory done.
Definition: trajectory_interface.h:178
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
hardware_interface
hardware_interface::TrajectoryInterface::registerGoalCallback
void registerGoalCallback(std::function< void(const TrajectoryType &)> f)
Register a RobotHW-side callback for new trajectory execution.
Definition: trajectory_interface.h:116
hardware_interface::TrajectoryInterface::registerDoneCallback
void registerDoneCallback(std::function< void(const ExecutionState &)> f)
Register a Controller-side callback for done signals from the hardware.
Definition: trajectory_interface.h:139
hardware_interface::TrajectoryInterface::setCancel
void setCancel()
Cancel the current trajectory execution.
Definition: trajectory_interface.h:162
ROS_WARN
#define ROS_WARN(...)
hardware_interface::CartesianTrajectory
cartesian_control_msgs::FollowCartesianTrajectoryGoal CartesianTrajectory
TrajectoryType for Cartesian trajectories.
Definition: trajectory_interface.h:63
hardware_interface::ExecutionState
ExecutionState
Hardware-generic done flags for trajectory execution.
Definition: trajectory_interface.h:48
hardware_interface::ExecutionState::PREEMPTED
@ PREEMPTED
hardware_interface::JointTrajectory
control_msgs::FollowJointTrajectoryGoal JointTrajectory
TrajectoryType for joint-based trajectories.
Definition: trajectory_interface.h:58
hardware_interface::TrajectoryInterface::getFeedback
FeedbackType getFeedback() const
Get trajectory feedback.
Definition: trajectory_interface.h:205
hardware_interface::ExecutionState::ABORTED
@ ABORTED
hardware_interface::TrajectoryInterface::setFeedback
void setFeedback(FeedbackType feedback)
Set trajectory feedback for PassThroughControllers.
Definition: trajectory_interface.h:192
hardware_interface::JointTrajectoryFeedback
control_msgs::FollowJointTrajectoryFeedback JointTrajectoryFeedback
FeedbackType for joint-based trajectories.
Definition: trajectory_interface.h:68
hardware_interface::TrajectoryInterface::setGoal
bool setGoal(TrajectoryType goal)
Start the forwarding of new trajectories.
hardware_interface::TrajectoryInterface::done_callback_
std::function< void(const ExecutionState &)> done_callback_
Definition: trajectory_interface.h:240
hardware_interface::TrajectoryInterface::setResources
void setResources(std::vector< std::string > resources)
Associate resources with this interface.
Definition: trajectory_interface.h:228
hardware_interface::HardwareInterface::claim
virtual void claim(std::string resource)
hardware_interface::TrajectoryInterface::getJointNames
std::vector< std::string > getJointNames() const
Get the joint names (resources) associated with this interface.
Definition: trajectory_interface.h:215


pass_through_controllers
Author(s):
autogenerated on Tue Oct 15 2024 02:10:52