8 #define EFFORT_LIMIT_COEF (0.95) 11 #define DXLPOS2RAD(pos) (( ((pos)*(360.0/POSITION_STEP) )/360) *2*M_PI) 12 #define RAD2DXLPOS(rad) (( ((rad)/2.0/M_PI)*360.0 ) * (POSITION_STEP / 360.0)) 13 #define INIT_EFFCNST_UNIT(c) ((c)*0.001) 21 int position_mode_joint_num = 0;
22 int current_mode_joint_num = 0;
37 JOINT_CONTROL work( list[jj].name, list[jj].
id, list[jj].center, list[jj].home, list[jj].eff_cnst, list[jj].mode );
49 uint8_t dxl_id =
joints[jj].get_dxl_id();
53 error_queue.push(
"Bulk current write setting failed.");
68 error_queue.push(
"Bulk group read setting failed.");
85 error_queue.push(
"Initialize communication failed.");
100 ++current_mode_joint_num;
103 ++position_mode_joint_num;
107 joints[jj].set_limits( limits );
113 reg_limits_handle( reg_joint_handle, limits, soft_limits );
117 if( position_mode_joint_num > 0 ){
120 if( current_mode_joint_num > 0 ){
165 int32_t present_pos = 0;
166 uint8_t dxl_id =
joints[jj].get_dxl_id();
168 if( !dxl_getdata_result ){
173 joints[jj].set_dxl_pos( present_pos );
174 present_pos = (present_pos -
joints[jj].get_center());
183 int16_t present_current = 0;
184 uint8_t dxl_id =
joints[jj].get_dxl_id();
186 if( !dxl_getdata_result ){
191 joints[jj].set_dxl_curr( present_current );
206 uint8_t dxl_id =
joints[jj].get_dxl_id();
208 if( !dxl_getdata_result ){
213 joints[jj].set_dxl_temp( present_temp );
214 joints[jj].set_temprature( present_temp );
224 uint8_t dxl_id =
joints[jj].get_dxl_id();
226 if( !dxl_getdata_result ){
242 get_cmd =
joints[jj].get_command();
243 joints[jj].updt_d_command( get_cmd );
244 joints[jj].set_position( get_cmd );
249 get_cmd =
joints[jj].get_command();
253 joints[jj].updt_d_command( 0.0 );
255 uint16_t dxl_cur = (uint32_t)round( work_cur );
256 uint8_t* goal_data =
joints[jj].get_dxl_goal_addr();
257 goal_data[0] = (uint8_t)(dxl_cur&0x000000FF);
258 goal_data[1] = (uint8_t)((dxl_cur&0x0000FF00)>>8);
264 joints[jj].updt_d_command( get_cmd );
265 work_pos +=
joints[jj].get_center();
273 uint32_t dxl_pos = (uint32_t)round( work_pos );
274 uint8_t* goal_data =
joints[jj].get_dxl_goal_addr();
276 goal_data[0] = (uint8_t)(dxl_pos&0x000000FF);
277 goal_data[1] = (uint8_t)((dxl_pos&0x0000FF00)>>8);
278 goal_data[2] = (uint8_t)((dxl_pos&0x00FF0000)>>16);
279 goal_data[3] = (uint8_t)((dxl_pos&0xFF000000)>>24);
296 if( fabs(
joints[jj].get_d_command() ) > 0.0 ){
318 uint8_t dxl_error = 0;
324 }
else if( dxl_error != 0 ){
345 uint8_t dxl_error = 0;
351 }
else if( dxl_error != 0 ){
366 uint8_t dxl_error = 0;
371 }
else if( dxl_error != 0 ){
381 for( uint8_t jj=0 ; jj<
joint_num; ++jj ){
383 joints[jj].set_torque( torque );
394 uint8_t dxl_error = 0;
399 }
else if( dxl_error != 0 ){
407 for( uint8_t jj=0 ; jj<
joint_num; ++jj ){
419 std::vector<ST_HOME_MOTION_DATA> home_motion_data;
434 joints[jj].set_command( 0.0 );
438 home_motion_data.push_back( motion_work );
446 for(
int step=0 ; step<step_max ; ++step ){
463 joints[jj].set_command(
joints[jj].get_command() + home_motion_data[jj].step_rad );
472 joints[jj].set_command( home_motion_data[jj].home_rad );
476 joints[jj].updt_d_command( 0.0 );
483 uint8_t dxl_error = 0;
491 }
else if( dxl_error != 0 ){
495 if( read_data == equal ){
498 read_val = read_data;
503 uint8_t dxl_error = 0;
511 }
else if( dxl_error != 0 ){
515 if( read_data == equal ){
518 read_val = read_data;
523 uint8_t dxl_error = 0;
531 }
else if( dxl_error != 0 ){
535 if( read_data == equal ){
538 read_val = read_data;
605 std::string res_str =
"[DYNAMIXEL PARAMETER SELF CHECK]\n";
608 res_str =
"SKIP SELF CHECK...";
612 bool check_result =
true;
614 uint8_t chk_8data, read_8data;
615 uint16_t chk_16data, read_16data;
616 uint32_t chk_32data, read_32data;
622 chk_8data = (uint8_t)
RegTable[ii].init_value;
623 if(
RegTable[ii].name ==
"OPERATION_MODE" ){
624 chk_8data =
joints[ii].get_ope_mode();
628 if(
RegTable[ii].selfcheck && !read_result ){
629 res_str +=
" ID: " + std::to_string(
joints[jj].get_dxl_id()) +
" check NG\n";
630 check_result =
false;
634 joints[jj].set_joint_param( work );
638 chk_16data = (uint16_t)
RegTable[ii].init_value;
641 if(
RegTable[ii].selfcheck && !read_result ){
642 res_str +=
" ID: " + std::to_string(
joints[jj].get_dxl_id()) +
" check NG\n";
643 check_result =
false;
647 joints[jj].set_joint_param( work );
651 chk_32data = (uint32_t)
RegTable[ii].init_value;
654 if(
RegTable[ii].selfcheck && !read_result ){
655 res_str +=
" ID: " + std::to_string(
joints[jj].get_dxl_id()) +
" check NG\n";
656 check_result =
false;
660 joints[jj].set_joint_param( work );
666 res_str +=
" CHECK OK\n";
668 res_str +=
" CHECK NG!\n";
677 uint8_t dxl_error = 0;
685 double now_eff = fabs(
joints[jj].get_effort() );
686 double max_eff =
joints[jj].get_max_effort();
687 if( now_eff > max_eff ){
688 joints[jj].inc_eff_over();
692 if(
joints[jj].is_effort_limiting() ){
697 }
else if( dxl_error != 0 ){
701 set_pgain = get_pgain;
706 joints[jj].set_eff_limiting(
true );
710 if(
joints[jj].is_effort_limiting() ){
715 }
else if( dxl_error != 0 ){
719 joints[jj].clear_eff_over();
720 joints[jj].set_eff_limiting(
false );
723 joints[jj].set_eff_limiting(
true );
735 uint8_t set_param = (uint8_t)val;
741 if( dxl_id ==
joints[jj].get_dxl_id() ){
744 uint8_t dxl_error = 0;
749 }
else if( dxl_error != 0 ){
755 joints[jj].set_joint_param( new_param );
762 uint8_t set_param = (uint8_t)val;
768 if( dxl_id ==
joints[jj].get_dxl_id() ){
771 uint8_t dxl_error = 0;
776 }
else if( dxl_error != 0 ){
782 joints[jj].set_joint_param( new_param );
789 uint8_t set_param = (uint8_t)val;
795 if( dxl_id ==
joints[jj].get_dxl_id() ){
798 uint8_t dxl_error = 0;
803 }
else if( dxl_error != 0 ){
809 joints[jj].set_joint_param( new_param );
816 uint32_t set_param = (uint32_t)val;
822 if( dxl_id ==
joints[jj].get_dxl_id() ){
825 uint8_t dxl_error = 0;
830 }
else if( dxl_error != 0 ){
836 joints[jj].set_joint_param( new_param );
843 uint32_t set_param = (uint32_t)val;
849 if( dxl_id ==
joints[jj].get_dxl_id() ){
852 uint8_t dxl_error = 0;
857 }
else if( dxl_error != 0 ){
863 joints[jj].set_joint_param( new_param );
870 uint8_t set_param = (uint8_t)val;
876 if( dxl_id ==
joints[jj].get_dxl_id() ){
879 uint8_t dxl_error = 0;
884 }
else if( dxl_error != 0 ){
890 joints[jj].set_joint_param( new_param );
897 uint16_t set_max_param = (uint32_t)max;
898 uint16_t set_min_param = (uint32_t)min;
904 if( dxl_id ==
joints[jj].get_dxl_id() ){
907 uint8_t dxl_error = 0;
912 }
else if( dxl_error != 0 ){
918 uint8_t dxl_error = 0;
923 }
else if( dxl_error != 0 ){
930 joints[jj].set_joint_param( new_param );
937 uint16_t set_param = (uint16_t)val;
943 if( dxl_id ==
joints[jj].get_dxl_id() ){
946 uint8_t dxl_error = 0;
951 }
else if( dxl_error != 0 ){
957 joints[jj].set_joint_param( new_param );
964 uint16_t set_p_param = (uint16_t)p;
965 uint16_t set_i_param = (uint16_t)i;
971 if( dxl_id ==
joints[jj].get_dxl_id() ){
974 uint8_t dxl_error = 0;
979 }
else if( dxl_error != 0 ){
985 uint8_t dxl_error = 0;
990 }
else if( dxl_error != 0 ){
997 joints[jj].set_joint_param( new_param );
1012 uint16_t set_p_param = (uint16_t)p;
1013 uint16_t set_i_param = (uint16_t)i;
1014 uint16_t set_d_param = (uint16_t)d;
1020 if( dxl_id ==
joints[jj].get_dxl_id() ){
1023 uint8_t dxl_error = 0;
1028 }
else if( dxl_error != 0 ){
1034 uint8_t dxl_error = 0;
1039 }
else if( dxl_error != 0 ){
1045 uint8_t dxl_error = 0;
1050 }
else if( dxl_error != 0 ){
1058 joints[jj].set_joint_param( new_param );
1066 std::string::size_type result =
error_queue.size();
void set_watchdog(uint8_t dxl_id, uint8_t value)
void registerInterface(T *iface)
void set_watchdog_all(uint8_t value)
void set_param_home_offset(uint8_t dxl_id, int val)
void set_param_pos_gain_all(int p, int i, int d)
void readTemp(ros::Time, ros::Duration)
virtual int read1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error=0)=0
bool isAvailable(uint8_t id, uint16_t address, uint16_t data_length)
#define ADDR_POSITION_DGAIN
static PortHandler * getPortHandler(const char *port_name)
#define DXL_VELOCITY2RAD_S(v)
#define ADDR_GOAL_CURRENT
DXLPORT_CONTROL(ros::NodeHandle handle, CONTROL_SETTING &setting)
std::string::size_type get_error(std::string &errorlog)
#define ADDR_MOVING_THRESHOLD
#define ADDR_PRESENT_MOVEMENT
void set_goal_current(uint8_t dxl_id, uint16_t current)
virtual bool openPort()=0
#define LEN_PRESENT_MOVEMENT
bool set_torque(uint8_t dxl_id, bool torque)
#define LEN_PRESENT_POSITION
bool addParam(uint8_t id, uint16_t start_address, uint16_t data_length)
void set_param_drive_mode(uint8_t dxl_id, int val)
uint32_t getjointNum(void)
bool changeParam(uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data)
#define ADDR_CURRENT_LIMIT
#define DXL_DEFAULT_PGAIN
#define ADDR_BUS_WATCHDOG
std::queue< std::string > error_queue
static const ST_DYNAMIXEL_REG_TABLE RegTable[]
void set_param_vol_limit(uint8_t dxl_id, int max, int min)
virtual int read2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error=0)=0
void startup_motion(void)
std::vector< ST_SERVO_PARAM > getServoParam(void)
#define LEN_GOAL_POSITION
#define EFFORT2DXL_CURRENT(e, coef)
uint16_t moving_threshold
#define LEN_PRESENT_CURRENT
void write(ros::Time, ros::Duration)
#define DXL_CURRENT2EFFORT(c, coef)
#define OPERATING_MODE_CURRENT
#define ADDR_POSITION_PGAIN
bool is_change_positions(void)
virtual void closePort()=0
virtual const char * getRxPacketError(uint8_t error)=0
std::string getPortName(void)
#define DXL_TORQUE_ON_STEP_MAX
#define ADDR_PRESENT_POSITION
#define ADDR_VELOCITY_PGAIN
void set_goal_current_all(uint16_t current)
#define ADDR_TORQUE_ENABLE
hardware_interface::JointStateInterface joint_stat_if
#define DXL_TORQUR_ON_STEP
void set_gain_all(uint16_t gain)
virtual int write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0)=0
#define ADDR_VELOCITY_IGAIN
#define ADDR_RETURN_DELAY
uint32_t getBaudrate(void)
void set_gain(uint8_t dxl_id, uint16_t gain)
static PacketHandler * getPacketHandler(float protocol_version=2.0)
void set_param_current_limit(uint8_t dxl_id, int val)
void set_torque_all(bool torque)
void registerHandle(const JointStateHandle &handle)
void init_joint_params(ST_JOINT_PARAM ¶m, int table_id, int value)
void readCurrent(ros::Time, ros::Duration)
void set_param_delay_time(uint8_t dxl_id, int val)
void effort_limitter(void)
dynamixel::GroupBulkRead * readTempGroup
uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)
JointStateHandle getHandle(const std::string &name)
#define ADDR_TEMPRATURE_LIMIT
bool check_servo_param(uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t &read_val)
uint8_t return_delay_time
dynamixel::GroupBulkWrite * writeGoalGroup
void set_param_moving_threshold(uint8_t dxl_id, int val)
virtual int write4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error=0)=0
bool read(ros::Time, ros::Duration)
#define ADDR_MAX_VOL_LIMIT
void readVel(ros::Time, ros::Duration)
#define DXL_TEMP_READ_DURATION
hardware_interface::EffortJointInterface joint_eff_if
#define ADDR_MIN_VOL_LIMIT
virtual int write2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error=0)=0
dynamixel::GroupBulkRead * readMovementGroup
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
void readPos(ros::Time, ros::Duration)
void set_param_vel_gain(uint8_t dxl_id, int p, int i)
hardware_interface::PositionJointInterface joint_pos_if
virtual int read4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error=0)=0
#define EFFORT_LIMITING_CNT
#define EFFORT_LIMIT_COEF
virtual bool setBaudRate(const int baudrate)=0
ros::Time getTime() const
std::string self_check(void)
#define ADDR_PRESENT_CURRENT
virtual const char * getTxRxResult(int result)=0
dynamixel::PacketHandler * packetHandler
#define ADDR_GOAL_POSITION
#define ADDR_PRESENT_TEMP
std::vector< JOINT_CONTROL > joints
void set_param_ope_mode(uint8_t dxl_id, int val)
void set_param_temp_limit(uint8_t dxl_id, int val)
ros::Duration getDuration(ros::Time t) const
void set_param_pos_gain(uint8_t dxl_id, int p, int i, int d)
#define ADDR_POSITION_IGAIN
dynamixel::PortHandler * portHandler
joint_limits_interface::PositionJointSoftLimitsInterface joint_limits_if