Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
trajectory_controllers::PassThroughController< TrajectoryInterface > Class Template Reference

A ROS controller for forwarding trajectories to a robot for interpolation. More...

#include <pass_through_controllers.h>

Inheritance diagram for trajectory_controllers::PassThroughController< TrajectoryInterface >:
Inheritance graph
[legend]

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
 
- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
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)
 
- Public Member Functions inherited from controller_interface::MultiInterfaceController< TrajectoryInterface, scaled_controllers::SpeedScalingInterface >
virtual bool init (hardware_interface::RobotHW *, ros::NodeHandle &)
 
 MultiInterfaceController (bool allow_optional_interfaces=false)
 
- Public Member Functions inherited from controller_interface::ControllerBase
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
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (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::SpeedScalingHandlespeed_scaling_
 
TrajectoryInterface * trajectory_interface_
 

Additional Inherited Members

- Public Attributes inherited from controller_interface::ControllerBase
ControllerState state_
 
- Protected Member Functions inherited from controller_interface::MultiInterfaceController< TrajectoryInterface, scaled_controllers::SpeedScalingInterface >
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 
- Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< TrajectoryInterface, scaled_controllers::SpeedScalingInterface >
static void clearClaims (hardware_interface::RobotHW *robot_hw)
 
static void extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out)
 
static bool hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw)
 
static void populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources)
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< TrajectoryInterface, scaled_controllers::SpeedScalingInterface >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

template<class TrajectoryInterface>
class trajectory_controllers::PassThroughController< TrajectoryInterface >

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:

# Your joint-based passthrough controller
forward_joint_trajectories:
type: "pass_through_controllers/JointTrajectoryController"
...
# Your Cartesian passthrough controller
forward_cartesian_trajectories:
type: "pass_through_controllers/CartesianTrajectoryController"
...
Template Parameters
TrajectoryInterfaceThe 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.

Member Typedef Documentation

◆ Base

template<class TrajectoryInterface >
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.

Constructor & Destructor Documentation

◆ PassThroughController()

template<class TrajectoryInterface >
trajectory_controllers::PassThroughController< TrajectoryInterface >::PassThroughController ( )
inline

Definition at line 113 of file pass_through_controllers.h.

Member Function Documentation

◆ doneCB()

template<class TrajectoryInterface >
void trajectory_controllers::PassThroughController< TrajectoryInterface >::doneCB ( const hardware_interface::ExecutionState state)
private

Will get called upon finishing the forwarded trajectory.

Definition at line 322 of file pass_through_controllers.hpp.

◆ executeCB()

template<class TrajectoryInterface >
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:

  • New goals are only accepted when the controller is running
  • Switching the controller (stopping) cancels running goals
  • The goal's success is monitored in update()

Further info on how the simple action server works is given here.

Parameters
goalThe trajectory goal

Definition at line 152 of file pass_through_controllers.hpp.

◆ init()

