]> defiant.homedns.org Git - wt_open_manipulator.git/blob - include/open_manipulator_i2c.h
open_manipulator: increase torque to gripper
[wt_open_manipulator.git] / include / open_manipulator_i2c.h
1 #include <chrono>
2 #include <unistd.h>
3 #include <sys/types.h>
4 #include <sys/ioctl.h>
5 #include <sys/stat.h>
6 #include <fcntl.h>
7 #include <mutex>
8 #include <linux/i2c-dev.h>
9 #include <hardware_interface/joint_command_interface.h>
10 #include <hardware_interface/joint_state_interface.h>
11 #include <hardware_interface/robot_hw.h>
12 #include "std_srvs/SetBool.h"
13 #include "wt_open_manipulator/GetError.h"
14
15 #define I2C_FILE "/dev/i2c-2"
16 #define I2C_ADDR (0x60>>1)
17 #define XM_OPERATING_MODE 11
18 #define XM_CURRENT_LIMIT 38
19 #define XM_SHUTDOWN 63
20 #define XM_TORQUE_ENABLE 64
21 #define XM_HARDWARE_ERROR_STATUS 70
22 #define XM_GOAL_CURRENT 102
23 #define XM_PROFILE_ACCELERATION 108
24 #define XM_PROFILE_VELOCITY 112
25 #define XM_GOAL_POSITION 116
26 #define XM_PRESENT_POSITION 132
27 #define XM_PRESENT_CURRENT 126
28 #define XM_PRESENT_VELOCITY 128
29 #define CMD_EOF 0xaa
30 #define STEPS_TO_RADIAN (2*M_PI/4096)
31 #define GRIPPER_RADIAN_TO_METER -0.015
32 #define VELOCITY_STEPS_TO_RADS (0.229*2*M_PI/60)
33
34 class WtOpenManipulatorI2C : public hardware_interface::RobotHW
35 {
36         public:
37                 WtOpenManipulatorI2C(ros::NodeHandle nh) {
38                         uint8_t mode=255;
39                         this->nh = nh;
40                         int16_t current;
41                         torque_enable_service = nh.advertiseService("torque_enable", &WtOpenManipulatorI2C::cbTorqueEnable, this);
42                         get_error_service = nh.advertiseService("get_error", &WtOpenManipulatorI2C::cbGetError, this);
43
44                         // connect and register the joint state interface
45                         hardware_interface::JointStateHandle state_handle_1("joint1", &pos[0], &vel[0], &eff[0]);
46                         jnt_state_interface.registerHandle(state_handle_1);
47                         hardware_interface::JointStateHandle state_handle_2("joint2", &pos[1], &vel[1], &eff[1]);
48                         jnt_state_interface.registerHandle(state_handle_2);
49                         hardware_interface::JointStateHandle state_handle_3("joint3", &pos[2], &vel[2], &eff[2]);
50                         jnt_state_interface.registerHandle(state_handle_3);
51                         hardware_interface::JointStateHandle state_handle_4("joint4", &pos[3], &vel[3], &eff[3]);
52                         jnt_state_interface.registerHandle(state_handle_4);
53                         hardware_interface::JointStateHandle state_handle_gripper("gripper", &pos[4], &vel[4], &eff[4]);
54                         jnt_state_interface.registerHandle(state_handle_gripper);
55                         registerInterface(&jnt_state_interface);
56
57                         // connect and register the joint position interface
58                         hardware_interface::JointHandle pos_handle_1(state_handle_1, &cmd[0]);
59                         jnt_pos_interface.registerHandle(pos_handle_1);
60                         hardware_interface::JointHandle pos_handle_2(state_handle_2, &cmd[1]);
61                         jnt_pos_interface.registerHandle(pos_handle_2);
62                         hardware_interface::JointHandle pos_handle_3(state_handle_3, &cmd[2]);
63                         jnt_pos_interface.registerHandle(pos_handle_3);
64                         hardware_interface::JointHandle pos_handle_4(state_handle_4, &cmd[3]);
65                         jnt_pos_interface.registerHandle(pos_handle_4);
66                         hardware_interface::JointHandle pos_handle_gripper(state_handle_gripper, &cmd[4]);
67                         jnt_pos_interface.registerHandle(pos_handle_gripper);
68                         registerInterface(&jnt_pos_interface);
69
70                         // Settings
71                         if (dynamixel_writeword(15, XM_GOAL_CURRENT, 600) != 1) { // 0..1193, 2.69mA/value
72                                 ROS_ERROR("I2C dynamixel id=15 write goal current error");
73                                 exit(1);
74                         }
75                         if (dynamixel_readbyte(15, XM_OPERATING_MODE, &mode) != 1) {
76                                 ROS_ERROR("I2C dynamixel id=15 read operating Mode error");
77                                 exit(1);
78                         }
79                         if (mode != 5) {
80                                 if (!torque_enable(false)) {
81                                         exit(1);
82                                 }
83                                 if (dynamixel_writebyte(15, XM_OPERATING_MODE, 5) != 1) { // Current-based Position Control Mode
84                                         ROS_ERROR("I2C dynamixel id=15 write operating Mode error");
85                                         exit(1);
86                                 }
87                         }
88                         if (dynamixel_writedword(15, XM_PROFILE_ACCELERATION, 20) != 1) {
89                                 ROS_ERROR("I2C dynamixel id=15 write profile Acceleration error");
90                                 exit(1);
91                         }
92                         if (dynamixel_writedword(15, XM_PROFILE_VELOCITY, 200) != 1) {
93                                 ROS_ERROR("I2C dynamixel id=15 write profile Velocity error");
94                                 exit(1);
95                         }
96                         if (!torque_enable(true)) {
97                                 exit(1);
98                         }
99                 }
100
101                 // Converts pos_encoder from wheels to wheel angles
102                 void read(ros::Duration period) {
103                         int32_t value;
104                         int16_t current;
105                         auto t1 = std::chrono::high_resolution_clock::now();
106                         int num_error = 0;
107
108                         // arm
109                         for(int i=0, id=11; id<=14; id++, i++) {
110                                 if (ignore_ids.count(i)  > 0) {
111                                         ROS_ERROR_THROTTLE(10, "Ignoring dynamixel %d", id);
112                                         continue;
113                                 }
114
115                                 if (dynamixel_readdword(id, XM_PRESENT_POSITION, &value) == 1) {
116                                         pos[i] = STEPS_TO_RADIAN*(value-2048);
117                                 } else {
118                                         ROS_ERROR("I2C dynamixel id=%d position read error", id);
119                                         num_error++;
120                                 }
121
122                                 if (dynamixel_readdword(id, XM_PRESENT_VELOCITY, &value) == 1) {
123                                         vel[i] = value*VELOCITY_STEPS_TO_RADS;
124                                 } else {
125                                         ROS_ERROR("I2C dynamixel id=%d velocity read error", id);
126                                         num_error++;
127                                 }
128
129 #ifdef READ_EFFORT
130                                 if (dynamixel_readword(id, XM_PRESENT_CURRENT, &current) == 1) {
131                                         eff[i] = current*2.69e-3;
132                                 } else {
133                                         ROS_ERROR("I2C dynamixel id=%d current read error", id);
134                                         num_error++;
135                                 }
136 #endif
137
138                                 if (num_error >= 3) {
139                                         ignore_ids.insert(i);
140                                 }
141                         }
142
143                         // gripper
144                         if (dynamixel_readdword(15, XM_PRESENT_POSITION, &value) == 1) {
145                                 pos[4] = STEPS_TO_RADIAN*(value-2048)*GRIPPER_RADIAN_TO_METER;
146                         } else {
147                                 ROS_ERROR("I2C dynamixel id=15 position read error");
148                         }
149                         if (dynamixel_readdword(15, XM_PRESENT_VELOCITY, &value) == 1) {
150                                 vel[4] = value*VELOCITY_STEPS_TO_RADS*GRIPPER_RADIAN_TO_METER;
151                         } else {
152                                 ROS_ERROR("I2C dynamixel id=15 velocity read error");
153                         }
154 #ifdef READ_EFFORT
155                         if (dynamixel_readword(15, XM_PRESENT_CURRENT, &current) == 1) {
156                                 eff[4] = current*2.69e-3;
157                         } else {
158                                 ROS_ERROR("I2C dynamixel id=15 current read error");
159                         }
160 #endif
161
162                         ROS_DEBUG("pos: %.2f %.2f %.2f %.2f %.2f", pos[0]*180/M_PI, pos[1]*180/M_PI, pos[2]*180/M_PI, pos[3]*180/M_PI, pos[4]);
163                         ROS_DEBUG("velocity: %.2f %.2f %.2f %.2f %.2f", vel[0]*30/M_PI, vel[1]*30/M_PI, vel[2]*30/M_PI, vel[3]*30/M_PI, vel[4]);
164 #ifdef READ_EFFORT
165                         ROS_DEBUG("current: %.2f %.2f %.2f %.2f %.2f", eff[0], eff[1], eff[2], eff[3], eff[4]);
166 #endif
167                         auto t2 = std::chrono::high_resolution_clock::now();
168                         int64_t duration = std::chrono::duration_cast<std::chrono::milliseconds>( t2 - t1 ).count();
169                         ROS_DEBUG("read duration: %lldms", duration);
170                 }
171
172                 // Writes current velocity command to hardware
173                 void write() {
174                         int32_t value;
175
176                         if (memcmp(cmd, cmd_pre, sizeof(cmd)) != 0) { // Only write new position when changed
177                                 ROS_DEBUG("cmd: %.2f %.2f %.2f %.2f %.2f", cmd[0]*180/M_PI, cmd[1]*180/M_PI, cmd[2]*180/M_PI, cmd[3]*180/M_PI, cmd[4]);
178
179                                 // arm
180                                 for(int i=0, id=11; id<=14; id++, i++) {
181                                         if (isnan(cmd[i])) {
182                                                 ROS_WARN("Desired angle for id=%d is NaN, skipping write.", id);
183                                                 continue;
184                                         }
185
186                                         value = cmd[i]/STEPS_TO_RADIAN + 2048;
187
188                                         if (dynamixel_writedword(id, XM_GOAL_POSITION, value) == 1) {
189                                                 cmd_pre[i] = cmd[i];
190                                         } else {
191                                                 ROS_ERROR("I2C dynamixel id=%d write error", id);
192                                         }
193                                 }
194
195                                 // gripper
196                                 if (isnan(cmd[4]) || cmd[4] < -0.010 || cmd[4] > 0.019) {
197                                         ROS_WARN("Desired angle for id=15 is NaN or outside joint limit, skipping write.");
198                                 } else {
199                                         value = cmd[4]/GRIPPER_RADIAN_TO_METER/STEPS_TO_RADIAN + 2048;
200                                         if (dynamixel_writedword(15, XM_GOAL_POSITION, value) == 1) {
201                                                 cmd_pre[4] = cmd[4];
202                                         } else {
203                                                 ROS_ERROR("I2C dynamixel id=15 write error");
204                                         }
205                                 }
206                         }
207                 }
208
209                 bool torque_enable(bool enable) {
210                         bool ret = true;
211                         for(int id=11; id<=15; id++) {
212                                 if (dynamixel_writebyte(id, XM_TORQUE_ENABLE, enable) != 1) {
213                                         ROS_ERROR("I2C dynamixel id=%d torque change", id);
214                                         ret = false;
215                                 }
216                         }
217                         return ret;
218                 }
219
220         private:
221                 hardware_interface::JointStateInterface jnt_state_interface;
222                 hardware_interface::PositionJointInterface jnt_pos_interface;
223                 ros::NodeHandle nh;
224                 double cmd[5] = {NAN, NAN, NAN, NAN, NAN};
225                 double cmd_pre[5] = {NAN, NAN, NAN, NAN, NAN}; // determine if cmd changed
226                 double pos[5] = {0, 0, 0, 0, 0};
227                 double vel[5] = {0, 0, 0, 0, 0};
228                 double eff[5] = {0, 0, 0, 0, 0};
229                 ros::ServiceServer torque_enable_service, get_error_service;
230                 std::mutex comm_mutex;
231                 std::set<int> ignore_ids;
232
233                 int dynamixel_write(uint8_t *write_data, int write_num, uint8_t *read_data, int read_num) {
234                         int file;
235                         int ret;
236                         uint8_t read_buf[read_num+1]; // for unknown reason need to read one more byte with USI Slave
237
238                         comm_mutex.lock();
239                         if ((file = open(I2C_FILE, O_RDWR)) < 0) {
240                                 perror("open");
241                                 goto error;
242                         }
243
244                         if (ioctl(file, I2C_SLAVE, I2C_ADDR) < 0) {
245                                 perror("ioctl");
246                                 goto error;
247                         }
248
249                         if ((ret = ::write(file, write_data, write_num)) != write_num) {
250                                 perror("i2c write");
251                                 goto error;
252                         }
253
254                         // wait at least the half duplex transmission time, assume 29 (=14+15) bytes send/received: 1/(115200.0/10/29) <= 2.6ms
255                         usleep(3.2*1e3);
256                         if (read_num > 0) {
257                                 if ((ret = ::read(file, read_buf, read_num+1)) != read_num+1) {
258                                         perror("i2c read");
259                                         goto error;
260                                 }
261                                 ret--; // remove extra byte
262                                 memcpy(read_data, read_buf, ret);
263                         }
264
265                         error:
266                                 close(file);
267                                 comm_mutex.unlock();
268                                 return ret;
269                 }
270
271                 uint8_t dynamixel_writebyte(uint8_t id, uint8_t cmd, uint8_t value) {
272                         uint8_t write_data[5] = {id, cmd, 1, value, CMD_EOF};
273                         uint8_t read_data[2];
274                         int ret = dynamixel_write(write_data, 5, read_data, 2);
275                         if (ret == 2 && read_data[1] == id) {
276                                 return read_data[0];
277                         }
278                         return 255;
279                 }
280
281                 uint8_t dynamixel_writeword(uint8_t id, uint8_t cmd, int16_t value) {
282                         uint8_t write_data[6] = {id, cmd, 2, (uint8_t)(value>>8), (uint8_t)value, CMD_EOF};
283                         uint8_t read_data[2];
284                         int ret = dynamixel_write(write_data, 6, read_data, 2);
285                         if (ret == 2 && read_data[1] == id) {
286                                 return read_data[0];
287                         }
288                         return 255;
289                 }
290
291                 uint8_t dynamixel_writedword(uint8_t id, uint8_t cmd, int32_t value) {
292                         uint8_t write_data[8] = {id, cmd, 4, (uint8_t)(value>>24), (uint8_t)(value>>16), (uint8_t)(value>>8), (uint8_t)value, CMD_EOF};
293                         uint8_t read_data[2];
294                         int ret = dynamixel_write(write_data, 8, read_data, 2);
295                         if (ret == 2 && read_data[1] == id) {
296                                 return read_data[0];
297                         }
298                         return 255;
299                 }
300
301                 uint8_t dynamixel_readbyte(uint8_t id, uint8_t cmd, uint8_t *value) {
302                         uint8_t write_data[4] = {id, cmd, 0x11, CMD_EOF};
303                         uint8_t read_data[3];
304                         int ret = dynamixel_write(write_data, 4, read_data, 3);
305                         if (ret == 3 && read_data[1] == id) {
306                                 *value = read_data[2];
307                                 return read_data[0];
308                         }
309                         if (read_data[0] != 1) {
310                                 ROS_ERROR("I2C dynamixel id=%d alert value: %d", id, read_data[0]);
311                         }
312                         return 255;
313                 }
314
315                 uint8_t dynamixel_readword(uint8_t id, uint8_t cmd, int16_t *value) {
316                         uint8_t write_data[4] = {id, cmd, 0x12, CMD_EOF};
317                         uint8_t read_data[4];
318                         int ret = dynamixel_write(write_data, 4, read_data, 4);
319                         if (ret == 4 && read_data[1] == id) {
320                                 *value = (read_data[2]<<8) | read_data[3];
321                                 return read_data[0];
322                         }
323                         return 255;
324                 }
325
326                 uint8_t dynamixel_readdword(uint8_t id, uint8_t cmd, int32_t *value) {
327                         uint8_t write_data[4] = {id, cmd, 0x14, CMD_EOF};
328                         uint8_t read_data[6];
329                         int ret = dynamixel_write(write_data, 4, read_data, 6);
330                         if (ret == 6 && read_data[0] == 1 && read_data[1] == id) {
331                                 *value = (read_data[2]<<24) | (read_data[3]<<16) | (read_data[4]<<8) | read_data[5];
332                                 return read_data[0];
333                         }
334                         if (read_data[0] != 1) {
335                                 ROS_ERROR("I2C dynamixel id=%d alert value: %d", id, read_data[0]);
336                         }
337                         return 255;
338                 }
339
340                 bool cbTorqueEnable(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) {
341                         ROS_INFO("Setting torque enable=%d", req.data);
342                         res.success = torque_enable(req.data);
343                         return true;
344                 }
345
346                 bool cbGetError(wt_open_manipulator::GetError::Request &req, wt_open_manipulator::GetError::Response &res) {
347                         ROS_INFO("Reading Hardware Error Status");
348
349                         for(int id=11, i=0; id<=15; id++, i++) {
350                                 wt_open_manipulator::HardwareError hw_error;
351                                 uint8_t value;
352                                 if (dynamixel_readbyte(id, XM_HARDWARE_ERROR_STATUS, &value) != 1) {
353                                         ROS_ERROR("I2C dynamixel id=%d reading hardware error status", id);
354                                 }
355                                 hw_error.id = id;
356                                 hw_error.inputVoltage = value & (1<<0);
357                                 hw_error.overHeating = value & (1<<2);
358                                 hw_error.motorEncoder = value & (1<<3);
359                                 hw_error.electricalShock = value & (1<<4);
360                                 hw_error.overload = value & (1<<5);
361                                 res.errors.push_back(hw_error);
362                         }
363
364                         return true;
365                 }
366 };