indirect_address_node.cpp
Go to the documentation of this file.
1 // Copyright 2021 ROBOTIS CO., LTD.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 /*******************************************************************************
16  * This example is written for DYNAMIXEL X(excluding XL-320) and MX(2.0) series with U2D2.
17  * For other series, please refer to the product eManual and modify the Control Table addresses and other definitions.
18  * To test this example, please follow the commands below.
19  *
20  * Open terminal #1
21  * $ roscore
22  *
23  * Open terminal #2
24  * $ rosrun dynamixel_sdk_examples indirect_address_node
25  *
26  * Open terminal #3 (run one of below commands at a time)
27  * $ rostopic pub -1 /sync_set_position dynamixel_sdk_examples/SyncSetPosition "{id1: 1, id2: 2, position1: 0, position2: 1000}"
28  * $ rostopic pub -1 /sync_set_position dynamixel_sdk_examples/SyncSetPosition "{id1: 1, id2: 2, position1: 1000, position2: 0}"
29  * $ rosservice call /sync_get_position "{id1: 1, id2: 2}"
30  *
31  * Author: Jaehyun Shim
32 *******************************************************************************/
33 
34 #include <ros/ros.h>
35 
36 #include "std_msgs/String.h"
37 #include "dynamixel_sdk_examples/SyncGetPosition.h"
38 #include "dynamixel_sdk_examples/SyncSetPosition.h"
40 
41 using namespace dynamixel;
42 
43 // Control table address
44 #define ADDR_TORQUE_ENABLE 64
45 #define ADDR_PRESENT_POSITION 132
46 #define ADDR_GOAL_POSITION 116
47 #define ADDR_INDIRECT_ADDR1 168
48 #define ADDR_INDIRECT_ADDR5 176
49 #define ADDR_INDIRECT_DATA1 224
50 #define ADDR_INDIRECT_DATA5 228
51 
52 // Protocol version
53 #define PROTOCOL_VERSION 2.0 // Default Protocol version of DYNAMIXEL X series.
54 
55 // Default setting
56 #define DXL1_ID 1 // DXL1 ID
57 #define DXL2_ID 2 // DXL2 ID
58 #define BAUDRATE 57600 // Default Baudrate of DYNAMIXEL X series
59 #define DEVICE_NAME "/dev/ttyUSB0" // [Linux] To find assigned port, use "$ ls /dev/ttyUSB*" command
60 
63 
64 GroupSyncRead groupSyncRead(portHandler, packetHandler, ADDR_INDIRECT_DATA1, 4);
65 GroupSyncWrite groupSyncWrite(portHandler, packetHandler, ADDR_INDIRECT_DATA5, 4);
66 
68  dynamixel_sdk_examples::SyncGetPosition::Request & req,
69  dynamixel_sdk_examples::SyncGetPosition::Response & res)
70 {
71  uint8_t dxl_error = 0;
72  int dxl_comm_result = COMM_TX_FAIL;
73  int dxl_addparam_result = false;
74 
75  // Position Value of X series is 4 byte data. For AX & MX(1.0) use 2 byte data(int16_t) for the Position Value.
76  int32_t position1 = 0;
77  int32_t position2 = 0;
78 
79  // Read Present Position (length : 4 bytes) and Convert uint32 -> int32
80  // When reading 2 byte data from AX / MX(1.0), use read2ByteTxRx() instead.
81  dxl_addparam_result = groupSyncRead.addParam((uint8_t)req.id1);
82  if (dxl_addparam_result != true) {
83  ROS_ERROR("Failed to addparam to groupSyncRead for Dynamixel ID %d", req.id1);
84  return 0;
85  }
86 
87  dxl_addparam_result = groupSyncRead.addParam((uint8_t)req.id2);
88  if (dxl_addparam_result != true) {
89  ROS_ERROR("Failed to addparam to groupSyncRead for Dynamixel ID %d", req.id2);
90  return 0;
91  }
92 
93  dxl_comm_result = groupSyncRead.txRxPacket();
94  if (dxl_comm_result == COMM_SUCCESS) {
95  position1 = groupSyncRead.getData((uint8_t)req.id1, ADDR_INDIRECT_DATA1, 4);
96  position2 = groupSyncRead.getData((uint8_t)req.id2, ADDR_INDIRECT_DATA1, 4);
97  ROS_INFO("getPosition : [POSITION:%d]", position1);
98  ROS_INFO("getPosition : [POSITION:%d]", position2);
99  res.position1 = position1;
100  res.position2 = position2;
102  return true;
103  } else {
104  ROS_ERROR("Failed to get position! Result: %d", dxl_comm_result);
106  return false;
107  }
108 }
109 
110 void syncSetPositionCallback(const dynamixel_sdk_examples::SyncSetPosition::ConstPtr & msg)
111 {
112  uint8_t dxl_error = 0;
113  int dxl_comm_result = COMM_TX_FAIL;
114  int dxl_addparam_result = false;
115  uint8_t param_goal_position1[4];
116  uint8_t param_goal_position2[4];
117 
118  // Position Value of X series is 4 byte data. For AX & MX(1.0) use 2 byte data(uint16_t) for the Position Value.
119  uint32_t position1 = (unsigned int)msg->position1; // Convert int32 -> uint32
120  param_goal_position1[0] = DXL_LOBYTE(DXL_LOWORD(position1));
121  param_goal_position1[1] = DXL_HIBYTE(DXL_LOWORD(position1));
122  param_goal_position1[2] = DXL_LOBYTE(DXL_HIWORD(position1));
123  param_goal_position1[3] = DXL_HIBYTE(DXL_HIWORD(position1));
124  uint32_t position2 = (unsigned int)msg->position2; // Convert int32 -> uint32
125  param_goal_position2[0] = DXL_LOBYTE(DXL_LOWORD(position2));
126  param_goal_position2[1] = DXL_HIBYTE(DXL_LOWORD(position2));
127  param_goal_position2[2] = DXL_LOBYTE(DXL_HIWORD(position2));
128  param_goal_position2[3] = DXL_HIBYTE(DXL_HIWORD(position2));
129 
130  // Write Goal Position (length : 4 bytes)
131  // When writing 2 byte data to AX / MX(1.0), use write2ByteTxRx() instead.
132  dxl_addparam_result = groupSyncWrite.addParam((uint8_t)msg->id1, param_goal_position1);
133  if (dxl_addparam_result != true) {
134  ROS_ERROR( "Failed to addparam to groupSyncWrite for Dynamixel ID %d", msg->id1);
135  }
136 
137  dxl_addparam_result = groupSyncWrite.addParam((uint8_t)msg->id2, param_goal_position2);
138  if (dxl_addparam_result != true) {
139  ROS_ERROR( "Failed to addparam to groupSyncWrite for Dynamixel ID %d", msg->id2);
140  }
141 
142  dxl_comm_result = groupSyncWrite.txPacket();
143  if (dxl_comm_result == COMM_SUCCESS) {
144  ROS_INFO("setPosition : [ID:%d] [POSITION:%d]", msg->id1, msg->position1);
145  ROS_INFO("setPosition : [ID:%d] [POSITION:%d]", msg->id2, msg->position2);
146  } else {
147  ROS_ERROR("Failed to set position! Result: %d", dxl_comm_result);
148  }
149 
151 }
152 
153 int main(int argc, char ** argv)
154 {
155  uint8_t dxl_error = 0;
156  int dxl_comm_result = COMM_TX_FAIL;
157 
158  if (!portHandler->openPort()) {
159  ROS_ERROR("Failed to open the port!");
160  return -1;
161  }
162 
163  if (!portHandler->setBaudRate(BAUDRATE)) {
164  ROS_ERROR("Failed to set the baudrate!");
165  return -1;
166  }
167 
168  // Indirect address
169  for (uint8_t i = 0; i < 4; i++) {
170  dxl_comm_result = packetHandler->write2ByteTxRx(
171  portHandler, DXL1_ID, ADDR_INDIRECT_ADDR1 + i * 2, ADDR_PRESENT_POSITION + i, &dxl_error);
172  if (dxl_comm_result != COMM_SUCCESS) {
173  ROS_ERROR("Failed to set indirect address for Dynamixel ID %d", DXL1_ID);
174  return -1;
175  }
176 
177  dxl_comm_result = packetHandler->write2ByteTxRx(
178  portHandler, DXL1_ID, ADDR_INDIRECT_ADDR5 + i * 2, ADDR_GOAL_POSITION + i, &dxl_error);
179  if (dxl_comm_result != COMM_SUCCESS) {
180  ROS_ERROR("Failed to set indirect address for Dynamixel ID %d", DXL1_ID);
181  return -1;
182  }
183 
184  dxl_comm_result = packetHandler->write2ByteTxRx(
185  portHandler, DXL2_ID, ADDR_INDIRECT_ADDR1 + i * 2, ADDR_PRESENT_POSITION + i, &dxl_error);
186  if (dxl_comm_result != COMM_SUCCESS) {
187  ROS_ERROR("Failed to set indirect address for Dynamixel ID %d", DXL2_ID);
188  return -1;
189  }
190 
191  dxl_comm_result = packetHandler->write2ByteTxRx(
192  portHandler, DXL2_ID, ADDR_INDIRECT_ADDR5 + i * 2, ADDR_GOAL_POSITION + i, &dxl_error);
193  if (dxl_comm_result != COMM_SUCCESS) {
194  ROS_ERROR("Failed to set indirect address for Dynamixel ID %d", DXL2_ID);
195  return -1;
196  }
197  }
198 
199  dxl_comm_result = packetHandler->write1ByteTxRx(
200  portHandler, DXL1_ID, ADDR_TORQUE_ENABLE, 1, &dxl_error);
201  if (dxl_comm_result != COMM_SUCCESS) {
202  ROS_ERROR("Failed to enable torque for Dynamixel ID %d", DXL1_ID);
203  return -1;
204  }
205 
206  dxl_comm_result = packetHandler->write1ByteTxRx(
207  portHandler, DXL2_ID, ADDR_TORQUE_ENABLE, 1, &dxl_error);
208  if (dxl_comm_result != COMM_SUCCESS) {
209  ROS_ERROR("Failed to enable torque for Dynamixel ID %d", DXL2_ID);
210  return -1;
211  }
212 
213  ros::init(argc, argv, "indirect_address_node");
214  ros::NodeHandle nh;
215  ros::ServiceServer sync_get_position_srv = nh.advertiseService("/sync_get_position", syncGetPresentPositionCallback);
216  ros::Subscriber sync_set_position_sub = nh.subscribe("/sync_set_position", 10, syncSetPositionCallback);
217  ros::spin();
218 
219  portHandler->closePort();
220  return 0;
221 }
#define ADDR_PRESENT_POSITION
static PortHandler * getPortHandler(const char *port_name)
#define DXL1_ID
virtual bool openPort()=0
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool addParam(uint8_t id, uint8_t *data)
PortHandler * portHandler
bool addParam(uint8_t id)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
int COMM_SUCCESS
virtual void closePort()=0
#define ADDR_INDIRECT_ADDR5
#define ADDR_GOAL_POSITION
#define DXL2_ID
#define ROS_INFO(...)
bool syncGetPresentPositionCallback(dynamixel_sdk_examples::SyncGetPosition::Request &req, dynamixel_sdk_examples::SyncGetPosition::Response &res)
virtual int write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0)=0
ROSCPP_DECL void spin()
static PacketHandler * getPacketHandler(float protocol_version=2.0)
def DXL_HIBYTE(w)
def DXL_LOWORD(l)
#define ADDR_INDIRECT_DATA5
def DXL_HIWORD(l)
virtual int write2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error=0)=0
#define ADDR_INDIRECT_ADDR1
GroupSyncWrite groupSyncWrite(portHandler, packetHandler, ADDR_INDIRECT_DATA5, 4)
#define BAUDRATE
#define DEVICE_NAME
void syncSetPositionCallback(const dynamixel_sdk_examples::SyncSetPosition::ConstPtr &msg)
virtual bool setBaudRate(const int baudrate)=0
GroupSyncRead groupSyncRead(portHandler, packetHandler, ADDR_INDIRECT_DATA1, 4)
#define ADDR_INDIRECT_DATA1
#define ROS_ERROR(...)
#define ADDR_TORQUE_ENABLE
def DXL_LOBYTE(w)
#define PROTOCOL_VERSION
int main(int argc, char **argv)
PacketHandler * packetHandler
int COMM_TX_FAIL


dynamixel_sdk_examples
Author(s): zerom
autogenerated on Fri Apr 16 2021 02:25:58