#include <dxlport_control.h>

| Public Member Functions | |
| DXLPORT_CONTROL (ros::NodeHandle handle, CONTROL_SETTING &setting) | |
| void | effort_limitter (void) | 
| std::string::size_type | get_error (std::string &errorlog) | 
| bool | get_init_stat (void) | 
| uint8_t | get_joint_num (void) | 
| ros::Duration | getDuration (ros::Time t) const | 
| ros::Time | getTime () const | 
| void | init_joint_params (ST_JOINT_PARAM ¶m, int table_id, int value) | 
| bool | is_change_positions (void) | 
| bool | read (ros::Time, ros::Duration) | 
| void | readCurrent (ros::Time, ros::Duration) | 
| void | readPos (ros::Time, ros::Duration) | 
| void | readTemp (ros::Time, ros::Duration) | 
| void | readVel (ros::Time, ros::Duration) | 
| std::string | self_check (void) | 
| void | set_gain (uint8_t dxl_id, uint16_t gain) | 
| void | set_gain_all (uint16_t gain) | 
| void | set_goal_current (uint8_t dxl_id, uint16_t current) | 
| void | set_goal_current_all (uint16_t current) | 
| void | set_param_current_limit (uint8_t dxl_id, int val) | 
| void | set_param_delay_time (uint8_t dxl_id, int val) | 
| void | set_param_drive_mode (uint8_t dxl_id, int val) | 
| void | set_param_home_offset (uint8_t dxl_id, int val) | 
| void | set_param_moving_threshold (uint8_t dxl_id, int val) | 
| void | set_param_ope_mode (uint8_t dxl_id, int val) | 
| void | set_param_pos_gain (uint8_t dxl_id, int p, int i, int d) | 
| void | set_param_pos_gain_all (int p, int i, int d) | 
| void | set_param_temp_limit (uint8_t dxl_id, int val) | 
| void | set_param_vel_gain (uint8_t dxl_id, int p, int i) | 
| void | set_param_vol_limit (uint8_t dxl_id, int max, int min) | 
| bool | set_torque (uint8_t dxl_id, bool torque) | 
| void | set_torque_all (bool torque) | 
| void | set_watchdog (uint8_t dxl_id, uint8_t value) | 
| void | set_watchdog_all (uint8_t value) | 
| void | startup_motion (void) | 
| void | write (ros::Time, ros::Duration) | 
| ~DXLPORT_CONTROL () | |
|  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 void | read (const ros::Time &, const ros::Duration &) | 
| virtual void | read (const ros::Time &, const ros::Duration &) | 
| virtual SwitchState | switchResult () const | 
| virtual SwitchState | switchResult (const ControllerInfo &) const | 
| virtual void | write (const ros::Time &, const ros::Duration &) | 
| virtual void | write (const ros::Time &, const ros::Duration &) | 
| 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) | 
| Public Attributes | |
| std::vector< JOINT_CONTROL > | joints | 
| uint32_t | tempCount | 
| Private Member Functions | |
| bool | check_servo_param (uint8_t dxl_id, uint32_t test_addr, uint16_t equal, uint16_t &read_val) | 
| bool | check_servo_param (uint8_t dxl_id, uint32_t test_addr, uint32_t equal, uint32_t &read_val) | 
| bool | check_servo_param (uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t &read_val) | 
| 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_ | 
Definition at line 30 of file dxlport_control.h.
| DXLPORT_CONTROL::DXLPORT_CONTROL | ( | ros::NodeHandle | handle, | 
| CONTROL_SETTING & | setting | ||
| ) | 
Definition at line 16 of file dxlport_control.cpp.
| DXLPORT_CONTROL::~DXLPORT_CONTROL | ( | ) | 
Definition at line 127 of file dxlport_control.cpp.
| 
 | private | 
Definition at line 501 of file dxlport_control.cpp.
| 
 | private | 
Definition at line 521 of file dxlport_control.cpp.
| 
 | private | 
Definition at line 481 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::effort_limitter | ( | void | ) | 
Definition at line 675 of file dxlport_control.cpp.
| std::string::size_type DXLPORT_CONTROL::get_error | ( | std::string & | errorlog | ) | 
Definition at line 1064 of file dxlport_control.cpp.
| 
 | inline | 
Definition at line 52 of file dxlport_control.h.
| 
 | inline | 
Definition at line 53 of file dxlport_control.h.
| 
 | inline | 
Definition at line 36 of file dxlport_control.h.
| 
 | inline | 
