Robot Hardware Interface and Resource Manager. More...
#include <robot_hw.h>
Public Member Functions | |
virtual bool | init (ros::NodeHandle &, ros::NodeHandle &) |
The init function is called to initialize the RobotHW from a non-realtime thread. More... | |
virtual | ~RobotHW ()=default |
Resource Management | |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
Control Loop | |
virtual void | read (const ros::Time &, const ros::Duration &) |
Read data from the robot hardware. More... | |
virtual void | write (const ros::Time &, const ros::Duration &) |
Write commands to the robot hardware. More... | |
Public Member Functions inherited from hardware_interface::InterfaceManager | |
template<class T > | |
T * | get () |
Get an interface. More... | |
std::vector< std::string > | getInterfaceResources (std::string iface_type) const |
Get the resource names registered to an interface, specified by type. More... | |
std::vector< std::string > | getNames () const |
Lists the demangled names of all registered interfaces. More... | |
template<class T > | |
void | registerInterface (T *iface) |
Register an interface. More... | |
void | registerInterfaceManager (InterfaceManager *iface_man) |
Register another interface manager. More... | |
Hardware Interface Switching | |
enum | SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR } |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
virtual SwitchState | switchResult () const |
Return (in realtime) the state of the last doSwitch(). More... | |
virtual SwitchState | switchResult (const ControllerInfo &) const |
Return (in realtime) the state of the last doSwitch() for a given controller. More... | |
Additional Inherited Members | |
Protected Types inherited from hardware_interface::InterfaceManager | |
typedef std::vector< InterfaceManager * > | InterfaceManagerVector |
typedef std::map< std::string, void * > | InterfaceMap |
typedef std::map< std::string, std::vector< std::string > > | ResourceMap |
typedef std::map< std::string, size_t > | SizeMap |
Protected Attributes inherited from hardware_interface::InterfaceManager | |
std::vector< ResourceManagerBase * > | interface_destruction_list_ |
InterfaceManagerVector | interface_managers_ |
InterfaceMap | interfaces_ |
InterfaceMap | interfaces_combo_ |
SizeMap | num_ifaces_registered_ |
ResourceMap | resources_ |
This will allow us to check the resources based on the demangled type name of the interface. More... | |
Robot Hardware Interface and Resource Manager.
This class provides a standardized interface to a set of robot hardware interfaces to the controller manager. It performs resource conflict checking for a given set of controllers and maintains a map of hardware interfaces. It is meant to be used as a base class for abstracting custom robot hardware.
The hardware interface map (interfaces_) is a 1-to-1 map between the names of interface types derived from HardwareInterface and instances of those interface types.
A class derived from this base interface represents a robot and stores the state of the robot's hardware resources (joints, sensors, actuators) and outgoing commands in its data member arrays. The names of these members should provide semantic meaning (e.g. pos, vel, eff, cmd). Commands from controllers are populated by the controller's update method, (controller_interface::ControllerBase::update()). For each resource a JointStateHandle (for read only joints), JointHandle (for read and write joints) or custom handle can be used which is registered (hardware_interface::ResourceManager::registerHandle) with one of the robot's interface types. Note that JointStateHandle should be preferred in case only reading from the joint is required because it doesn't create conflicts between controllers. For read-only joints it is possible to use JointStateInterface and for joints that accept commands and provide feedback (read and write) JointCommandInterface can be used or one of its derived interfaces (e.g. PositionJointInterface). Another option is to define and use custom ones. The interfaces themselfes are then registered (registerInterface) with the derived robot class. The registration (registerInterface) of interfaces can be done either in the constructor or init of a custom robot hardware class.
Definition at line 78 of file robot_hw.h.
|
strong |
Enumerator | |
---|---|
DONE | |
ONGOING | |
ERROR |
Definition at line 167 of file robot_hw.h.
|
virtualdefault |
|
inlinevirtual |
Check (in non-realtime) if the given set of controllers is allowed to run simultaneously.
This default implementation simply checks if any two controllers use the same resource.
Definition at line 113 of file robot_hw.h.
|
inlinevirtual |
Perform (in realtime) all necessary hardware interface switches in order to start and stop the given controllers. Start and stop list are disjoint. The feasability was checked in prepareSwitch() beforehand.
Definition at line 164 of file robot_hw.h.
|
inlinevirtual |
The init function is called to initialize the RobotHW from a non-realtime thread.
Initialising a custom robot is done by registering joint handles (hardware_interface::ResourceManager::registerHandle) to hardware interfaces that group similar joints and registering those individual hardware interfaces with the class that represents the custom robot (derived from this hardware_interface::RobotHW)
root_nh | A NodeHandle in the root of the caller namespace. |
robot_hw_nh | A NodeHandle in the namespace from which the RobotHW should read its configuration. |
Definition at line 102 of file robot_hw.h.
|
inlinevirtual |
Check (in non-realtime) if given controllers could be started and stopped from the current state of the RobotHW with regard to necessary hardware interface switches and prepare the switching. Start and stop list are disjoint. This handles the check and preparation, the actual switch is commited in doSwitch().
Definition at line 157 of file robot_hw.h.
|
inlinevirtual |
Read data from the robot hardware.
The read method is part of the control loop cycle (read, update, write) and is used to populate the robot state from the robot's hardware resources (joints, sensors, actuators). This method should be called before controller_manager::ControllerManager::update() and write.
Querying WallTime inside read is not realtime safe. The parameters time and period make it possible to inject time from a realtime source.
time | The current time |
period | The time passed since the last call to read |
Definition at line 206 of file robot_hw.h.
|
inlinevirtual |
Return (in realtime) the state of the last doSwitch().
Definition at line 175 of file robot_hw.h.
|
inlinevirtual |
Return (in realtime) the state of the last doSwitch() for a given controller.
Definition at line 181 of file robot_hw.h.
|
inlinevirtual |
Write commands to the robot hardware.
The write method is part of the control loop cycle (read, update, write) and is used to send out commands to the robot's hardware resources (joints, actuators). This method should be called after read and controller_manager::ControllerManager::update.
Querying WallTime inside write is not realtime safe. The parameters time and period make it possible to inject time from a realtime source.
time | The current time |
period | The time passed since the last call to write |
Definition at line 224 of file robot_hw.h.