template<class TrajectoryInterface >
bool trajectory_controllers::PassThroughController< TrajectoryInterface >::init ( hardware_interface::RobotHW hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
virtual

◆ isValid() [1/3]

template<class TrajectoryInterface >
bool trajectory_controllers::PassThroughController< TrajectoryInterface >::isValid ( const typename Base::GoalConstPtr &  goal)
private

Check if follow trajectory goals are valid.

Parameters
goalThe goal to check.
Returns
True if goal is valid, false otherwise

◆ isValid() [2/3]

bool trajectory_controllers::PassThroughController< hardware_interface::JointTrajectoryInterface >::isValid ( const typename Base::GoalConstPtr &  goal)
private

Definition at line 297 of file pass_through_controllers.hpp.

◆ isValid() [3/3]

bool trajectory_controllers::PassThroughController< hardware_interface::CartesianTrajectoryInterface >::isValid ( const typename Base::GoalConstPtr &  goal)
private

Definition at line 314 of file pass_through_controllers.hpp.

◆ monitorExecution()

template<class TrajectoryInterface >
void trajectory_controllers::PassThroughController< TrajectoryInterface >::monitorExecution ( const typename Base::TrajectoryFeedback &  feedback)
private

Monitor the trajectory execution.

Parameters
feedbackThe feedback to use for evaluating tolerances

Definition at line 211 of file pass_through_controllers.hpp.

◆ preemptCB()

template<class TrajectoryInterface >
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.

◆ starting()

template<class TrajectoryInterface >
void trajectory_controllers::PassThroughController< TrajectoryInterface >::starting ( const ros::Time time)
virtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 100 of file pass_through_controllers.hpp.

◆ stopping()

template<class TrajectoryInterface >
void trajectory_controllers::PassThroughController< TrajectoryInterface >::stopping ( const ros::Time time)
virtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 106 of file pass_through_controllers.hpp.

◆ update()

template<class TrajectoryInterface >
void trajectory_controllers::PassThroughController< TrajectoryInterface >::update ( const ros::Time time,
const ros::Duration period 
)
virtual

◆ withinTolerances() [1/3]

bool trajectory_controllers::PassThroughController< hardware_interface::JointTrajectoryInterface >::withinTolerances ( const TrajectoryPoint &  error,
const Tolerance &  tolerances 
)
private

Definition at line 221 of file pass_through_controllers.hpp.

◆ withinTolerances() [2/3]

template<class TrajectoryInterface >
bool trajectory_controllers::PassThroughController< TrajectoryInterface >::withinTolerances ( const typename Base::TrajectoryPoint &  error,
const typename Base::Tolerance &  tolerances 
)
private

Check if tolerances are met.

Parameters
errorThe error to check
tolerancesThe tolerances to check against
Returns
False if any of the errors exceeds its tolerance, else true

◆ withinTolerances() [3/3]

bool trajectory_controllers::PassThroughController< hardware_interface::CartesianTrajectoryInterface >::withinTolerances ( const typename Base::TrajectoryPoint &  error,
const typename Base::Tolerance &  tolerances 
)
private

Definition at line 265 of file pass_through_controllers.hpp.

Member Data Documentation

◆ action_duration_

template<class TrajectoryInterface >
ActionDuration trajectory_controllers::PassThroughController< TrajectoryInterface >::action_duration_
private

Definition at line 218 of file pass_through_controllers.h.

◆ action_server_

template<class TrajectoryInterface >
std::unique_ptr<actionlib::SimpleActionServer<typename Base::FollowTrajectoryAction> > trajectory_controllers::PassThroughController< TrajectoryInterface >::action_server_
private
  • Resource managed by RobotHW

Definition at line 224 of file pass_through_controllers.h.

◆ done_

template<class TrajectoryInterface >
std::atomic<bool> trajectory_controllers::PassThroughController< TrajectoryInterface >::done_
private

Definition at line 217 of file pass_through_controllers.h.

◆ goal_tolerances_

template<class TrajectoryInterface >
Base::Tolerance trajectory_controllers::PassThroughController< TrajectoryInterface >::goal_tolerances_
private

Definition at line 222 of file pass_through_controllers.h.

◆ joint_names_

template<class TrajectoryInterface >
std::vector<std::string> trajectory_controllers::PassThroughController< TrajectoryInterface >::joint_names_
private

Definition at line 220 of file pass_through_controllers.h.

◆ path_tolerances_

template<class TrajectoryInterface >
Base::Tolerance trajectory_controllers::PassThroughController< TrajectoryInterface >::path_tolerances_
private

Definition at line 221 of file pass_through_controllers.h.

◆ speed_scaling_

template<class TrajectoryInterface >
std::unique_ptr<scaled_controllers::SpeedScalingHandle> trajectory_controllers::PassThroughController< TrajectoryInterface >::speed_scaling_
private

Definition at line 219 of file pass_through_controllers.h.

◆ trajectory_interface_

template<class TrajectoryInterface >
TrajectoryInterface* trajectory_controllers::PassThroughController< TrajectoryInterface >::trajectory_interface_
private

Definition at line 223 of file pass_through_controllers.h.


The documentation for this class was generated from the following files:


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