Hardware interface for a robot. More...
#include <sim_hw_interface.h>
Public Member Functions | |
virtual void | enforceLimits (ros::Duration &period) |
virtual void | init () |
Initialize the robot hardware interface. More... | |
virtual void | read (ros::Duration &elapsed_time) |
Read the state from the robot hardware. More... | |
SimHWInterface (ros::NodeHandle &nh, urdf::Model *urdf_model=NULL) | |
Constructor. More... | |
virtual void | write (ros::Duration &elapsed_time) |
Write the command to the robot hardware. More... | |
Public Member Functions inherited from ros_control_boilerplate::GenericHWInterface | |
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... | |
GenericHWInterface (const ros::NodeHandle &nh, urdf::Model *urdf_model=NULL) | |
Constructor. 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 | 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 | ~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 | positionControlSimulation (ros::Duration &elapsed_time, const std::size_t joint_id) |
Basic model of system for position control. More... | |
Protected Member Functions inherited from ros_control_boilerplate::GenericHWInterface | |
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 49 of file sim_hw_interface.h.
ros_control_boilerplate::SimHWInterface::SimHWInterface | ( | ros::NodeHandle & | nh, |
urdf::Model * | urdf_model = NULL |
||
) |
Constructor.
nh | - Node handle for topics. |
Definition at line 47 of file sim_hw_interface.cpp.
|
virtual |
Enforce limits for all values before writing
Implements ros_control_boilerplate::GenericHWInterface.
Definition at line 121 of file sim_hw_interface.cpp.
|
virtual |
Initialize the robot hardware interface.
Reimplemented from ros_control_boilerplate::GenericHWInterface.
Definition at line 63 of file sim_hw_interface.cpp.
|
protectedvirtual |
Basic model of system for position control.
Definition at line 127 of file sim_hw_interface.cpp.
|
virtual |
Read the state from the robot hardware.
Implements ros_control_boilerplate::GenericHWInterface.
Definition at line 74 of file sim_hw_interface.cpp.
|
virtual |
Write the command to the robot hardware.
Implements ros_control_boilerplate::GenericHWInterface.
Definition at line 79 of file sim_hw_interface.cpp.
|
protected |
Definition at line 83 of file sim_hw_interface.h.
|
protected |
Definition at line 76 of file sim_hw_interface.h.
|
protected |
Definition at line 79 of file sim_hw_interface.h.
|
protected |
Definition at line 86 of file sim_hw_interface.h.
|
protected |
Definition at line 80 of file sim_hw_interface.h.