Go to the documentation of this file. 1 #ifndef DXL_JOINT_CONTROL_H
2 #define DXL_JOINT_CONTROL_H
9 #include <dynamic_reconfigure/server.h>
10 #include <sciurus17_msgs/ServoParameterConfig.h>
13 #define PROTOCOL_VERSION (2.0) // See which protocol version is used in the Dynamixel
29 #define REG_LENGTH_BYTE (1)
30 #define REG_LENGTH_WORD (2)
31 #define REG_LENGTH_DWORD (4)
109 #define BAUDRATE (3000000) // 通信速度
110 #define ADDR_RETURN_DELAY (RegTable[enTableId_ReturnDelay].address)
111 #define LEN_PRETURN_DELAY (RegTable[enTableId_ReturnDelay].length)
112 #define ADDR_DRIVE_MODE (RegTable[enTableId_DriveMode].address)
113 #define LEN_DRIVE_MODE (RegTable[enTableId_DriveMode].length)
114 #define ADDR_OPE_MODE (RegTable[enTableId_OpeMode].address)
115 #define LEN_OPE_MODE (RegTable[enTableId_OpeMode].length)
116 #define ADDR_HOMING_OFFSET (RegTable[enTableId_HomingOffset].address)
117 #define LEN_HOMING_OFFSET (RegTable[enTableId_HomingOffset].length)
118 #define ADDR_MOVING_THRESHOLD (RegTable[enTableId_MovingThreshold].address)
119 #define LEN_MOVING_THRESHOLD (RegTable[enTableId_MovingThreshold].length)
120 #define ADDR_TEMPRATURE_LIMIT (RegTable[enTableId_TempLimit].address)
121 #define LEN_TEMPRATURE_LIMIT (RegTable[enTableId_TempLimit].length)
122 #define ADDR_MAX_VOL_LIMIT (RegTable[enTableId_MaxVolLimit].address)
123 #define LEN_MAX_VOL_LIMIT (RegTable[enTableId_MaxVolLimit].length)
124 #define ADDR_MIN_VOL_LIMIT (RegTable[enTableId_MinVolLimit].address)
125 #define LEN_MIN_VOL_LIMIT (RegTable[enTableId_MinVolLimit].length)
126 #define ADDR_CURRENT_LIMIT (RegTable[enTableId_CurrentLimit].address)
127 #define LEN_CURRENT_LIMIT (RegTable[enTableId_CurrentLimit].length)
128 #define ADDR_TORQUE_ENABLE (RegTable[enTableId_TorqueEnable].address) // Control table address is different in Dynamixel model
129 #define ADDR_VELOCITY_IGAIN (RegTable[enTableId_VelocityIGain].address)
130 #define LEN_VELOCITY_IGAIN (RegTable[enTableId_VelocityIGain].length)
131 #define ADDR_VELOCITY_PGAIN (RegTable[enTableId_VelocityPGain].address)
132 #define LEN_VELOCITY_PGAIN (RegTable[enTableId_VelocityPGain].length)
133 #define ADDR_POSITION_DGAIN (RegTable[enTableId_PositionDGain].address)
134 #define LEN_POSITION_DGAIN (RegTable[enTableId_PositionDGain].length)
135 #define ADDR_POSITION_IGAIN (RegTable[enTableId_PositionIGain].address)
136 #define LEN_POSITION_IGAIN (RegTable[enTableId_PositionIGain].length)
137 #define ADDR_POSITION_PGAIN (RegTable[enTableId_PositionPGain].address)
138 #define LEN_POSITION_PGAIN (RegTable[enTableId_PositionPGain].length)
139 #define ADDR_BUS_WATCHDOG (RegTable[enTableId_BusWatchdog].address)
140 #define LEN_BUS_WATCHDOG (RegTable[enTableId_BusWatchdog].length)
141 #define ADDR_GOAL_CURRENT (RegTable[enTableId_GoalCurrent].address) // ゴールカレントアドレス
142 #define LEN_GOAL_CURRENT (RegTable[enTableId_GoalCurrent].length) // ゴールカレント
143 #define ADDR_GOAL_POSITION (RegTable[enTableId_GoalPosition].address) // ゴールポジションアドレス
144 #define LEN_GOAL_POSITION (RegTable[enTableId_GoalPosition].length) // ゴールポジション
145 #define ADDR_PRESENT_CURRENT (RegTable[enTableId_PresentCurrent].address)
146 #define LEN_PRESENT_CURRENT (RegTable[enTableId_PresentCurrent].length)
147 #define ADDR_PRESENT_VEL (RegTable[enTableId_PresentVelocity].address)
148 #define LEN_PRESENT_VEL (RegTable[enTableId_PresentVelocity].length)
149 #define ADDR_PRESENT_POSITION (RegTable[enTableId_PresentPosition].address)
150 #define LEN_PRESENT_POSITION (RegTable[enTableId_PresentPosition].length)
151 #define ADDR_PRESENT_TEMP (RegTable[enTableId_PresentTemp].address)
152 #define LEN_PRESENT_TEMP (RegTable[enTableId_PresentTemp].length)
154 #define ADDR_INDIRECT_TOP (168)
155 #define DATA_INDIRECT_TOP (224)
156 #define LEN_INDIRECT_GROUP (12)
157 #define ADDR_INDIRECT_DXLID (DATA_INDIRECT_TOP)
158 #define LEN_INDIRECT_DXLID (1)
159 #define ADDR_INDIRECT_CURRENT (DATA_INDIRECT_TOP+1)
160 #define ADDR_INDIRECT_VELOCITY (DATA_INDIRECT_TOP+3)
161 #define ADDR_INDIRECT_POSITION (DATA_INDIRECT_TOP+7)
162 #define ADDR_INDIRECT_TEMP (DATA_INDIRECT_TOP+11)
164 #define TORQUE_ENABLE (1) // Value for enabling the torque
165 #define TORQUE_DISABLE (0) // Value for disabling the torque
167 #define POSITION_STEP (4096.0)
168 #define DXL_MIN_LIMIT (0.0)
169 #define DXL_MAX_LIMIT (4095.0)
170 #define DXL_CURRENT_UNIT (2.69) // mA
171 #define DXL_EFFORT_CONST (1.79)
172 #define DXL_TEMP_READ_DURATION (5)
173 #define DXL_PGAIN_MAX (16383)
174 #define DXL_DEFAULT_PGAIN (800)
175 #define DXL_FREE_PGAIN (0)
176 #define DXL_FREE_IGAIN (0)
177 #define DXL_FREE_DGAIN (0)
179 #define DXL_OFFSET_DEFAULT (2048)
181 #define DXL_TORQUE_ON_TIME (5*1000) // msec
182 #define DXL_TORQUR_ON_STEP (20) // Hz
183 #define DXL_TORQUE_ON_STEP_MAX (DXL_TORQUE_ON_TIME / (1000 / DXL_TORQUR_ON_STEP))
185 #define DXL_CURRENT2EFFORT(c,coef) (DXL_CURRENT_UNIT * (c) * (coef) * 0.001)// (mA*CONST*0.001)=Nm
186 #define EFFORT2DXL_CURRENT(e,coef) ((e) / (coef) / 0.001 / DXL_CURRENT_UNIT)// (Nm/CONST/0.001)=mA
187 #define DEFAULT_MAX_EFFORT (5.0)
188 #define EFFORT_LIMITING_CNT (10)
189 #define DXL_VELOCITY2RAD_S(v) ((v) * 0.229 * 0.1047)
191 #define DXL_WATCHDOG_RESET_VALUE (0)
192 #define MSEC2DXL_WATCHDOG(msec) ((uint8_t)(msec) / 20)
194 #define OPERATING_MODE_CURRENT (0)
195 #define OPERATING_MODE_VELOCITY (1)
196 #define OPERATING_MODE_POSITION (3)
197 #define OPERATING_MODE_EXT_POS (4)
198 #define OPERATING_MODE_CURR_POS (5)
199 #define OPERATING_MODE_PWM (16)
207 JOINT_CONTROL( std::string init_name, uint8_t init_dxlid, uint16_t init_center, uint16_t init_home,
double init_eff_const, uint8_t init_mode );
210 void init_parameter( std::string init_name, uint8_t init_dxlid, uint16_t init_center, uint16_t init_home,
double init_eff_const, uint8_t init_mode );
253 | (uint32_t)((
dxl_goal[1]<<8)&0x0000FF00)
254 | (uint32_t)((
dxl_goal[2]<<16)&0x00FF0000)
255 | (uint32_t)((
dxl_goal[3]<<24)&0xFF0000FF); }
uint16_t get_center(void)
double get_temprature(void)
ST_JOINT_PARAM get_joint_param(void)
bool is_effort_limiting(void)
void set_center(uint16_t set_center)
uint8_t * get_dxl_goal_addr(void)
void set_position(double set_rad)
uint32_t get_dxl_pos(void)
void init_parameter(std::string init_name, uint8_t init_dxlid, uint16_t init_center, uint16_t init_home, double init_eff_const, uint8_t init_mode)
void set_velocity(double set_vel)
uint8_t get_dxl_temp(void)
uint8_t get_eff_over_cnt(void)
void set_dxl_id(uint8_t set_id)
joint_limits_interface::JointLimits limits
void set_joint_name(std::string set_name)
@ enTableId_PositionPGain
@ enTableId_VelocityIGain
void set_current(double set_curr)
uint8_t get_dxl_goal(void)
double * get_effort_addr(void)
static const ST_DYNAMIXEL_REG_TABLE RegTable[]
void set_dxl_curr(uint16_t set_dxl_curr)
void set_temprature(double set_temp)
uint16_t moving_threshold
void set_eff_limiting(bool set_limiting)
void set_joint_param(ST_JOINT_PARAM set_param)
std::string get_joint_name(void)
uint8_t get_ope_mode(void)
void set_torque(bool set_trq)
void set_dxl_pos(uint32_t set_dxl_pos)
void set_connect(bool set_connect)
struct ST_JOINT_PARAM ST_JOINT_PARAM
@ enTableId_PositionIGain
double get_eff_const(void)
@ enTableId_PresentPosition
@ enTableId_PositionDGain
void updt_d_command(double val)
void set_home(uint16_t set_home)
double * get_command_addr(void)
@ enTableId_PresentVelocity
@ enTableId_MovingThreshold
@ enTableId_PresentCurrent
void set_effort(double set_eff)
uint8_t return_delay_time
void set_limits(joint_limits_interface::JointLimits &set_limits)
double get_max_effort(void)
uint16_t get_dxl_curr(void)
void set_dxl_temp(uint8_t set_dxl_temp)
double get_d_command(void)
double * get_velocity_addr(void)
double get_position(void)
void clear_eff_over(void)
double * get_position_addr(void)
void set_command(double set_cmd)
#define DEFAULT_MAX_EFFORT
double get_velocity(void)
@ enTableId_VelocityPGain
sciurus17_control
Author(s): Hiroyuki Nomura
autogenerated on Fri Aug 2 2024 08:37:24