Controller with a specific hardware interface More...
#include <controller.h>
Public Member Functions | |
virtual bool | init (T *, ros::NodeHandle &) |
The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW. More... | |
virtual bool | init (T *, ros::NodeHandle &, ros::NodeHandle &) |
The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW. More... | |
Public Member Functions inherited from controller_interface::ControllerBase | |
ControllerBase ()=default | |
ControllerBase (const ControllerBase &)=delete | |
ControllerBase (ControllerBase &&)=delete | |
ControllerBase & | operator= (const ControllerBase &)=delete |
ControllerBase & | operator= (ControllerBase &&)=delete |
virtual | ~ControllerBase ()=default |
virtual void | starting (const ros::Time &) |
This is called from within the realtime thread just before the first call to update. More... | |
virtual void | update (const ros::Time &time, const ros::Duration &period)=0 |
This is called periodically by the realtime thread when the controller is running. More... | |
virtual void | stopping (const ros::Time &) |
This is called from within the realtime thread just after the last update call before the controller is stopped. More... | |
virtual void | waiting (const ros::Time &) |
This is called from within the realtime thread while the controller is waiting to start. More... | |
virtual void | aborting (const ros::Time &) |
This is called from within the realtime thread when the controller needs to be aborted. More... | |
bool | isInitialized () const |
Check if the controller is initialized. More... | |
bool | isRunning () const |
Check if the controller is running. More... | |
bool | isStopped () const |
Check if the controller is stopped. More... | |
bool | isWaiting () const |
Check if the controller is waiting. More... | |
bool | isAborted () const |
Check if the controller is aborted. More... | |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
Calls update only if this controller is running. More... | |
bool | startRequest (const ros::Time &time) |
Calls starting unless this controller is just constructed. More... | |
bool | stopRequest (const ros::Time &time) |
Calls stopping unless this controller is just constructed. More... | |
bool | waitRequest (const ros::Time &time) |
Calls waiting unless this controller is just constructed. More... | |
bool | abortRequest (const ros::Time &time) |
Calls abort unless this controller is just constructed. More... | |
Protected Member Functions | |
std::string | getHardwareInterfaceType () const |
Get the name of this controller's hardware interface type. More... | |
bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
Initialize the controller from a RobotHW pointer. More... | |
Additional Inherited Members | |
Public Types inherited from controller_interface::ControllerBase | |
enum | ControllerState { ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED, ControllerState::WAITING, ControllerState::ABORTED } |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
Public Attributes inherited from controller_interface::ControllerBase | |
ControllerState | state_ = ControllerState::CONSTRUCTED |
The current execution state of the controller. More... | |
Controller with a specific hardware interface
T | The hardware interface type used by this controller. This enforces semantic compatibility between the controller and the hardware it's meant to control. |
Definition at line 52 of file controller.h.
|
inlineprotected |
Get the name of this controller's hardware interface type.
Definition at line 134 of file controller.h.
|
inlinevirtual |
The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW.
hw | The specific hardware interface used by this controller. |
controller_nh | A NodeHandle in the namespace from which the controller should read its configuration, and where it should set up its ROS interface. |
Definition at line 69 of file controller.h.
|
inlinevirtual |
The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW.
hw | The specific hardware interface used by this controller. |
root_nh | A NodeHandle in the root of the controller manager namespace. This is where the ROS interfaces are setup (publishers, subscribers, services). |
controller_nh | A NodeHandle in the namespace of the controller. This is where the controller-specific configuration resides. |
Definition at line 86 of file controller.h.
|
inlineoverrideprotectedvirtual |
Initialize the controller from a RobotHW pointer.
This calls init with the hardware interface for this controller if it can extract the correct interface from robot_hw
.
Implements controller_interface::ControllerBase.
Definition at line 96 of file controller.h.