A ROS controller for forwarding trajectories to a robot for interpolation. More...
#include <pass_through_controllers.h>
Classes | |
struct | ActionDuration |
Container for easy time management. More... | |
Public Types | |
using | Base = typename std::conditional< std::is_same< TrajectoryInterface, hardware_interface::JointTrajectoryInterface >::value, JointBase, CartesianBase >::type |
![]() | |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
enum | ControllerState { ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED, ControllerState::WAITING, ControllerState::ABORTED } |
Public Member Functions | |
void | executeCB (const typename Base::GoalConstPtr &goal) |
Callback method for new action goals. More... | |
bool | init (hardware_interface::RobotHW *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
PassThroughController () | |
void | preemptCB () |
Callback method for preempt requests. More... | |
void | starting (const ros::Time &time) |
void | stopping (const ros::Time &time) |
void | update (const ros::Time &time, const ros::Duration &period) |
![]() | |
virtual bool | init (hardware_interface::RobotHW *, ros::NodeHandle &) |
MultiInterfaceController (bool allow_optional_interfaces=false) | |
![]() | |
virtual void | aborting (const ros::Time &) |
virtual void | aborting (const ros::Time &) |
bool | abortRequest (const ros::Time &time) |
bool | abortRequest (const ros::Time &time) |
ControllerBase ()=default | |
ControllerBase (const ControllerBase &)=delete | |
ControllerBase (ControllerBase &&)=delete | |
bool | isAborted () const |
bool | isAborted () const |
bool | isInitialized () const |
bool | isInitialized () const |
bool | isRunning () const |
bool | isRunning () const |
bool | isStopped () const |
bool | isStopped () const |
bool | isWaiting () const |
bool | isWaiting () const |
ControllerBase & | operator= (const ControllerBase &)=delete |
ControllerBase & | operator= (ControllerBase &&)=delete |
bool | startRequest (const ros::Time &time) |
bool | startRequest (const ros::Time &time) |
bool | stopRequest (const ros::Time &time) |
bool | stopRequest (const ros::Time &time) |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
virtual void | waiting (const ros::Time &) |
virtual void | waiting (const ros::Time &) |
bool | waitRequest (const ros::Time &time) |
bool | waitRequest (const ros::Time &time) |
virtual | ~ControllerBase ()=default |
Private Member Functions | |
void | doneCB (const hardware_interface::ExecutionState &state) |
Will get called upon finishing the forwarded trajectory. More... | |
bool | isValid (const typename Base::GoalConstPtr &goal) |
Check if follow trajectory goals are valid. More... | |
bool | isValid (const typename Base::GoalConstPtr &goal) |
bool | isValid (const typename Base::GoalConstPtr &goal) |
void | monitorExecution (const typename Base::TrajectoryFeedback &feedback) |
Monitor the trajectory execution. More... | |
bool | withinTolerances (const TrajectoryPoint &error, const Tolerance &tolerances) |
bool | withinTolerances (const typename Base::TrajectoryPoint &error, const typename Base::Tolerance &tolerances) |
Check if tolerances are met. More... | |
bool | withinTolerances (const typename Base::TrajectoryPoint &error, const typename Base::Tolerance &tolerances) |
Private Attributes | |
ActionDuration | action_duration_ |
std::unique_ptr< actionlib::SimpleActionServer< typename Base::FollowTrajectoryAction > > | action_server_ |
std::atomic< bool > | done_ |
Base::Tolerance | goal_tolerances_ |
std::vector< std::string > | joint_names_ |
Base::Tolerance | path_tolerances_ |
std::unique_ptr< scaled_controllers::SpeedScalingHandle > | speed_scaling_ |
TrajectoryInterface * | trajectory_interface_ |
A ROS controller for forwarding trajectories to a robot for interpolation.
Instead of interpolating between the waypoints itself, this driver passes the complete trajectories down to the according HW interfaces, assuming that the driver's implementation makes use of whichever components are suitable for that specific robot.
This controller implements a simple action server that provides the common /follow_joint_trajectory or /follow_cartesian_trajectory action interface.
Users specify this controller in their .yaml files with:
TrajectoryInterface | The type of trajectory interface used for this controller. Either hardware_interface::JointTrajectoryInterface or hardware_interface::CartesianTrajectoryInterface. |
Definition at line 106 of file pass_through_controllers.h.
using trajectory_controllers::PassThroughController< TrajectoryInterface >::Base = typename std::conditional<std::is_same<TrajectoryInterface, hardware_interface::JointTrajectoryInterface>::value, JointBase, CartesianBase>::type |
Definition at line 125 of file pass_through_controllers.h.
|
inline |
Definition at line 113 of file pass_through_controllers.h.
|
private |
Will get called upon finishing the forwarded trajectory.
Definition at line 322 of file pass_through_controllers.hpp.
void trajectory_controllers::PassThroughController< TrajectoryInterface >::executeCB | ( | const typename Base::GoalConstPtr & | goal | ) |
Callback method for new action goals.
This method calls the setGoal() method from the TrajectoryInterface. Implementers of the ROS-control HW can choose how the trajectory goal is forwarded to the robot for interpolation.
Things in detail:
Further info on how the simple action server works is given here.
goal | The trajectory goal |
Definition at line 152 of file pass_through_controllers.hpp.
|
virtual |
Reimplemented from controller_interface::MultiInterfaceController< TrajectoryInterface, scaled_controllers::SpeedScalingInterface >.
Definition at line 41 of file pass_through_controllers.hpp.
|
private |
Check if follow trajectory goals are valid.
goal | The goal to check. |
|
private |
Definition at line 297 of file pass_through_controllers.hpp.
|
private |
Definition at line 314 of file pass_through_controllers.hpp.
|
private |
Monitor the trajectory execution.
feedback | The feedback to use for evaluating tolerances |
Definition at line 211 of file pass_through_controllers.hpp.
void trajectory_controllers::PassThroughController< TrajectoryInterface >::preemptCB |
Callback method for preempt requests.
This method gets called on every preempt request that happens either directly upon a client request or indirectly when receiving a new goal while another is still active.
This method calls the setCancel() method from the TrajectoryInterface. The RobotHW should implement how this notification is handled by the robot vendor control.
Also check this info. on the simple action server's preemption policy:
Definition at line 201 of file pass_through_controllers.hpp.
|
virtual |
Reimplemented from controller_interface::ControllerBase.
Definition at line 100 of file pass_through_controllers.hpp.
|
virtual |
Reimplemented from controller_interface::ControllerBase.
Definition at line 106 of file pass_through_controllers.hpp.
|
virtual |
Implements controller_interface::ControllerBase.
Definition at line 122 of file pass_through_controllers.hpp.
|
private |
Definition at line 221 of file pass_through_controllers.hpp.
|
private |
Check if tolerances are met.
error | The error to check |
tolerances | The tolerances to check against |
|
private |
Definition at line 265 of file pass_through_controllers.hpp.
|
private |
Definition at line 218 of file pass_through_controllers.h.
|
private |
Definition at line 224 of file pass_through_controllers.h.
|
private |
Definition at line 217 of file pass_through_controllers.h.
|
private |
Definition at line 222 of file pass_through_controllers.h.
|
private |
Definition at line 220 of file pass_through_controllers.h.
|
private |
Definition at line 221 of file pass_through_controllers.h.
|
private |
Definition at line 219 of file pass_through_controllers.h.
|
private |
Definition at line 223 of file pass_through_controllers.h.