Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
forward_command_controller::ForwardJointGroupCommandController< T > Class Template Reference

Forward command controller for a set of joints. More...

#include <forward_joint_group_command_controller.h>

Inheritance diagram for forward_command_controller::ForwardJointGroupCommandController< T >:
Inheritance graph
[legend]

Public Member Functions

 ForwardJointGroupCommandController ()
 
bool init (T *hw, ros::NodeHandle &n)
 
void starting (const ros::Time &time)
 
void update (const ros::Time &, const ros::Duration &)
 
 ~ForwardJointGroupCommandController ()
 
- Public Member Functions inherited from controller_interface::Controller< T >
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 
- 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)
 
virtual void stopping (const ros::Time &)
 
virtual void stopping (const ros::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
 

Public Attributes

realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_
 
std::vector< std::string > joint_names_
 
std::vector< hardware_interface::JointHandlejoints_
 
unsigned int n_joints_
 
- Public Attributes inherited from controller_interface::ControllerBase
ControllerState state_
 

Private Member Functions

void commandCB (const std_msgs::Float64MultiArrayConstPtr &msg)
 

Private Attributes

ros::Subscriber sub_command_
 

Additional Inherited Members

- 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
}
 
- Protected Member Functions inherited from controller_interface::Controller< T >
std::string getHardwareInterfaceType () const
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 

Detailed Description

template<class T>
class forward_command_controller::ForwardJointGroupCommandController< T >

Forward command controller for a set of joints.

This class forwards the command signal down to a set of joints. Command signal and joint hardware interface are of the same type, e.g. effort commands for an effort-controlled joint.

Template Parameters
TType implementing the JointCommandInterface.

interface

Parameters
typehardware interface type.
jointsNames of the joints to control.

Subscribes to:

Definition at line 107 of file forward_joint_group_command_controller.h.

Constructor & Destructor Documentation

◆ ForwardJointGroupCommandController()

Definition at line 145 of file forward_joint_group_command_controller.h.

◆ ~ForwardJointGroupCommandController()

Definition at line 146 of file forward_joint_group_command_controller.h.

Member Function Documentation

◆ commandCB()

template<class T >
void forward_command_controller::ForwardJointGroupCommandController< T >::commandCB ( const std_msgs::Float64MultiArrayConstPtr &  msg)
inlineprivate

Definition at line 197 of file forward_joint_group_command_controller.h.

◆ init()

template<class T >
bool forward_command_controller::ForwardJointGroupCommandController< T >::init ( T *  hw,
ros::NodeHandle n 
)
inlinevirtual

◆ starting()

template<class T >
void forward_command_controller::ForwardJointGroupCommandController< T >::starting ( const ros::Time time)
virtual

◆ update()

template<class T >
void forward_command_controller::ForwardJointGroupCommandController< T >::update ( const ros::Time ,
const ros::Duration  
)
inlinevirtual

Member Data Documentation

◆ commands_buffer_

template<class T >
realtime_tools::RealtimeBuffer<std::vector<double> > forward_command_controller::ForwardJointGroupCommandController< T >::commands_buffer_

Definition at line 192 of file forward_joint_group_command_controller.h.

◆ joint_names_

template<class T >
std::vector< std::string > forward_command_controller::ForwardJointGroupCommandController< T >::joint_names_

Definition at line 190 of file forward_joint_group_command_controller.h.

◆ joints_

Definition at line 191 of file forward_joint_group_command_controller.h.

◆ n_joints_

template<class T >
unsigned int forward_command_controller::ForwardJointGroupCommandController< T >::n_joints_

Definition at line 193 of file forward_joint_group_command_controller.h.

◆ sub_command_

Definition at line 196 of file forward_joint_group_command_controller.h.


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


forward_command_controller
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Sun Mar 3 2024 03:19:16