#include <xarm_hw.h>

Public Member Functions | |
| void | get_status (int state_mode_err[3]) |
| virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) |
| bool | need_reset () |
| virtual void | read (const ros::Time &time, const ros::Duration &period) |
| virtual void | write (const ros::Time &time, const ros::Duration &period) |
| XArmHW () | |
| ~XArmHW () | |
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 void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
| 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 Types | |
| enum | ControlMethod { POSITION, VELOCITY, EFFORT } |
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 |
Private Member Functions | |
| void | _enforce_limits (const ros::Duration &period) |
| void | _register_joint_limits (ros::NodeHandle &root_nh, std::string joint_name, const ControlMethod ctrl_method) |
| void | _reset_limits (void) |
| void | clientInit (const std::string &robot_ip, ros::NodeHandle &root_nh) |
| void | pos_fb_cb (const sensor_msgs::JointState::ConstPtr &data) |
| void | state_fb_cb (const xarm_msgs::RobotMsg::ConstPtr &data) |
Additional Inherited Members | |
Protected Attributes inherited from hardware_interface::InterfaceManager | |
| boost::ptr_vector< ResourceManagerBase > | interface_destruction_list_ |
| InterfaceManagerVector | interface_managers_ |
| InterfaceMap | interfaces_ |
| InterfaceMap | interfaces_combo_ |
| SizeMap | num_ifaces_registered_ |
| ResourceMap | resources_ |
|
protected |
| xarm_control::XArmHW::~XArmHW | ( | ) |
Definition at line 195 of file xarm_hw.cpp.
|
private |
Definition at line 224 of file xarm_hw.cpp.
|
private |
Definition at line 12 of file xarm_hw.cpp.
|
private |
Definition at line 218 of file xarm_hw.cpp.
|
private |
Definition at line 68 of file xarm_hw.cpp.
| void xarm_control::XArmHW::get_status | ( | int | state_mode_err[3] | ) |
Definition at line 314 of file xarm_hw.cpp.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 142 of file xarm_hw.cpp.
| bool xarm_control::XArmHW::need_reset | ( | ) |
Definition at line 321 of file xarm_hw.cpp.
|
private |
Definition at line 200 of file xarm_hw.cpp.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 250 of file xarm_hw.cpp.
|
private |
Definition at line 211 of file xarm_hw.cpp.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 255 of file xarm_hw.cpp.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |