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