36 #include "std_msgs/String.h"
37 #include "dynamixel_sdk_examples/BulkGetItem.h"
38 #include "dynamixel_sdk_examples/BulkSetItem.h"
44 #define ADDR_TORQUE_ENABLE 64
45 #define ADDR_PRESENT_LED 65
46 #define ADDR_PRESENT_POSITION 132
47 #define ADDR_GOAL_POSITION 116
50 #define PROTOCOL_VERSION 2.0 // Default Protocol version of DYNAMIXEL X series.
53 #define DXL1_ID 1 // DXL1 ID
54 #define DXL2_ID 2 // DXL2 ID
55 #define BAUDRATE 57600 // Default Baudrate of DYNAMIXEL X series
56 #define DEVICE_NAME "/dev/ttyUSB0" // [Linux] To find assigned port, use "$ ls /dev/ttyUSB*" command
65 dynamixel_sdk_examples::BulkGetItem::Request & req,
66 dynamixel_sdk_examples::BulkGetItem::Response & res)
68 uint8_t dxl_error = 0;
70 int dxl_addparam_result =
false;
73 int32_t position1 = 0;
74 int32_t position2 = 0;
78 if (req.item1 ==
"position") {
80 }
else if (req.item1 ==
"LED") {
83 if (dxl_addparam_result !=
true) {
84 ROS_ERROR(
"Failed to addparam to groupBulkRead for Dynamixel ID: %d", req.id1);
88 if (req.item2 ==
"position") {
90 }
else if (req.item2 ==
"LED") {
93 if (dxl_addparam_result !=
true) {
94 ROS_ERROR(
"Failed to addparam to groupBulkRead for Dynamixel ID %d", req.id2);
102 if (req.item1 ==
"position") {
104 }
else if (req.item2 ==
"LED") {
108 if (req.item1 ==
"position") {
110 }
else if (req.item2 ==
"LED") {
114 ROS_INFO(
"getItem : [ID:%d] [%s: %d]", req.id1, req.item1.c_str(), value1);
115 ROS_INFO(
"getItem : [ID:%d] [%s: %d]", req.id2, req.item2.c_str(), value2);
121 ROS_ERROR(
"Failed to get position! Result: %d", dxl_comm_result);
129 uint8_t dxl_error = 0;
131 int dxl_addparam_result =
false;
132 uint8_t param_goal_position1[4];
133 uint8_t param_goal_position2[4];
134 uint8_t param_goal_led1[1];
135 uint8_t param_goal_led2[1];
136 uint8_t addr_goal_item[2];
137 uint8_t len_goal_item[2];
140 if (msg->item1 ==
"position") {
141 uint32_t position1 = (
unsigned int)msg->value1;
147 len_goal_item[0] = 4;
148 }
else if (msg->item1 ==
"LED") {
149 uint32_t led1 = (
unsigned int)msg->value1;
150 param_goal_led1[0] = led1;
152 len_goal_item[0] = 1;
155 if (msg->item2 ==
"position") {
156 uint32_t position2 = (
unsigned int)msg->value2;
162 len_goal_item[1] = 4;
163 }
else if (msg->item2 ==
"LED") {
164 uint32_t led2 = (
unsigned int)msg->value2;
165 param_goal_led2[0] = led2;
167 len_goal_item[1] = 1;
172 if (msg->item1 ==
"position") {
173 dxl_addparam_result =
groupBulkWrite.
addParam((uint8_t)msg->id1, addr_goal_item[0], len_goal_item[0], param_goal_position1);
174 }
else if (msg->item1 ==
"LED") {
175 dxl_addparam_result =
groupBulkWrite.
addParam((uint8_t)msg->id1, addr_goal_item[0], len_goal_item[0], param_goal_led1);
177 if (dxl_addparam_result !=
true) {
178 ROS_ERROR(
"Failed to addparam to groupBulkWrite for Dynamixel ID: %d", msg->id1);
181 if (msg->item2 ==
"position") {
182 dxl_addparam_result =
groupBulkWrite.
addParam((uint8_t)msg->id2, addr_goal_item[1], len_goal_item[1], param_goal_position2);
183 }
else if (msg->item2 ==
"LED") {
184 dxl_addparam_result =
groupBulkWrite.
addParam((uint8_t)msg->id2, addr_goal_item[1], len_goal_item[1], param_goal_led2);
186 if (dxl_addparam_result !=
true) {
187 ROS_ERROR(
"Failed to addparam to groupBulkWrite for Dynamixel ID: %d", msg->id2);
192 ROS_INFO(
"setItem : [ID:%d] [%s:%d]", msg->id1, msg->item1.c_str(), msg->value1);
193 ROS_INFO(
"setItem : [ID:%d] [%s:%d]", msg->id2, msg->item2.c_str(), msg->value2);
195 ROS_INFO(
"Failed to set position! Result: %d", dxl_comm_result);
201 int main(
int argc,
char ** argv)
203 uint8_t dxl_error = 0;
212 ROS_ERROR(
"Failed to set the baudrate!");
230 ros::init(argc, argv,
"bulk_read_write_node");