#include <khi_robot_hardware_interface.h>

Public Member Functions | |
| bool | activate () |
| void | close () |
| void | deactivate () |
| bool | getPeriodDiff (double &diff) |
| int | getStateTrigger () |
| bool | hold () |
| KhiRobotHardwareInterface () | |
| bool | open (const std::string &robot_name, const std::string &ip_address, const double &period, const bool in_simulation=false) |
| void | read (const ros::Time &time, const ros::Duration &period) override |
| int | updateState () |
| void | write (const ros::Time &time, const ros::Duration &period) override |
| ~KhiRobotHardwareInterface () | |
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 void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
| virtual bool | init (ros::NodeHandle &, ros::NodeHandle &) |
| virtual bool | prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
| virtual SwitchState | switchResult (const ControllerInfo &) const |
| virtual SwitchState | switchResult () 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) |
Additional Inherited Members | |
Public Types inherited from hardware_interface::RobotHW | |
| enum | SwitchState |
Public Attributes inherited from hardware_interface::RobotHW | |
| DONE | |
| ERROR | |
| ONGOING | |
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_ |
Definition at line 48 of file khi_robot_hardware_interface.h.
| khi_robot_control::KhiRobotHardwareInterface::KhiRobotHardwareInterface | ( | ) |
Definition at line 41 of file khi_robot_hardware_interface.cpp.
| khi_robot_control::KhiRobotHardwareInterface::~KhiRobotHardwareInterface | ( | ) |
Definition at line 45 of file khi_robot_hardware_interface.cpp.
| bool khi_robot_control::KhiRobotHardwareInterface::activate | ( | ) |
Definition at line 117 of file khi_robot_hardware_interface.cpp.
| void khi_robot_control::KhiRobotHardwareInterface::close | ( | ) |
Definition at line 133 of file khi_robot_hardware_interface.cpp.
| void khi_robot_control::KhiRobotHardwareInterface::deactivate | ( | ) |
Definition at line 128 of file khi_robot_hardware_interface.cpp.
| bool khi_robot_control::KhiRobotHardwareInterface::getPeriodDiff | ( | double & | diff | ) |
Definition at line 160 of file khi_robot_hardware_interface.cpp.
| int khi_robot_control::KhiRobotHardwareInterface::getStateTrigger | ( | ) |
Definition at line 155 of file khi_robot_hardware_interface.cpp.
| bool khi_robot_control::KhiRobotHardwareInterface::hold | ( | ) |
Definition at line 123 of file khi_robot_hardware_interface.cpp.
| bool khi_robot_control::KhiRobotHardwareInterface::open | ( | const std::string & | robot_name, |
| const std::string & | ip_address, | ||
| const double & | period, | ||
| const bool | in_simulation = false |
||
| ) |
Definition at line 51 of file khi_robot_hardware_interface.cpp.
|
overridevirtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 139 of file khi_robot_hardware_interface.cpp.
| int khi_robot_control::KhiRobotHardwareInterface::updateState | ( | ) |
Definition at line 150 of file khi_robot_hardware_interface.cpp.
|
overridevirtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 144 of file khi_robot_hardware_interface.cpp.
|
private |
Definition at line 71 of file khi_robot_hardware_interface.h.
|
private |
Definition at line 70 of file khi_robot_hardware_interface.h.
|
private |
Definition at line 68 of file khi_robot_hardware_interface.h.
|
private |
Definition at line 67 of file khi_robot_hardware_interface.h.
|
private |
Definition at line 66 of file khi_robot_hardware_interface.h.