Forward command controller for a set of joints. More...
#include <forward_joint_group_command_controller.h>
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 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 |
ControllerBase & | operator= (const ControllerBase &)=delete |
ControllerBase & | operator= (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< std::vector< double > > | commands_buffer_ |
std::vector< std::string > | joint_names_ |
std::vector< hardware_interface::JointHandle > | joints_ |
unsigned int | n_joints_ |
Public Attributes inherited from controller_interface::ControllerBase | |
ControllerState | state_ |
Private Member Functions | |
void | commandCB (const std_msgs::Float64MultiArrayConstPtr &msg) |
Private Attributes | |
ros::Subscriber | sub_command_ |
Additional Inherited Members | |
Public Types inherited from controller_interface::ControllerBase | |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
enum | ControllerState { ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED, ControllerState::WAITING, ControllerState::ABORTED } |
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 |
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.
T | Type implementing the JointCommandInterface. |
type | hardware interface type. |
joints | Names of the joints to control. |
Subscribes to:
Definition at line 107 of file forward_joint_group_command_controller.h.
|
inline |
Definition at line 145 of file forward_joint_group_command_controller.h.
|
inline |
Definition at line 146 of file forward_joint_group_command_controller.h.
|
inlineprivate |
Definition at line 197 of file forward_joint_group_command_controller.h.
|
inlinevirtual |
Reimplemented from controller_interface::Controller< T >.
Definition at line 148 of file forward_joint_group_command_controller.h.
|
virtual |
Reimplemented from controller_interface::ControllerBase.
|
inlinevirtual |
Implements controller_interface::ControllerBase.
Definition at line 183 of file forward_joint_group_command_controller.h.
realtime_tools::RealtimeBuffer<std::vector<double> > forward_command_controller::ForwardJointGroupCommandController< T >::commands_buffer_ |
Definition at line 192 of file forward_joint_group_command_controller.h.
std::vector< std::string > forward_command_controller::ForwardJointGroupCommandController< T >::joint_names_ |
Definition at line 190 of file forward_joint_group_command_controller.h.
std::vector< hardware_interface::JointHandle > forward_command_controller::ForwardJointGroupCommandController< T >::joints_ |
Definition at line 191 of file forward_joint_group_command_controller.h.
unsigned int forward_command_controller::ForwardJointGroupCommandController< T >::n_joints_ |
Definition at line 193 of file forward_joint_group_command_controller.h.
|
private |
Definition at line 196 of file forward_joint_group_command_controller.h.