#include <denso_robot_hw.h>
Public Member Functions | |
DensoRobotHW () | |
ros::Duration | getPeriod () const |
ros::Time | getTime () const |
HRESULT | Initialize () |
void | read (ros::Time, ros::Duration) |
void | write (ros::Time, ros::Duration) |
virtual | ~DensoRobotHW () |
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 | 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) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
RobotHW () | |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
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) |
Private Member Functions | |
void | Callback_ChangeMode (const Int32::ConstPtr &msg) |
void | Callback_HandIO (const Int32::ConstPtr &msg) |
void | Callback_MiniIO (const Int32::ConstPtr &msg) |
void | Callback_RecvUserIO (const UserIO::ConstPtr &msg) |
void | Callback_SendUserIO (const UserIO::ConstPtr &msg) |
HRESULT | ChangeModeWithClearError (int mode) |
HRESULT | CheckRobotType () |
Private Attributes | |
double | m_cmd [JOINT_MAX] |
DensoController_Ptr | m_ctrl |
double | m_eff [JOINT_MAX] |
DensoRobotCore_Ptr | m_eng |
hardware_interface::JointStateInterface | m_JntStInterface |
std::vector< double > | m_joint |
boost::mutex | m_mtxMode |
double | m_pos [JOINT_MAX] |
hardware_interface::PositionJointInterface | m_PosJntInterface |
ros::Publisher | m_pubCurMode |
ros::Publisher | m_pubCurrent |
ros::Publisher | m_pubHandIO |
ros::Publisher | m_pubMiniIO |
ros::Publisher | m_pubRecvUserIO |
int | m_recvfmt |
DensoRobotRC8_Ptr | m_rob |
int | m_robJoints |
std::string | m_robName |
int | m_sendfmt |
ros::Subscriber | m_subChangeMode |
ros::Subscriber | m_subHandIO |
ros::Subscriber | m_subMiniIO |
ros::Subscriber | m_subRecvUserIO |
ros::Subscriber | m_subSendUserIO |
int | m_type [JOINT_MAX] |
DensoVariable_Ptr | m_varErr |
double | m_vel [JOINT_MAX] |
Additional Inherited Members | |
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 | |
boost::ptr_vector< ResourceManagerBase > | interface_destruction_list_ |
InterfaceManagerVector | interface_managers_ |
InterfaceMap | interfaces_ |
InterfaceMap | interfaces_combo_ |
SizeMap | num_ifaces_registered_ |
ResourceMap | resources_ |
Definition at line 54 of file denso_robot_hw.h.
denso_robot_control::DensoRobotHW::DensoRobotHW | ( | ) |
Definition at line 38 of file denso_robot_hw.cpp.
|
virtual |
Definition at line 61 of file denso_robot_hw.cpp.
|
private |
Definition at line 280 of file denso_robot_hw.cpp.
|
private |
Definition at line 410 of file denso_robot_hw.cpp.
|
private |
Definition at line 405 of file denso_robot_hw.cpp.
|
private |
Definition at line 420 of file denso_robot_hw.cpp.
|
private |
Definition at line 415 of file denso_robot_hw.cpp.
|
private |
Definition at line 214 of file denso_robot_hw.cpp.
|
private |
Definition at line 291 of file denso_robot_hw.cpp.
|
inline |
Definition at line 67 of file denso_robot_hw.h.
|
inline |
Definition at line 62 of file denso_robot_hw.h.
HRESULT denso_robot_control::DensoRobotHW::Initialize | ( | ) |
Definition at line 66 of file denso_robot_hw.cpp.
void denso_robot_control::DensoRobotHW::read | ( | ros::Time | time, |
ros::Duration | period | ||
) |
Definition at line 315 of file denso_robot_hw.cpp.
void denso_robot_control::DensoRobotHW::write | ( | ros::Time | time, |
ros::Duration | period | ||
) |
Definition at line 342 of file denso_robot_hw.cpp.
|
private |
Definition at line 89 of file denso_robot_hw.h.
|
private |
Definition at line 97 of file denso_robot_hw.h.
|
private |
Definition at line 92 of file denso_robot_hw.h.
|
private |
Definition at line 96 of file denso_robot_hw.h.
|
private |
Definition at line 87 of file denso_robot_hw.h.
|
private |
Definition at line 94 of file denso_robot_hw.h.
|
private |
Definition at line 118 of file denso_robot_hw.h.
|
private |
Definition at line 90 of file denso_robot_hw.h.
|
private |
Definition at line 88 of file denso_robot_hw.h.
|
private |
Definition at line 112 of file denso_robot_hw.h.
|
private |
Definition at line 116 of file denso_robot_hw.h.
|
private |
Definition at line 114 of file denso_robot_hw.h.
|
private |
Definition at line 113 of file denso_robot_hw.h.
|
private |
Definition at line 115 of file denso_robot_hw.h.
|
private |
Definition at line 104 of file denso_robot_hw.h.
|
private |
Definition at line 98 of file denso_robot_hw.h.
|
private |
Definition at line 102 of file denso_robot_hw.h.
|
private |
Definition at line 101 of file denso_robot_hw.h.
|
private |
Definition at line 103 of file denso_robot_hw.h.
|
private |
Definition at line 106 of file denso_robot_hw.h.
|
private |
Definition at line 108 of file denso_robot_hw.h.
|
private |
Definition at line 107 of file denso_robot_hw.h.
|
private |
Definition at line 110 of file denso_robot_hw.h.
|
private |
Definition at line 109 of file denso_robot_hw.h.
|
private |
Definition at line 93 of file denso_robot_hw.h.
|
private |
Definition at line 99 of file denso_robot_hw.h.
|
private |
Definition at line 91 of file denso_robot_hw.h.