#include <khi_robot_hardware_interface.h>
|
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 () |
|
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 void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
|
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 () |
|
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) |
|
khi_robot_control::KhiRobotHardwareInterface::KhiRobotHardwareInterface |
( |
| ) |
|
khi_robot_control::KhiRobotHardwareInterface::~KhiRobotHardwareInterface |
( |
| ) |
|
bool khi_robot_control::KhiRobotHardwareInterface::activate |
( |
| ) |
|
void khi_robot_control::KhiRobotHardwareInterface::close |
( |
| ) |
|
void khi_robot_control::KhiRobotHardwareInterface::deactivate |
( |
| ) |
|
bool khi_robot_control::KhiRobotHardwareInterface::getPeriodDiff |
( |
double & |
diff | ) |
|
int khi_robot_control::KhiRobotHardwareInterface::getStateTrigger |
( |
| ) |
|
bool khi_robot_control::KhiRobotHardwareInterface::hold |
( |
| ) |
|
bool khi_robot_control::KhiRobotHardwareInterface::open |
( |
const std::string & |
robot_name, |
|
|
const std::string & |
ip_address, |
|
|
const double & |
period, |
|
|
const bool |
in_simulation = false |
|
) |
| |
void khi_robot_control::KhiRobotHardwareInterface::read |
( |
const ros::Time & |
time, |
|
|
const ros::Duration & |
period |
|
) |
| |
|
overridevirtual |
int khi_robot_control::KhiRobotHardwareInterface::updateState |
( |
| ) |
|
void khi_robot_control::KhiRobotHardwareInterface::write |
( |
const ros::Time & |
time, |
|
|
const ros::Duration & |
period |
|
) |
| |
|
overridevirtual |
The documentation for this class was generated from the following files: