sync_read_write_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 sync_read_write_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 
48 // Protocol version
49 #define PROTOCOL_VERSION 2.0 // Default Protocol version of DYNAMIXEL X series.
50 
51 // Default setting
52 #define DXL1_ID 1 // DXL1 ID
53 #define DXL2_ID 2 // DXL2 ID
54 #define BAUDRATE 57600 // Default Baudrate of DYNAMIXEL X series
55 #define DEVICE_NAME "/dev/ttyUSB0" // [Linux] To find assigned port, use "$ ls /dev/ttyUSB*" command
56 
59 
62 
64  dynamixel_sdk_examples::SyncGetPosition::Request & req,
65  dynamixel_sdk_examples::SyncGetPosition::Response & res)
66 {
67  uint8_t dxl_error = 0;
68  int dxl_comm_result = COMM_TX_FAIL;
69  int dxl_addparam_result = false;
70 
71  // Position Value of X series is 4 byte data. For AX & MX(1.0) use 2 byte data(int16_t) for the Position Value.
72  int32_t position1 = 0;
73  int32_t position2 = 0;
74 
75  // Read Present Position (length : 4 bytes) and Convert uint32 -> int32
76  // When reading 2 byte data from AX / MX(1.0), use read2ByteTxRx() instead.
77  dxl_addparam_result = groupSyncRead.addParam((uint8_t)req.id1);
78  if (dxl_addparam_result != true) {
79  ROS_ERROR("Failed to addparam to groupSyncRead for Dynamixel ID %d", req.id1);
80  return 0;
81  }
82 
83  dxl_addparam_result = groupSyncRead.addParam((uint8_t)req.id2);
84  if (dxl_addparam_result != true) {
85  ROS_ERROR("Failed to addparam to groupSyncRead for Dynamixel ID %d", req.id2);
86  return 0;
87  }
88 
89  dxl_comm_result = groupSyncRead.txRxPacket();
90  if (dxl_comm_result == COMM_SUCCESS) {
91  position1 = groupSyncRead.getData((uint8_t)req.id1, ADDR_PRESENT_POSITION, 4);
92  position2 = groupSyncRead.getData((uint8_t)req.id2, ADDR_PRESENT_POSITION, 4);
93  ROS_INFO("getPosition : [POSITION:%d]", position1);
94  ROS_INFO("getPosition : [POSITION:%d]", position2);
95  res.position1 = position1;
96  res.position2 = position2;
98  return true;
99  } else {
100  ROS_ERROR("Failed to get position! Result: %d", dxl_comm_result);
102  return false;
103  }
104 }
105 
106 void syncSetPositionCallback(const dynamixel_sdk_examples::SyncSetPosition::ConstPtr & msg)
107 {
108  uint8_t dxl_error = 0;
109  int dxl_comm_result = COMM_TX_FAIL;
110  int dxl_addparam_result = false;
111  uint8_t param_goal_position1[4];
112  uint8_t param_goal_position2[4];
113 
114  // Position Value of X series is 4 byte data. For AX & MX(1.0) use 2 byte data(uint16_t) for the Position Value.
115  uint32_t position1 = (unsigned int)msg->position1; // Convert int32 -> uint32
116  param_goal_position1[0] = DXL_LOBYTE(DXL_LOWORD(position1));
117  param_goal_position1[1] = DXL_HIBYTE(DXL_LOWORD(position1));
118  param_goal_position1[2] = DXL_LOBYTE(DXL_HIWORD(position1));
119  param_goal_position1[3] = DXL_HIBYTE(DXL_HIWORD(position1));
120  uint32_t position2 = (unsigned int)msg->position2; // Convert int32 -> uint32
121  param_goal_position2[0] = DXL_LOBYTE(DXL_LOWORD(position2));
122  param_goal_position2[1] = DXL_HIBYTE(DXL_LOWORD(position2));
123  param_goal_position2[2] = DXL_LOBYTE(DXL_HIWORD(position2));
124  param_goal_position2[3] = DXL_HIBYTE(DXL_HIWORD(position2));
125 
126  // Write Goal Position (length : 4 bytes)
127  // When writing 2 byte data to AX / MX(1.0), use write2ByteTxRx() instead.
128  dxl_addparam_result = groupSyncWrite.addParam((uint8_t)msg->id1, param_goal_position1);
129  if (dxl_addparam_result != true) {
130  ROS_ERROR( "Failed to addparam to groupSyncWrite for Dynamixel ID %d", msg->id1);
131  }
132 
133  dxl_addparam_result = groupSyncWrite.addParam((uint8_t)msg->id2, param_goal_position2);
134  if (dxl_addparam_result != true) {
135  ROS_ERROR( "Failed to addparam to groupSyncWrite for Dynamixel ID %d", msg->id2);
136  }
137 
138  dxl_comm_result = groupSyncWrite.txPacket();
139  if (dxl_comm_result == COMM_SUCCESS) {
140  ROS_INFO("setPosition : [ID:%d] [POSITION:%d]", msg->id1, msg->position1);
141  ROS_INFO("setPosition : [ID:%d] [POSITION:%d]", msg->id2, msg->position2);
142  } else {
143  ROS_ERROR("Failed to set position! Result: %d", dxl_comm_result);
144  }
145 
147 }
148 
149 int main(int argc, char ** argv)
150 {
151  uint8_t dxl_error = 0;
152  int dxl_comm_result = COMM_TX_FAIL;
153 
154  if (!portHandler->openPort()) {
155  ROS_ERROR("Failed to open the port!");
156  return -1;
157  }
158 
160  ROS_ERROR("Failed to set the baudrate!");
161  return -1;
162  }
163 
164  dxl_comm_result = packetHandler->write1ByteTxRx(
165  portHandler, DXL1_ID, ADDR_TORQUE_ENABLE, 1, &dxl_error);
166  if (dxl_comm_result != COMM_SUCCESS) {
167  ROS_ERROR("Failed to enable torque for Dynamixel ID %d", DXL1_ID);
168  return -1;
169  }
170 
171  dxl_comm_result = packetHandler->write1ByteTxRx(
172  portHandler, DXL2_ID, ADDR_TORQUE_ENABLE, 1, &dxl_error);
173  if (dxl_comm_result != COMM_SUCCESS) {
174  ROS_ERROR("Failed to enable torque for Dynamixel ID %d", DXL2_ID);
175  return -1;
176  }
177 
178  ros::init(argc, argv, "sync_read_write_node");
179  ros::NodeHandle nh;
180  ros::ServiceServer sync_get_position_srv = nh.advertiseService("/sync_get_position", syncGetPresentPositionCallback);
181  ros::Subscriber sync_set_position_sub = nh.subscribe("/sync_set_position", 10, syncSetPositionCallback);
182  ros::spin();
183 
185  return 0;
186 }
ADDR_GOAL_POSITION
#define ADDR_GOAL_POSITION
Definition: sync_read_write_node.cpp:46
COMM_TX_FAIL
int COMM_TX_FAIL
packetHandler
PacketHandler * packetHandler
Definition: sync_read_write_node.cpp:58
dynamixel::GroupSyncRead::clearParam
void clearParam()
dynamixel::GroupSyncRead::addParam
bool addParam(uint8_t id)
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
main
int main(int argc, char **argv)
Definition: sync_read_write_node.cpp:149
dynamixel::PortHandler::setBaudRate
virtual bool setBaudRate(const int baudrate)=0
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
PROTOCOL_VERSION
#define PROTOCOL_VERSION
Definition: sync_read_write_node.cpp:49
ros::ServiceServer
syncSetPositionCallback
void syncSetPositionCallback(const dynamixel_sdk_examples::SyncSetPosition::ConstPtr &msg)
Definition: sync_read_write_node.cpp:106
dynamixel
dynamixel::PortHandler
dynamixel::GroupSyncWrite::addParam
bool addParam(uint8_t id, uint8_t *data)
BAUDRATE
#define BAUDRATE
Definition: sync_read_write_node.cpp:54
dynamixel::PacketHandler::getPacketHandler
static PacketHandler * getPacketHandler(float protocol_version=2.0)
ADDR_PRESENT_POSITION
#define ADDR_PRESENT_POSITION
Definition: sync_read_write_node.cpp:45
dynamixel::GroupSyncWrite::txPacket
int txPacket()
COMM_SUCCESS
int COMM_SUCCESS
groupSyncWrite
GroupSyncWrite groupSyncWrite(portHandler, packetHandler, ADDR_GOAL_POSITION, 4)
DXL_HIBYTE
def DXL_HIBYTE(w)
dynamixel::PortHandler::getPortHandler
static PortHandler * getPortHandler(const char *port_name)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
dynamixel::PortHandler::openPort
virtual bool openPort()=0
dynamixel::PacketHandler::write1ByteTxRx
virtual int write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0)=0
ADDR_TORQUE_ENABLE
#define ADDR_TORQUE_ENABLE
Definition: sync_read_write_node.cpp:44
DXL_LOWORD
def DXL_LOWORD(l)
dynamixel::GroupSyncWrite
ROS_ERROR
#define ROS_ERROR(...)
dynamixel::GroupSyncRead::txRxPacket
int txRxPacket()
DEVICE_NAME
#define DEVICE_NAME
Definition: sync_read_write_node.cpp:55
DXL_LOBYTE
def DXL_LOBYTE(w)
DXL_HIWORD
def DXL_HIWORD(l)
dynamixel_sdk.h
ros::spin
ROSCPP_DECL void spin()
dynamixel::GroupSyncRead
DXL2_ID
#define DXL2_ID
Definition: sync_read_write_node.cpp:53
groupSyncRead
GroupSyncRead groupSyncRead(portHandler, packetHandler, ADDR_PRESENT_POSITION, 4)
dynamixel::GroupSyncRead::getData
uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)
ROS_INFO
#define ROS_INFO(...)
dynamixel::GroupSyncWrite::clearParam
void clearParam()
dynamixel::PortHandler::closePort
virtual void closePort()=0
syncGetPresentPositionCallback
bool syncGetPresentPositionCallback(dynamixel_sdk_examples::SyncGetPosition::Request &req, dynamixel_sdk_examples::SyncGetPosition::Response &res)
Definition: sync_read_write_node.cpp:63
DXL1_ID
#define DXL1_ID
Definition: sync_read_write_node.cpp:52
dynamixel::PacketHandler
ros::NodeHandle
ros::Subscriber
portHandler
PortHandler * portHandler
Definition: sync_read_write_node.cpp:57


dynamixel_sdk_examples
Author(s): zerom
autogenerated on Wed Mar 2 2022 00:13:53