Definition at line 35 of file dxlport_control.h.
| void DXLPORT_CONTROL::init_joint_params | ( | ST_JOINT_PARAM & | param, | 
| int | table_id, | ||
| int | value | ||
| ) | 
Definition at line 542 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::is_change_positions | ( | void | ) | 
Definition at line 291 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::read | ( | ros::Time | time, | 
| ros::Duration | period | ||
| ) | 
Definition at line 137 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::readCurrent | ( | ros::Time | time, | 
| ros::Duration | period | ||
| ) | 
Definition at line 180 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::readPos | ( | ros::Time | time, | 
| ros::Duration | period | ||
| ) | 
Definition at line 162 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::readTemp | ( | ros::Time | time, | 
| ros::Duration | period | ||
| ) | 
Definition at line 198 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::readVel | ( | ros::Time | time, | 
| ros::Duration | period | ||
| ) | 
Definition at line 221 of file dxlport_control.cpp.
| std::string DXLPORT_CONTROL::self_check | ( | void | ) | 
Definition at line 603 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_gain | ( | uint8_t | dxl_id, | 
| uint16_t | gain | ||
| ) | 
Definition at line 316 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_gain_all | ( | uint16_t | gain | ) | 
Definition at line 303 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_goal_current | ( | uint8_t | dxl_id, | 
| uint16_t | current | ||
| ) | 
Definition at line 343 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_goal_current_all | ( | uint16_t | current | ) | 
Definition at line 330 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_current_limit | ( | uint8_t | dxl_id, | 
| int | val | ||
| ) | 
Definition at line 935 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_delay_time | ( | uint8_t | dxl_id, | 
| int | val | ||
| ) | 
Definition at line 733 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_drive_mode | ( | uint8_t | dxl_id, | 
| int | val | ||
| ) | 
Definition at line 760 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_home_offset | ( | uint8_t | dxl_id, | 
| int | val | ||
| ) | 
Definition at line 814 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_moving_threshold | ( | uint8_t | dxl_id, | 
| int | val | ||
| ) | 
Definition at line 841 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_ope_mode | ( | uint8_t | dxl_id, | 
| int | val | ||
| ) | 
Definition at line 787 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_pos_gain | ( | uint8_t | dxl_id, | 
| int | p, | ||
| int | i, | ||
| int | d | ||
| ) | 
Definition at line 1010 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_pos_gain_all | ( | int | p, | 
| int | i, | ||
| int | d | ||
| ) | 
Definition at line 1003 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_temp_limit | ( | uint8_t | dxl_id, | 
| int | val | ||
| ) | 
Definition at line 868 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_vel_gain | ( | uint8_t | dxl_id, | 
| int | p, | ||
| int | i | ||
| ) | 
Definition at line 962 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_vol_limit | ( | uint8_t | dxl_id, | 
| int | max, | ||
| int | min | ||
| ) | 
Definition at line 895 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::set_torque | ( | uint8_t | dxl_id, | 
| bool | torque | ||
| ) | 
Definition at line 357 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_torque_all | ( | bool | torque | ) | 
Definition at line 379 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_watchdog | ( | uint8_t | dxl_id, | 
| uint8_t | value | ||
| ) | 
Definition at line 388 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_watchdog_all | ( | uint8_t | value | ) | 
Definition at line 405 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::startup_motion | ( | void | ) | 
Definition at line 413 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::write | ( | ros::Time | time, | 
| ros::Duration | period | ||
| ) | 
Definition at line 236 of file dxlport_control.cpp.
| 
 | private | 
Definition at line 94 of file dxlport_control.h.
| 
 | private | 
Definition at line 89 of file dxlport_control.h.
| 
 | private | 
Definition at line 83 of file dxlport_control.h.
| 
 | private | 
Definition at line 84 of file dxlport_control.h.
| 
 | private | 
Definition at line 77 of file dxlport_control.h.
| 
 | private | 
Definition at line 82 of file dxlport_control.h.
| 
 | private | 
Definition at line 81 of file dxlport_control.h.
| std::vector<JOINT_CONTROL> DXLPORT_CONTROL::joints | 
Definition at line 74 of file dxlport_control.h.
| 
 | private | 
Definition at line 79 of file dxlport_control.h.
| 
 | private | 
Definition at line 78 of file dxlport_control.h.
| 
 | private | 
Definition at line 80 of file dxlport_control.h.
| 
 | private | 
Definition at line 86 of file dxlport_control.h.
| 
 | private | 
Definition at line 85 of file dxlport_control.h.
| 
 | private | 
Definition at line 90 of file dxlport_control.h.
| uint32_t DXLPORT_CONTROL::tempCount | 
Definition at line 73 of file dxlport_control.h.
| 
 | private | 
Definition at line 92 of file dxlport_control.h.
| 
 | private | 
Definition at line 91 of file dxlport_control.h.
| 
 | private | 
Definition at line 87 of file dxlport_control.h.