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

Single joint controller. More...

#include <forward_command_controller.h>

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

Public Member Functions

 ForwardCommandController ()
 
bool init (T *hw, ros::NodeHandle &n)
 
void starting (const ros::Time &time)
 
void update (const ros::Time &, const ros::Duration &)
 
 ~ForwardCommandController ()
 
- 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< double > command_buffer_
 
hardware_interface::JointHandle joint_
 
- Public Attributes inherited from controller_interface::ControllerBase
 ABORTED
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
 STOPPED
 
 WAITING
 

Private Member Functions

void commandCB (const std_msgs::Float64ConstPtr &msg)
 

Private Attributes

ros::Subscriber sub_command_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- 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::ForwardCommandController< T >

Single joint controller.

This class passes the command signal down to the joint. 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.
jointName of the joint to control.

Subscribes to:

Definition at line 68 of file forward_command_controller.h.

Constructor & Destructor Documentation

◆ ForwardCommandController()

Definition at line 71 of file forward_command_controller.h.

◆ ~ForwardCommandController()

Definition at line 72 of file forward_command_controller.h.

Member Function Documentation

◆ commandCB()

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

Definition at line 95 of file forward_command_controller.h.

◆ init()

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

Reimplemented from controller_interface::Controller< T >.

Definition at line 74 of file forward_command_controller.h.

◆ starting()

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

◆ update()

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

Implements controller_interface::ControllerBase.

Definition at line 88 of file forward_command_controller.h.

Member Data Documentation

◆ command_buffer_

Definition at line 91 of file forward_command_controller.h.

◆ joint_

Definition at line 90 of file forward_command_controller.h.

◆ sub_command_

template<class T >
ros::Subscriber forward_command_controller::ForwardCommandController< T >::sub_command_
private

Definition at line 94 of file forward_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 Fri Feb 3 2023 03:19:07