Go to the documentation of this file. 1 #ifndef DXLPORT_CONTROL_H
2 #define DXLPORT_CONTROL_H
46 bool set_torque( uint8_t dxl_id,
bool torque );
51 void set_gain( uint8_t dxl_id, uint16_t gain );
74 std::string::size_type
get_error( std::string& errorlog );
102 bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t& read_val );
103 bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint16_t equal, uint16_t& read_val );
104 bool check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint32_t equal, uint32_t& read_val );
std::string::size_type get_error(std::string &errorlog)
void set_param_drive_mode(uint8_t dxl_id, int val)
uint8_t get_joint_num(void)
std::vector< JOINT_CONTROL > joints
void set_param_pos_gain_all(int p, int i, int d)
void set_param_ope_mode(uint8_t dxl_id, int val)
DXLPORT_CONTROL(ros::NodeHandle handle, CONTROL_SETTING &setting)
void set_param_home_offset(uint8_t dxl_id, int val)
bool readPos(ros::Time, ros::Duration)
bool set_torque(uint8_t dxl_id, bool torque)
struct HOME_MOTION_DATA ST_HOME_MOTION_DATA
bool is_change_positions(void)
bool readCurrent(ros::Time, ros::Duration)
bool readVel(ros::Time, ros::Duration)
void startup_motion(void)
dynamixel::GroupBulkRead * readIndirectGroup
std::queue< std::string > error_queue
void set_param_vol_limit(uint8_t dxl_id, int max, int min)
void set_torque_all(bool torque)
hardware_interface::JointStateInterface joint_stat_if
ros::Duration getDuration(ros::Time t) const
void write(ros::Time, ros::Duration)
dynamixel::GroupBulkRead * readTempGroup
void set_param_moving_threshold(uint8_t dxl_id, int val)
void init_joint_params(ST_JOINT_PARAM ¶m, int table_id, int value)
bool read(ros::Time, ros::Duration)
void set_goal_current_all(uint16_t current)
void set_param_vel_gain(uint8_t dxl_id, int p, int i)
dynamixel::GroupBulkWrite * writeGoalGroup
ros::Time getTime() const
void set_gain(uint8_t dxl_id, uint16_t gain)
void set_gain_all(uint16_t gain)
bool readTemp(ros::Time, ros::Duration)
void set_param_delay_time(uint8_t dxl_id, int val)
dynamixel::PacketHandler * packetHandler
hardware_interface::PositionJointInterface joint_pos_if
bool check_servo_param(uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t &read_val)
void set_param_current_limit(uint8_t dxl_id, int val)
void set_param_temp_limit(uint8_t dxl_id, int val)
void set_param_pos_gain(uint8_t dxl_id, int p, int i, int d)
dynamixel::PortHandler * portHandler
joint_limits_interface::PositionJointSoftLimitsInterface joint_limits_if
dynamixel::GroupBulkWrite * writePosGoalGroup
hardware_interface::EffortJointInterface joint_eff_if
void set_watchdog(uint8_t dxl_id, uint8_t value)
std::string self_check(void)
void set_watchdog_all(uint8_t value)
bool setup_indirect(uint8_t dxl_id)
void set_goal_current(uint8_t dxl_id, uint16_t current)
bool readId(ros::Time, ros::Duration)
sciurus17_control
Author(s): Hiroyuki Nomura
autogenerated on Fri Aug 2 2024 08:37:24