pass_through_controllers.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 // ROS control
34 
35 // Joint-based
36 #include <control_msgs/FollowJointTrajectoryGoal.h>
37 #include <control_msgs/JointTolerance.h>
38 #include <trajectory_msgs/JointTrajectoryPoint.h>
39 #include <control_msgs/FollowJointTrajectoryAction.h>
40 
41 // Cartesian
42 #include <cartesian_control_msgs/CartesianTolerance.h>
43 #include <cartesian_control_msgs/CartesianTrajectoryPoint.h>
44 #include <cartesian_control_msgs/FollowCartesianTrajectoryGoal.h>
45 #include <cartesian_control_msgs/FollowCartesianTrajectoryAction.h>
46 
47 // Other
49 #include <vector>
50 #include <memory>
51 #include <atomic>
52 
54 {
55 struct JointBase
56 {
57  using Tolerance = std::vector<control_msgs::JointTolerance>;
58  using TrajectoryPoint = trajectory_msgs::JointTrajectoryPoint;
60  using FollowTrajectoryAction = control_msgs::FollowJointTrajectoryAction;
61  using FollowTrajectoryResult = control_msgs::FollowJointTrajectoryResult;
62  using GoalConstPtr = control_msgs::FollowJointTrajectoryGoalConstPtr;
63 };
64 
66 {
67  using Tolerance = cartesian_control_msgs::CartesianTolerance;
68  using TrajectoryPoint = cartesian_control_msgs::CartesianTrajectoryPoint;
70  using FollowTrajectoryAction = cartesian_control_msgs::FollowCartesianTrajectoryAction;
71  using FollowTrajectoryResult = cartesian_control_msgs::FollowCartesianTrajectoryResult;
72  using GoalConstPtr = cartesian_control_msgs::FollowCartesianTrajectoryGoalConstPtr;
73 };
74 
105 template <class TrajectoryInterface>
107  : public controller_interface::MultiInterfaceController<TrajectoryInterface,
108  scaled_controllers::SpeedScalingInterface>,
109  public std::conditional<std::is_same<TrajectoryInterface, hardware_interface::JointTrajectoryInterface>::value,
110  JointBase, CartesianBase>::type
111 {
112 public:
114  : controller_interface::MultiInterfaceController<TrajectoryInterface,
115  scaled_controllers::SpeedScalingInterface>(
116  true) // Make speed scaling optional
117  {
118  }
119 
120  // Alias for full qualifications of inherited types.
121  // This enables a compact definition of member functions for both joint-based
122  // and Cartesian-based PassThroughControllers.
123  using Base =
124  typename std::conditional<std::is_same<TrajectoryInterface, hardware_interface::JointTrajectoryInterface>::value,
126 
127  bool init(hardware_interface::RobotHW* hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
128 
129  void starting(const ros::Time& time);
130 
131  void stopping(const ros::Time& time);
132 
133  void update(const ros::Time& time, const ros::Duration& period);
134 
152  void executeCB(const typename Base::GoalConstPtr& goal);
153 
169  void preemptCB();
170 
171 private:
177  {
179  {
180  }
181 
184  };
185 
191  void monitorExecution(const typename Base::TrajectoryFeedback& feedback);
192 
201  bool withinTolerances(const typename Base::TrajectoryPoint& error, const typename Base::Tolerance& tolerances);
202 
210  bool isValid(const typename Base::GoalConstPtr& goal);
211 
215  void doneCB(const hardware_interface::ExecutionState& state);
216 
217  std::atomic<bool> done_;
219  std::unique_ptr<scaled_controllers::SpeedScalingHandle> speed_scaling_;
220  std::vector<std::string> joint_names_;
221  typename Base::Tolerance path_tolerances_;
222  typename Base::Tolerance goal_tolerances_;
223  TrajectoryInterface* trajectory_interface_;
224  std::unique_ptr<actionlib::SimpleActionServer<typename Base::FollowTrajectoryAction> > action_server_;
225 };
226 
227 } // namespace trajectory_controllers
228 
trajectory_controllers::CartesianBase
Definition: pass_through_controllers.h:65
hardware_interface::CartesianTrajectoryFeedback
cartesian_control_msgs::FollowCartesianTrajectoryFeedback CartesianTrajectoryFeedback
FeedbackType for Cartesian trajectories.
Definition: trajectory_interface.h:73
trajectory_controllers::JointBase::TrajectoryFeedback
hardware_interface::JointTrajectoryFeedback TrajectoryFeedback
Definition: pass_through_controllers.h:59
trajectory_controllers::PassThroughController::starting
void starting(const ros::Time &time)
Definition: pass_through_controllers.hpp:100
trajectory_controllers::JointBase::FollowTrajectoryResult
control_msgs::FollowJointTrajectoryResult FollowTrajectoryResult
Definition: pass_through_controllers.h:61
trajectory_controllers::PassThroughController::ActionDuration::ActionDuration
ActionDuration()
Definition: pass_through_controllers.h:178
trajectory_controllers::PassThroughController::done_
std::atomic< bool > done_
Definition: pass_through_controllers.h:217
scaled_controllers
trajectory_controllers::PassThroughController::PassThroughController
PassThroughController()
Definition: pass_through_controllers.h:113
trajectory_interface.h
pass_through_controllers.hpp
simple_action_server.h
trajectory_controllers::JointBase::TrajectoryPoint
trajectory_msgs::JointTrajectoryPoint TrajectoryPoint
Definition: pass_through_controllers.h:58
trajectory_controllers::PassThroughController::action_duration_
ActionDuration action_duration_
Definition: pass_through_controllers.h:218
trajectory_controllers::PassThroughController::speed_scaling_
std::unique_ptr< scaled_controllers::SpeedScalingHandle > speed_scaling_
Definition: pass_through_controllers.h:219
trajectory_controllers::JointBase::Tolerance
std::vector< control_msgs::JointTolerance > Tolerance
Definition: pass_through_controllers.h:57
trajectory_controllers::CartesianBase::TrajectoryPoint
cartesian_control_msgs::CartesianTrajectoryPoint TrajectoryPoint
Definition: pass_through_controllers.h:68
trajectory_controllers::PassThroughController::executeCB
void executeCB(const typename Base::GoalConstPtr &goal)
Callback method for new action goals.
Definition: pass_through_controllers.hpp:152
trajectory_controllers::JointBase::FollowTrajectoryAction
control_msgs::FollowJointTrajectoryAction FollowTrajectoryAction
Definition: pass_through_controllers.h:60
hardware_interface::RobotHW
trajectory_controllers::PassThroughController::ActionDuration
Container for easy time management.
Definition: pass_through_controllers.h:176
trajectory_controllers::CartesianBase::TrajectoryFeedback
hardware_interface::CartesianTrajectoryFeedback TrajectoryFeedback
Definition: pass_through_controllers.h:69
speed_scaling_interface.h
trajectory_controllers::PassThroughController::update
void update(const ros::Time &time, const ros::Duration &period)
Definition: pass_through_controllers.hpp:122
trajectory_controllers::PassThroughController::init
bool init(hardware_interface::RobotHW *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Definition: pass_through_controllers.hpp:41
controller_interface::MultiInterfaceController
Base
trajectory_controllers::PassThroughController::withinTolerances
bool withinTolerances(const typename Base::TrajectoryPoint &error, const typename Base::Tolerance &tolerances)
Check if tolerances are met.
trajectory_controllers::PassThroughController::action_server_
std::unique_ptr< actionlib::SimpleActionServer< typename Base::FollowTrajectoryAction > > action_server_
Definition: pass_through_controllers.h:224
trajectory_controllers::CartesianBase::Tolerance
cartesian_control_msgs::CartesianTolerance Tolerance
Definition: pass_through_controllers.h:67
trajectory_controllers::PassThroughController::trajectory_interface_
TrajectoryInterface * trajectory_interface_
Definition: pass_through_controllers.h:223
trajectory_controllers::PassThroughController::preemptCB
void preemptCB()
Callback method for preempt requests.
Definition: pass_through_controllers.hpp:201
hardware_interface::ExecutionState
ExecutionState
Hardware-generic done flags for trajectory execution.
Definition: trajectory_interface.h:48
controller_interface::MultiInterfaceController< TrajectoryInterface, scaled_controllers::SpeedScalingInterface >::MultiInterfaceController
MultiInterfaceController(bool allow_optional_interfaces=false)
trajectory_controllers::CartesianBase::FollowTrajectoryResult
cartesian_control_msgs::FollowCartesianTrajectoryResult FollowTrajectoryResult
Definition: pass_through_controllers.h:71
trajectory_controllers
Definition: pass_through_controllers.h:53
ros::Time
trajectory_controllers::PassThroughController::stopping
void stopping(const ros::Time &time)
Definition: pass_through_controllers.hpp:106
trajectory_controllers::JointBase
Definition: pass_through_controllers.h:55
trajectory_controllers::JointBase::GoalConstPtr
control_msgs::FollowJointTrajectoryGoalConstPtr GoalConstPtr
Definition: pass_through_controllers.h:62
robot_hw.h
hardware_interface::JointTrajectoryFeedback
control_msgs::FollowJointTrajectoryFeedback JointTrajectoryFeedback
FeedbackType for joint-based trajectories.
Definition: trajectory_interface.h:68
trajectory_controllers::PassThroughController::joint_names_
std::vector< std::string > joint_names_
Definition: pass_through_controllers.h:220
controller_interface
trajectory_controllers::CartesianBase::GoalConstPtr
cartesian_control_msgs::FollowCartesianTrajectoryGoalConstPtr GoalConstPtr
Definition: pass_through_controllers.h:72
trajectory_controllers::PassThroughController::ActionDuration::current
ros::Duration current
Real duration of the current action.
Definition: pass_through_controllers.h:183
ros::Duration
trajectory_controllers::PassThroughController::path_tolerances_
Base::Tolerance path_tolerances_
Definition: pass_through_controllers.h:221
trajectory_controllers::PassThroughController::isValid
bool isValid(const typename Base::GoalConstPtr &goal)
Check if follow trajectory goals are valid.
trajectory_controllers::PassThroughController
A ROS controller for forwarding trajectories to a robot for interpolation.
Definition: pass_through_controllers.h:106
trajectory_controllers::PassThroughController::goal_tolerances_
Base::Tolerance goal_tolerances_
Definition: pass_through_controllers.h:222
ros::NodeHandle
trajectory_controllers::CartesianBase::FollowTrajectoryAction
cartesian_control_msgs::FollowCartesianTrajectoryAction FollowTrajectoryAction
Definition: pass_through_controllers.h:70
trajectory_controllers::PassThroughController::ActionDuration::target
ros::Duration target
Target duration of the current action.
Definition: pass_through_controllers.h:182
trajectory_controllers::PassThroughController::monitorExecution
void monitorExecution(const typename Base::TrajectoryFeedback &feedback)
Monitor the trajectory execution.
Definition: pass_through_controllers.hpp:211
trajectory_controllers::PassThroughController::doneCB
void doneCB(const hardware_interface::ExecutionState &state)
Will get called upon finishing the forwarded trajectory.
Definition: pass_through_controllers.hpp:322
multi_interface_controller.h


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