#include <dxlport_control.h>

Public Member Functions | |
| DXLPORT_CONTROL (ros::NodeHandle handle, CONTROL_SETTING &setting) | |
| 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) |
| void | lock_port (void) |
| bool | read (ros::Time, ros::Duration) |
| bool | readCurrent (ros::Time, ros::Duration) |
| bool | readId (ros::Time, ros::Duration) |
| bool | readPos (ros::Time, ros::Duration) |
| bool | readTemp (ros::Time, ros::Duration) |
| bool | 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) |
| bool | setup_indirect (uint8_t dxl_id) |
| void | startup_motion (void) |
| void | unlock_port (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 31 of file dxlport_control.h.
| DXLPORT_CONTROL::DXLPORT_CONTROL | ( | ros::NodeHandle | handle, |
| CONTROL_SETTING & | setting | ||
| ) |
Definition at line 15 of file dxlport_control.cpp.
| DXLPORT_CONTROL::~DXLPORT_CONTROL | ( | ) |
Definition at line 145 of file dxlport_control.cpp.
|
private |
Definition at line 588 of file dxlport_control.cpp.
|
private |
Definition at line 610 of file dxlport_control.cpp.
|
private |
Definition at line 566 of file dxlport_control.cpp.
| std::string::size_type DXLPORT_CONTROL::get_error | ( | std::string & | errorlog | ) |
Definition at line 1128 of file dxlport_control.cpp.
|
inline |
Definition at line 54 of file dxlport_control.h.
|
inline |
Definition at line 55 of file dxlport_control.h.
|
inline |
Definition at line 37 of file dxlport_control.h.
|
inline |
Definition at line 36 of file dxlport_control.h.
| void DXLPORT_CONTROL::init_joint_params | ( | ST_JOINT_PARAM & | param, |
| int | table_id, | ||
| int | value | ||
| ) |
Definition at line 633 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::is_change_positions | ( | void | ) |
Definition at line 359 of file dxlport_control.cpp.
|
inline |
Definition at line 72 of file dxlport_control.h.
| bool DXLPORT_CONTROL::read | ( | ros::Time | time, |
| ros::Duration | period | ||
| ) |
Definition at line 156 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::readCurrent | ( | ros::Time | time, |
| ros::Duration | period | ||
| ) |
Definition at line 223 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::readId | ( | ros::Time | time, |
| ros::Duration | period | ||
| ) |
Definition at line 177 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::readPos | ( | ros::Time | time, |
| ros::Duration | period | ||
| ) |
Definition at line 201 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::readTemp | ( | ros::Time | time, |
| ros::Duration | period | ||
| ) |
Definition at line 245 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::readVel | ( | ros::Time | time, |
| ros::Duration | period | ||
| ) |
Definition at line 266 of file dxlport_control.cpp.
| std::string DXLPORT_CONTROL::self_check | ( | void | ) |
Definition at line 694 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_gain | ( | uint8_t | dxl_id, |
| uint16_t | gain | ||
| ) |
Definition at line 385 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_gain_all | ( | uint16_t | gain | ) |
Definition at line 372 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_goal_current | ( | uint8_t | dxl_id, |
| uint16_t | current | ||
| ) |
Definition at line 414 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_goal_current_all | ( | uint16_t | current | ) |
Definition at line 401 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_current_limit | ( | uint8_t | dxl_id, |
| int | val | ||
| ) |
Definition at line 984 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_delay_time | ( | uint8_t | dxl_id, |
| int | val | ||
| ) |
Definition at line 766 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_drive_mode | ( | uint8_t | dxl_id, |
| int | val | ||
| ) |
Definition at line 795 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_home_offset | ( | uint8_t | dxl_id, |
| int | val | ||
| ) |
Definition at line 853 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_moving_threshold | ( | uint8_t | dxl_id, |
| int | val | ||
| ) |
Definition at line 882 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_ope_mode | ( | uint8_t | dxl_id, |
| int | val | ||
| ) |
Definition at line 824 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 1068 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_pos_gain_all | ( | int | p, |
| int | i, | ||
| int | d | ||
| ) |
Definition at line 1058 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_temp_limit | ( | uint8_t | dxl_id, |
| int | val | ||
| ) |
Definition at line 911 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_vel_gain | ( | uint8_t | dxl_id, |
| int | p, | ||
| int | i | ||
| ) |
Definition at line 1013 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_param_vol_limit | ( | uint8_t | dxl_id, |
| int | max, | ||
| int | min | ||
| ) |
Definition at line 940 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::set_torque | ( | uint8_t | dxl_id, |
| bool | torque | ||
| ) |
Definition at line 430 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_torque_all | ( | bool | torque | ) |
Definition at line 454 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_watchdog | ( | uint8_t | dxl_id, |
| uint8_t | value | ||
| ) |
Definition at line 463 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::set_watchdog_all | ( | uint8_t | value | ) |
Definition at line 482 of file dxlport_control.cpp.
| bool DXLPORT_CONTROL::setup_indirect | ( | uint8_t | dxl_id | ) |
Definition at line 1138 of file dxlport_control.cpp.
| void DXLPORT_CONTROL::startup_motion | ( | void | ) |
Definition at line 490 of file dxlport_control.cpp.
|
inline |
Definition at line 73 of file dxlport_control.h.
| void DXLPORT_CONTROL::write | ( | ros::Time | time, |
| ros::Duration | period | ||
| ) |
Definition at line 285 of file dxlport_control.cpp.
|
private |
Definition at line 99 of file dxlport_control.h.
|
private |
Definition at line 100 of file dxlport_control.h.
|
private |
Definition at line 94 of file dxlport_control.h.
|
private |
Definition at line 87 of file dxlport_control.h.
|
private |
Definition at line 88 of file dxlport_control.h.
|
private |
Definition at line 81 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.
| std::vector<JOINT_CONTROL> DXLPORT_CONTROL::joints |
Definition at line 78 of file dxlport_control.h.
|
private |
Definition at line 83 of file dxlport_control.h.
|
private |
Definition at line 82 of file dxlport_control.h.
|
private |
Definition at line 84 of file dxlport_control.h.
|
private |
Definition at line 90 of file dxlport_control.h.
|
private |
Definition at line 89 of file dxlport_control.h.
|
private |
Definition at line 95 of file dxlport_control.h.
| uint32_t DXLPORT_CONTROL::tempCount |
Definition at line 77 of file dxlport_control.h.
|
private |
Definition at line 97 of file dxlport_control.h.
|
private |
Definition at line 96 of file dxlport_control.h.
|
private |
Definition at line 91 of file dxlport_control.h.
|
private |
Definition at line 92 of file dxlport_control.h.