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

List of all members.

Public Member Functions

 ForwardCommandController ()
bool init (T *hw, ros::NodeHandle &n)
void starting (const ros::Time &time)
void update (const ros::Time &time, const ros::Duration &period)
 ~ForwardCommandController ()

Public Attributes

double command_
hardware_interface::JointHandle joint_

Private Member Functions

void commandCB (const std_msgs::Float64ConstPtr &msg)

Private Attributes

ros::Subscriber sub_command_

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.

ROS

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

Definition at line 71 of file forward_command_controller.h.

Definition at line 72 of file forward_command_controller.h.


Member Function Documentation

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

Definition at line 95 of file forward_command_controller.h.

template<class T >
bool forward_command_controller::ForwardCommandController< T >::init ( T *  hw,
ros::NodeHandle n 
) [inline, virtual]

Reimplemented from controller_interface::Controller< T >.

Definition at line 74 of file forward_command_controller.h.

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

Reimplemented from controller_interface::ControllerBase.

Definition at line 87 of file forward_command_controller.h.

template<class T >
void forward_command_controller::ForwardCommandController< T >::update ( const ros::Time time,
const ros::Duration period 
) [inline, virtual]

Implements controller_interface::ControllerBase.

Definition at line 88 of file forward_command_controller.h.


Member Data Documentation

Definition at line 91 of file forward_command_controller.h.

Definition at line 90 of file forward_command_controller.h.

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 Aug 28 2015 12:36:42