Hardware interface for a robot. More...
#include <generic_hw_interface.h>

Public Member Functions | |
| virtual bool | canSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) const |
| 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. Start and stop list are disjoint. This is just a check, the actual switch is done in doSwitch() More... | |
| virtual void | doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) |
| Perform (in non-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 canSwitch() beforehand. More... | |
| virtual void | enforceLimits (ros::Duration &period)=0 |
| GenericHWInterface (const ros::NodeHandle &nh, urdf::Model *urdf_model=NULL) | |
| Constructor. More... | |
| virtual void | init () |
| Initialize the hardware interface. More... | |
| std::string | printCommandHelper () |
| Helper for debugging a joint's command. More... | |
| virtual void | printState () |
| Helper for debugging a joint's state. More... | |
| std::string | printStateHelper () |
| virtual void | read (const ros::Time &, const ros::Duration &period) override |
| Read the state from the robot hardware. More... | |
| virtual void | read (ros::Duration &elapsed_time)=0 |
| Read the state from the robot hardware. More... | |
| virtual void | registerJointLimits (const hardware_interface::JointHandle &joint_handle_position, const hardware_interface::JointHandle &joint_handle_velocity, const hardware_interface::JointHandle &joint_handle_effort, std::size_t joint_id) |
| Register the limits of the joint specified by joint_id and joint_handle. The limits are retrieved from the urdf_model. More... | |
| virtual void | reset () |
| Set all members to default values. More... | |
| virtual void | write (const ros::Time &, const ros::Duration &period) override |
| Write the command to the robot hardware. More... | |
| virtual void | write (ros::Duration &elapsed_time)=0 |
| Write the command to the robot hardware. More... | |
| virtual | ~GenericHWInterface () |
| Destructor. More... | |
Public Member Functions inherited from hardware_interface::RobotHW | |
| virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
| virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
| virtual bool | init (ros::NodeHandle &, ros::NodeHandle &) |
| virtual bool | prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
| virtual SwitchState | switchResult () const |
| virtual SwitchState | switchResult (const ControllerInfo &) const |
| virtual | ~RobotHW ()=default |
Public Member Functions inherited from hardware_interface::InterfaceManager | |
| T * | get () |
| std::vector< std::string > | getInterfaceResources (std::string iface_type) const |
| std::vector< std::string > | getNames () const |
| void | registerInterface (T *iface) |
| void | registerInterfaceManager (InterfaceManager *iface_man) |
Protected Member Functions | |
| virtual void | loadURDF (const ros::NodeHandle &nh, std::string param_name) |
| Get the URDF XML from the parameter server. More... | |
Additional Inherited Members | |
Public Types inherited from hardware_interface::RobotHW | |
| enum | SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR } |
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 |
Hardware interface for a robot.
Definition at line 92 of file generic_hw_interface.h.
| ros_control_boilerplate::GenericHWInterface::GenericHWInterface | ( | const ros::NodeHandle & | nh, |
| urdf::Model * | urdf_model = NULL |
||
| ) |
Constructor.
| nh | - Node handle for topics. |
| urdf | - optional pointer to a parsed robot model |
Definition at line 79 of file generic_hw_interface.cpp.
|
inlinevirtual |
Destructor.
Definition at line 135 of file generic_hw_interface.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. Start and stop list are disjoint. This is just a check, the actual switch is done in doSwitch()
Definition at line 183 of file generic_hw_interface.h.
|
inlinevirtual |
Perform (in non-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 canSwitch() beforehand.
Reimplemented from hardware_interface::RobotHW.
Definition at line 194 of file generic_hw_interface.h.
|
pure virtual |
\breif Enforce limits for all values before writing
Implemented in ros_control_boilerplate::SimHWInterface, and rrbot_control::RRBotHWInterface.
|
virtual |
Initialize the hardware interface.
Reimplemented in ros_control_boilerplate::SimHWInterface.
Definition at line 96 of file generic_hw_interface.cpp.
|
protectedvirtual |
Get the URDF XML from the parameter server.
Definition at line 332 of file generic_hw_interface.cpp.
| std::string ros_control_boilerplate::GenericHWInterface::printCommandHelper | ( | ) |
Helper for debugging a joint's command.
Definition at line 318 of file generic_hw_interface.cpp.
|
virtual |
Helper for debugging a joint's state.
Definition at line 297 of file generic_hw_interface.cpp.
| std::string ros_control_boilerplate::GenericHWInterface::printStateHelper | ( | ) |
Definition at line 304 of file generic_hw_interface.cpp.
|
inlineoverridevirtual |
Read the state from the robot hardware.
| time | The current time, currently unused |
| period | The time passed since the last call |
Reimplemented from hardware_interface::RobotHW.
Definition at line 152 of file generic_hw_interface.h.
|
pure virtual |
Read the state from the robot hardware.
Implemented in ros_control_boilerplate::SimHWInterface, and rrbot_control::RRBotHWInterface.
|
virtual |
Register the limits of the joint specified by joint_id and joint_handle. The limits are retrieved from the urdf_model.
Definition at line 151 of file generic_hw_interface.cpp.
|
virtual |
Set all members to default values.
Definition at line 290 of file generic_hw_interface.cpp.
|
inlineoverridevirtual |
Write the command to the robot hardware.
| time | The current time, currently unused |
| period | The time passed since the last call |
Reimplemented from hardware_interface::RobotHW.
Definition at line 168 of file generic_hw_interface.h.
|
pure virtual |
Write the command to the robot hardware.
Implemented in ros_control_boilerplate::SimHWInterface, and rrbot_control::RRBotHWInterface.
|
protected |
Definition at line 238 of file generic_hw_interface.h.
|
protected |
Definition at line 243 of file generic_hw_interface.h.
|
protected |
Definition at line 233 of file generic_hw_interface.h.
|
protected |
Definition at line 257 of file generic_hw_interface.h.
|
protected |
Definition at line 262 of file generic_hw_interface.h.
|
protected |
Definition at line 268 of file generic_hw_interface.h.
|
protected |
Definition at line 246 of file generic_hw_interface.h.
|
protected |
Definition at line 255 of file generic_hw_interface.h.
|
protected |
Definition at line 260 of file generic_hw_interface.h.
|
protected |
Definition at line 265 of file generic_hw_interface.h.
|
protected |
Definition at line 266 of file generic_hw_interface.h.
|
protected |
Definition at line 230 of file generic_hw_interface.h.
|
protected |
Definition at line 256 of file generic_hw_interface.h.
|
protected |
Definition at line 261 of file generic_hw_interface.h.
|
protected |
Definition at line 267 of file generic_hw_interface.h.
|
protected |
Definition at line 224 of file generic_hw_interface.h.
|
protected |
Definition at line 227 of file generic_hw_interface.h.
|
protected |
Definition at line 247 of file generic_hw_interface.h.
|
protected |
Definition at line 236 of file generic_hw_interface.h.
|
protected |
Definition at line 241 of file generic_hw_interface.h.
|
protected |
Definition at line 231 of file generic_hw_interface.h.
|
protected |
Definition at line 248 of file generic_hw_interface.h.
|
protected |
Definition at line 251 of file generic_hw_interface.h.
|
protected |
Definition at line 252 of file generic_hw_interface.h.
|
protected |
Definition at line 237 of file generic_hw_interface.h.
|
protected |
Definition at line 242 of file generic_hw_interface.h.
|
protected |
Definition at line 232 of file generic_hw_interface.h.