Public Member Functions | Private Attributes | List of all members
khi_robot_control::KhiRobotHardwareInterface Class Reference

#include <khi_robot_hardware_interface.h>

Inheritance diagram for khi_robot_control::KhiRobotHardwareInterface:
Inheritance graph
[legend]

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
 
virtual SwitchState switchResult (const ControllerInfo &) 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)
 

Private Attributes

khi_robot_control::KhiRobotClientclient
 
khi_robot_control::KhiRobotData data
 
joint_limits_interface::PositionJointSaturationInterface joint_limit_interface
 
hardware_interface::PositionJointInterface joint_position_interface
 
hardware_interface::JointStateInterface joint_state_interface
 

Additional Inherited Members

- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR }
 
- 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_
 

Detailed Description

Definition at line 80 of file khi_robot_hardware_interface.h.

Constructor & Destructor Documentation

◆ KhiRobotHardwareInterface()

khi_robot_control::KhiRobotHardwareInterface::KhiRobotHardwareInterface ( )

Definition at line 73 of file khi_robot_hardware_interface.cpp.

◆ ~KhiRobotHardwareInterface()

khi_robot_control::KhiRobotHardwareInterface::~KhiRobotHardwareInterface ( )

Definition at line 77 of file khi_robot_hardware_interface.cpp.

Member Function Documentation

◆ activate()

bool khi_robot_control::KhiRobotHardwareInterface::activate ( )

Definition at line 149 of file khi_robot_hardware_interface.cpp.

◆ close()

void khi_robot_control::KhiRobotHardwareInterface::close ( )

Definition at line 165 of file khi_robot_hardware_interface.cpp.

◆ deactivate()

void khi_robot_control::KhiRobotHardwareInterface::deactivate ( )

Definition at line 160 of file khi_robot_hardware_interface.cpp.

◆ getPeriodDiff()

bool khi_robot_control::KhiRobotHardwareInterface::getPeriodDiff ( double &  diff)

Definition at line 192 of file khi_robot_hardware_interface.cpp.

◆ getStateTrigger()

int khi_robot_control::KhiRobotHardwareInterface::getStateTrigger ( )

Definition at line 187 of file khi_robot_hardware_interface.cpp.

◆ hold()

bool khi_robot_control::KhiRobotHardwareInterface::hold ( )

Definition at line 155 of file khi_robot_hardware_interface.cpp.

◆ open()

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 83 of file khi_robot_hardware_interface.cpp.

◆ read()

void khi_robot_control::KhiRobotHardwareInterface::read ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 171 of file khi_robot_hardware_interface.cpp.

◆ updateState()

int khi_robot_control::KhiRobotHardwareInterface::updateState ( )

Definition at line 182 of file khi_robot_hardware_interface.cpp.

◆ write()

void khi_robot_control::KhiRobotHardwareInterface::write ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 176 of file khi_robot_hardware_interface.cpp.

Member Data Documentation

◆ client

khi_robot_control::KhiRobotClient* khi_robot_control::KhiRobotHardwareInterface::client
private

Definition at line 135 of file khi_robot_hardware_interface.h.

◆ data

khi_robot_control::KhiRobotData khi_robot_control::KhiRobotHardwareInterface::data
private

Definition at line 134 of file khi_robot_hardware_interface.h.

◆ joint_limit_interface

joint_limits_interface::PositionJointSaturationInterface khi_robot_control::KhiRobotHardwareInterface::joint_limit_interface
private

Definition at line 132 of file khi_robot_hardware_interface.h.

◆ joint_position_interface

hardware_interface::PositionJointInterface khi_robot_control::KhiRobotHardwareInterface::joint_position_interface
private

Definition at line 131 of file khi_robot_hardware_interface.h.

◆ joint_state_interface

hardware_interface::JointStateInterface khi_robot_control::KhiRobotHardwareInterface::joint_state_interface
private

Definition at line 130 of file khi_robot_hardware_interface.h.


The documentation for this class was generated from the following files:


khi_robot_control
Author(s): nakamichi_d
autogenerated on Sat Oct 21 2023 02:54:50