Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
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]

List of all members.

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 Attributes

realtime_tools::RealtimeBuffer
< std::vector< double > > 
commands_buffer_
std::vector< std::string > joint_names_
std::vector
< hardware_interface::JointHandle
joints_
unsigned int n_joints_

Private Member Functions

void commandCB (const std_msgs::Float64MultiArrayConstPtr &msg)

Private Attributes

ros::Subscriber sub_command_

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 73 of file forward_joint_group_command_controller.h.


Constructor & Destructor Documentation

Definition at line 76 of file forward_joint_group_command_controller.h.

Definition at line 77 of file forward_joint_group_command_controller.h.


Member Function Documentation

template<class T >
void forward_command_controller::ForwardJointGroupCommandController< T >::commandCB ( const std_msgs::Float64MultiArrayConstPtr &  msg) [inline, private]

Definition at line 128 of file forward_joint_group_command_controller.h.

template<class T >
bool forward_command_controller::ForwardJointGroupCommandController< T >::init ( T *  hw,
ros::NodeHandle n 
) [inline, virtual]
template<class T >
void forward_command_controller::ForwardJointGroupCommandController< T >::starting ( const ros::Time time) [virtual]
template<class T >
void forward_command_controller::ForwardJointGroupCommandController< T >::update ( const ros::Time ,
const ros::Duration  
) [inline, virtual]

Member Data Documentation

Definition at line 123 of file forward_joint_group_command_controller.h.

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

Definition at line 121 of file forward_joint_group_command_controller.h.

Definition at line 122 of file forward_joint_group_command_controller.h.

Definition at line 124 of file forward_joint_group_command_controller.h.

Definition at line 127 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 Thu Jun 6 2019 18:58:53