This class defines a ros-control hardware interface. More...
#include <SVHRosControlHWInterface.h>
Public Member Functions | |
void | doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) |
virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) |
Initialize the hardware interface. More... | |
bool | isEnabled () const |
bool | isFault () |
Returns true, when at least one node in the hardware is in a fault state. More... | |
bool | prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
Read the state from the robot hardware. More... | |
SVHRosControlHWInterface () | |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
write the command to the robot hardware. More... | |
~SVHRosControlHWInterface () | |
![]() | |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual SwitchState | switchResult () const |
virtual SwitchState | switchResult (const ControllerInfo &) const |
virtual | ~RobotHW ()=default |
![]() | |
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) |
Private Attributes | |
bool | m_hardware_ready |
Additional Inherited Members | |
![]() | |
enum | SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR } |
![]() | |
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 |
This class defines a ros-control hardware interface.
Definition at line 51 of file SVHRosControlHWInterface.h.
SVHRosControlHWInterface::SVHRosControlHWInterface | ( | ) |
Definition at line 49 of file SVHRosControlHWInterface.cpp.
SVHRosControlHWInterface::~SVHRosControlHWInterface | ( | ) |
Definition at line 51 of file SVHRosControlHWInterface.cpp.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 184 of file SVHRosControlHWInterface.cpp.
|
virtual |
Initialize the hardware interface.
Reimplemented from hardware_interface::RobotHW.
Definition at line 54 of file SVHRosControlHWInterface.cpp.
bool SVHRosControlHWInterface::isEnabled | ( | ) | const |
Definition at line 191 of file SVHRosControlHWInterface.cpp.
|
inline |
Returns true, when at least one node in the hardware is in a fault state.
Definition at line 77 of file SVHRosControlHWInterface.h.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 177 of file SVHRosControlHWInterface.cpp.
|
virtual |
Read the state from the robot hardware.
Reimplemented from hardware_interface::RobotHW.
Definition at line 104 of file SVHRosControlHWInterface.cpp.
|
virtual |
write the command to the robot hardware.
Reimplemented from hardware_interface::RobotHW.
Definition at line 146 of file SVHRosControlHWInterface.cpp.
|
protected |
Definition at line 95 of file SVHRosControlHWInterface.h.
|
private |
Definition at line 108 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 101 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 98 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 103 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 99 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 96 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 105 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 89 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 97 of file SVHRosControlHWInterface.h.
|
protected |
Creates a joint_state message from the current joint angles and returns it.
Definition at line 84 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 94 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 92 of file SVHRosControlHWInterface.h.
|
protected |
Definition at line 90 of file SVHRosControlHWInterface.h.
|
protected |
Handle to the SVH finger manager for library access.
Definition at line 86 of file SVHRosControlHWInterface.h.