+#include <unistd.h>
+#include <sys/types.h>
+#include <sys/ioctl.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+#include <mutex>
+#include <linux/i2c-dev.h>
+#include <hardware_interface/joint_command_interface.h>
+#include <hardware_interface/joint_state_interface.h>
+#include <hardware_interface/robot_hw.h>
+#include "std_srvs/SetBool.h"
+
+/* http://wiki.ros.org/joint_trajectory_controller?distro=melodic
+ *
+ * arm:
+ * - Gripper Goal Current(102)=200, Operating Mode(11)=Current-based Position Control Mode, Profile_Acceleration=20, Profile_Velocity=200
+ * - Read: Present Current(126), Present Velocity(128), Present Position(132)
+ * - Gripper joint limits:
+ * 0.010, // max gripper limit (0.01 m)
+ * -0.010, // min gripper limit (-0.01 m)
+ * -0.015, // Change unit from `meter` to `radian`
+ */
+
+#define I2C_FILE "/dev/i2c-2"
+#define I2C_ADDR (0x60>>1)
+#define XM_TORQUE_ENABLE 64
+#define XM_GOAL_POSITION 116
+#define XM_PRESENT_POSITION 132
+#define CMD_EOF 0xaa
+
+class WtOpenManipulatorI2C : public hardware_interface::RobotHW
+{
+ public:
+ WtOpenManipulatorI2C(ros::NodeHandle nh) {
+ this->nh = nh;
+ torque_enable_service = nh.advertiseService("torque_enable", &WtOpenManipulatorI2C::cbTorqueEnable, this);
+
+ // connect and register the joint state interface
+ hardware_interface::JointStateHandle state_handle_1("joint1", &pos[0], &vel[0], &eff[0]);
+ jnt_state_interface.registerHandle(state_handle_1);
+ hardware_interface::JointStateHandle state_handle_2("joint2", &pos[1], &vel[1], &eff[1]);
+ jnt_state_interface.registerHandle(state_handle_2);
+ hardware_interface::JointStateHandle state_handle_3("joint3", &pos[2], &vel[2], &eff[2]);
+ jnt_state_interface.registerHandle(state_handle_3);
+ hardware_interface::JointStateHandle state_handle_4("joint4", &pos[3], &vel[3], &eff[3]);
+ jnt_state_interface.registerHandle(state_handle_4);
+ registerInterface(&jnt_state_interface);
+
+ // connect and register the joint position interface
+ hardware_interface::JointHandle pos_handle_1(state_handle_1, &cmd[0]);
+ jnt_pos_interface.registerHandle(pos_handle_1);
+ hardware_interface::JointHandle pos_handle_2(state_handle_2, &cmd[1]);
+ jnt_pos_interface.registerHandle(pos_handle_2);
+ hardware_interface::JointHandle pos_handle_3(state_handle_3, &cmd[2]);
+ jnt_pos_interface.registerHandle(pos_handle_3);
+ hardware_interface::JointHandle pos_handle_4(state_handle_4, &cmd[3]);
+ jnt_pos_interface.registerHandle(pos_handle_4);
+ registerInterface(&jnt_pos_interface);
+
+ torque_enable(0x1);
+ }
+
+ // Converts pos_encoder from wheels to wheel angles
+ void read(ros::Duration period) {
+ for(int i=0, id=11; id<=14; id++, i++) {
+ int32_t value;
+ if (dynamixel_readdword(id, XM_PRESENT_POSITION, &value) != 1) {
+ ROS_ERROR("I2C dynamixel id=%d read error", id);
+ return;
+ }
+ pos[i] = 0.088*M_PI/180*(value-2048);
+ }
+ ROS_DEBUG("pos: %.2f %.2f %.2f %.2f", pos[0]*180/M_PI, pos[1]*180/M_PI, pos[2]*180/M_PI, pos[3]*180/M_PI);
+ }
+
+ // Writes current velocity command to hardware
+ void write() {
+ ROS_DEBUG("cmd: %.2f %.2f %.2f %.2f", cmd[0]*180/M_PI, cmd[1]*180/M_PI, cmd[2]*180/M_PI, cmd[3]*180/M_PI);
+
+ for(int i=0, id=11; id<=14; id++, i++) {
+ if (isnan(cmd[i])) {
+ ROS_WARN("Desired angle for id=%d is NaN, skipping write.", id);
+ continue;
+ }
+
+ int32_t value = cmd[i]/(0.088*M_PI/180) + 2048;
+
+ if (dynamixel_writedword(id, XM_GOAL_POSITION, value) != 1) {
+ ROS_ERROR("I2C dynamixel id=%d write error", id);
+ }
+ }
+ }
+
+ private:
+ hardware_interface::JointStateInterface jnt_state_interface;
+ hardware_interface::PositionJointInterface jnt_pos_interface;
+ ros::NodeHandle nh;
+ double cmd[4] = {NAN, NAN, NAN, NAN};
+ double pos[4] = {0, 0, 0, 0};
+ double vel[4] = {0, 0, 0, 0};
+ double eff[4] = {0, 0, 0, 0};
+ ros::ServiceServer torque_enable_service;
+ std::mutex comm_mutex;
+
+ int dynamixel_write(uint8_t *write_data, int write_num, uint8_t *read_data, int read_num) {
+ int file;
+ uint8_t buf[32];
+ int ret;
+ uint8_t read_buf[read_num+1]; // for unknown reason need to read one more byte with USI Slave
+
+ comm_mutex.lock();
+ if ((file = open(I2C_FILE, O_RDWR)) < 0) {
+ perror("open");
+ goto error;
+ }
+
+ if (ioctl(file, I2C_SLAVE, I2C_ADDR) < 0) {
+ perror("ioctl");
+ goto error;
+ }
+
+ if ((ret = i2c_smbus_write_i2c_block_data(file, 0x0, write_num, write_data)) != 0) {
+ perror("i2c_smbus_write_block_data");
+ goto error;
+ }
+
+ for(int i=0; i<10; i++) {
+ usleep(10*1000);
+
+ if ((ret = i2c_smbus_read_i2c_block_data(file, 0x0, read_num+1, read_buf)) != read_num+1) {
+ perror("i2c_smbus_write_block_data");
+ goto error;
+ }
+ if (read_data[0] == 1) {
+ break;
+ }
+ }
+ ret--; // remove extra byte
+ memcpy(read_data, read_buf, ret);
+
+ error:
+ close(file);
+ comm_mutex.unlock();
+ return ret;
+ }
+
+ uint8_t dynamixel_writebyte(uint8_t id, uint8_t cmd, uint8_t value) {
+ uint8_t write_data[5] = {id, cmd, 1, value, CMD_EOF};
+ uint8_t read_data[2];
+ int ret = dynamixel_write(write_data, 5, read_data, 2);
+ if (ret == 2 && read_data[1] == id) {
+ return read_data[0];
+ }
+ return 255;
+ }
+
+ uint8_t dynamixel_writedword(uint8_t id, uint8_t cmd, int32_t value) {
+ 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};
+ uint8_t read_data[2];
+ int ret = dynamixel_write(write_data, 8, read_data, 2);
+ if (ret == 2 && read_data[1] == id) {
+ return read_data[0];
+ }
+ return 255;
+ }
+
+ uint8_t dynamixel_readdword(uint8_t id, uint8_t cmd, int32_t *value) {
+ uint8_t write_data[4] = {id, cmd, 0x14, CMD_EOF};
+ uint8_t read_data[6];
+ int ret = dynamixel_write(write_data, 4, read_data, 6);
+ if (ret == 6 && read_data[1] == id) {
+ *value = (read_data[2]<<24) | (read_data[3]<<16) | (read_data[4]<<8) | read_data[5];
+ return read_data[0];
+ }
+ return 255;
+ }
+
+ bool torque_enable(uint8_t enable) {
+ bool ret = true;
+ for(int id=11; id<=14; id++) {
+ if (dynamixel_writebyte(id, XM_TORQUE_ENABLE, enable) != 1) {
+ ROS_ERROR("I2C dynamixel id=%d torque change", id);
+ ret = false;
+ }
+ }
+ return ret;
+ }
+
+ bool cbTorqueEnable(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) {
+ ROS_INFO("Setting torque enable=%d", req.data);
+ res.success = torque_enable(req.data);
+ return true;
+ }
+};