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 (ros::Duration &elapsed_time)=0 |
Read the state from the robot hardware. More... | |
virtual void | read (const ros::Time &, const ros::Duration &period) override |
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 (ros::Duration &elapsed_time)=0 |
Write the command to the robot hardware. More... | |
virtual void | write (const ros::Time &, const ros::Duration &period) override |
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 &root_nh, ros::NodeHandle &robot_hw_nh) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
RobotHW () | |
virtual | ~RobotHW () |
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 | |
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 64 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 47 of file generic_hw_interface.cpp.
|
inlinevirtual |
Destructor.
Definition at line 75 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 121 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 132 of file generic_hw_interface.h.
|
pure virtual |
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 66 of file generic_hw_interface.cpp.
|
protectedvirtual |
Get the URDF XML from the parameter server.
Definition at line 304 of file generic_hw_interface.cpp.
std::string ros_control_boilerplate::GenericHWInterface::printCommandHelper | ( | ) |
Helper for debugging a joint's command.
Definition at line 290 of file generic_hw_interface.cpp.
|
virtual |
Helper for debugging a joint's state.
Definition at line 268 of file generic_hw_interface.cpp.
std::string ros_control_boilerplate::GenericHWInterface::printStateHelper | ( | ) |
Definition at line 276 of file generic_hw_interface.cpp.
|
pure virtual |
Read the state from the robot hardware.
Implemented in ros_control_boilerplate::SimHWInterface, and rrbot_control::RRBotHWInterface.
|
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 90 of file generic_hw_interface.h.
|
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 121 of file generic_hw_interface.cpp.
|
virtual |
Set all members to default values.
Definition at line 261 of file generic_hw_interface.cpp.
|
pure virtual |
Write the command to the robot hardware.
Implemented in ros_control_boilerplate::SimHWInterface, and rrbot_control::RRBotHWInterface.
|
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 106 of file generic_hw_interface.h.
|
protected |
Definition at line 178 of file generic_hw_interface.h.
|
protected |
Definition at line 183 of file generic_hw_interface.h.
|
protected |
Definition at line 173 of file generic_hw_interface.h.
|
protected |
Definition at line 197 of file generic_hw_interface.h.
|
protected |
Definition at line 202 of file generic_hw_interface.h.
|
protected |
Definition at line 208 of file generic_hw_interface.h.
|
protected |
Definition at line 186 of file generic_hw_interface.h.
|
protected |
Definition at line 195 of file generic_hw_interface.h.
|
protected |
Definition at line 200 of file generic_hw_interface.h.
|
protected |
Definition at line 205 of file generic_hw_interface.h.
|
protected |
Definition at line 206 of file generic_hw_interface.h.
|
protected |
Definition at line 170 of file generic_hw_interface.h.
|
protected |
Definition at line 196 of file generic_hw_interface.h.
|
protected |
Definition at line 201 of file generic_hw_interface.h.
|
protected |
Definition at line 207 of file generic_hw_interface.h.
|
protected |
Definition at line 164 of file generic_hw_interface.h.
|
protected |
Definition at line 167 of file generic_hw_interface.h.
|
protected |
Definition at line 187 of file generic_hw_interface.h.
|
protected |
Definition at line 176 of file generic_hw_interface.h.
|
protected |
Definition at line 181 of file generic_hw_interface.h.
|
protected |
Definition at line 171 of file generic_hw_interface.h.
|
protected |
Definition at line 188 of file generic_hw_interface.h.
|
protected |
Definition at line 191 of file generic_hw_interface.h.
|
protected |
Definition at line 192 of file generic_hw_interface.h.
|
protected |
Definition at line 177 of file generic_hw_interface.h.
|
protected |
Definition at line 182 of file generic_hw_interface.h.
|
protected |
Definition at line 172 of file generic_hw_interface.h.