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 >
 Controller ()
 
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 
virtual ~Controller ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
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 ~ControllerBase ()
 

Public Attributes

realtime_tools::RealtimeBuffer< double > command_buffer_
 
hardware_interface::JointHandle joint_
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 

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
 
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 

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 69 of file forward_command_controller.h.

Constructor & Destructor Documentation

Definition at line 72 of file forward_command_controller.h.

Definition at line 73 of file forward_command_controller.h.

Member Function Documentation

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

Definition at line 96 of file forward_command_controller.h.

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 75 of file forward_command_controller.h.

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

Implements controller_interface::ControllerBase.

Definition at line 89 of file forward_command_controller.h.

Member Data Documentation

Definition at line 92 of file forward_command_controller.h.

Definition at line 91 of file forward_command_controller.h.

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

Definition at line 95 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 Sat Apr 18 2020 03:58:10