Single joint controller. More...
#include <forward_command_controller.h>

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 Attributes | |
| realtime_tools::RealtimeBuffer < double > | command_buffer_ |
| hardware_interface::JointHandle | joint_ |
Private Member Functions | |
| void | commandCB (const std_msgs::Float64ConstPtr &msg) |
Private Attributes | |
| ros::Subscriber | sub_command_ |
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.
| T | Type implementing the JointCommandInterface. |
| type | hardware interface type. |
| joint | Name of the joint to control. |
Subscribes to:
Definition at line 69 of file forward_command_controller.h.
| forward_command_controller::ForwardCommandController< T >::ForwardCommandController | ( | ) | [inline] |
Definition at line 72 of file forward_command_controller.h.
| forward_command_controller::ForwardCommandController< T >::~ForwardCommandController | ( | ) | [inline] |
Definition at line 73 of file forward_command_controller.h.
| void forward_command_controller::ForwardCommandController< T >::commandCB | ( | const std_msgs::Float64ConstPtr & | msg | ) | [inline, private] |
Definition at line 96 of file forward_command_controller.h.
| bool forward_command_controller::ForwardCommandController< T >::init | ( | T * | hw, |
| ros::NodeHandle & | n | ||
| ) | [inline, virtual] |
Reimplemented from controller_interface::Controller< T >.
Definition at line 75 of file forward_command_controller.h.
| void forward_command_controller::ForwardCommandController< T >::starting | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
| void forward_command_controller::ForwardCommandController< T >::update | ( | const ros::Time & | , |
| const ros::Duration & | |||
| ) | [inline, virtual] |
Implements controller_interface::ControllerBase.
Definition at line 89 of file forward_command_controller.h.
| realtime_tools::RealtimeBuffer<double> forward_command_controller::ForwardCommandController< T >::command_buffer_ |
Definition at line 92 of file forward_command_controller.h.
| hardware_interface::JointHandle forward_command_controller::ForwardCommandController< T >::joint_ |
Definition at line 91 of file forward_command_controller.h.
ros::Subscriber forward_command_controller::ForwardCommandController< T >::sub_command_ [private] |
Definition at line 95 of file forward_command_controller.h.