1 #ifndef DXLPORT_CONTROL_H 2 #define DXLPORT_CONTROL_H 43 void set_torque_all(
bool torque );
44 bool set_torque( uint8_t dxl_id,
bool torque );
45 void set_watchdog( uint8_t dxl_id, uint8_t value );
46 void set_watchdog_all( uint8_t value );
47 void startup_motion(
void );
48 void set_gain_all( uint16_t gain );
49 void set_gain( uint8_t dxl_id, uint16_t gain );
50 void set_goal_current_all( uint16_t current );
51 void set_goal_current( uint8_t dxl_id, uint16_t current );
54 std::string self_check(
void );
55 void effort_limitter(
void );
58 void set_param_delay_time( uint8_t dxl_id,
int val );
59 void set_param_drive_mode( uint8_t dxl_id,
int val );
60 void set_param_ope_mode( uint8_t dxl_id,
int val );
61 void set_param_home_offset( uint8_t dxl_id,
int val );
62 void set_param_moving_threshold( uint8_t dxl_id,
int val );
63 void set_param_temp_limit( uint8_t dxl_id,
int val );
64 void set_param_vol_limit( uint8_t dxl_id,
int max,
int min );
65 void set_param_current_limit( uint8_t dxl_id,
int val );
66 void set_param_vel_gain( uint8_t dxl_id,
int p,
int i );
67 void set_param_pos_gain_all(
int p,
int i,
int d );
68 void set_param_pos_gain( uint8_t dxl_id,
int p,
int i,
int d );
70 bool is_change_positions(
void );
71 std::string::size_type get_error( std::string& errorlog );
96 bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t& read_val );
97 bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint16_t equal, uint16_t& read_val );
98 bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint32_t equal, uint32_t& read_val );
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
std::queue< std::string > error_queue
hardware_interface::JointStateInterface joint_stat_if
struct HOME_MOTION_DATA ST_HOME_MOTION_DATA
dynamixel::GroupBulkRead * readTempGroup
dynamixel::GroupBulkWrite * writeGoalGroup
hardware_interface::EffortJointInterface joint_eff_if
dynamixel::GroupBulkRead * readMovementGroup
hardware_interface::PositionJointInterface joint_pos_if
ros::Time getTime() const
dynamixel::PacketHandler * packetHandler
std::vector< JOINT_CONTROL > joints
ros::Duration getDuration(ros::Time t) const
uint8_t get_joint_num(void)
dynamixel::PortHandler * portHandler
joint_limits_interface::PositionJointSoftLimitsInterface joint_limits_if