MercurySDK
Software development kit for Mercury digital servos
read_write.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright (C) 2021 <Robot Articulation/code@robotarticulation.com>
3 *
4 * Source files modified to support the Mercury range of digital servo motors from Robot Articulation
5 *******************************************************************************/
6 
7 /*******************************************************************************
8 * Copyright 2017 ROBOTIS CO., LTD.
9 *
10 * Licensed under the Apache License, Version 2.0 (the "License");
11 * you may not use this file except in compliance with the License.
12 * You may obtain a copy of the License at
13 *
14 * http://www.apache.org/licenses/LICENSE-2.0
15 *
16 * Unless required by applicable law or agreed to in writing, software
17 * distributed under the License is distributed on an "AS IS" BASIS,
18 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
19 * See the License for the specific language governing permissions and
20 * limitations under the License.
21 *******************************************************************************/
22 
23 /* Original author: Zerom, Leon (RyuWoon Jung) */
24 
25 //
26 // ********* Read and Write Example *********
27 //
28 // This example is tested with a Mercury M65, and a USB2Mercury.
29 // Ensure that the Mercury servo is in position control mode prior to running this example.
30 //
31 
32 #if defined(__linux__) || defined(__APPLE__)
33 #include <fcntl.h>
34 #include <termios.h>
35 #include <unistd.h>
36 #define STDIN_FILENO 0
37 #elif defined(_WIN32) || defined(_WIN64)
38 #include <conio.h>
39 #endif
40 
41 #include <stdlib.h>
42 #include <stdio.h>
43 
44 #include "mercury_sdk/mercury_sdk.h" // Uses Mercury SDK library
45 
46 bool synchroniseMotor(mercury::PortHandler *portHandler, mercury::PacketHandler *packetHandler);
47 
48 #define ADDR_MCY_TORQUE_ENABLE 0x30 // Mercury Control table register addresses
49 #define ADDR_MCY_GOAL_POSITION 0x4e
50 #define ADDR_MCY_PRESENT_POSITION 0x56
51 #define ADDR_MCY_HARDWARE_STATUS 0x6b
52 
53 // Default setting
54 #define MCY_ID 1 // Mercury ID: 1
55 #define BAUDRATE 1000000
56 #define DEVICENAME "/dev/ttyACM1" // Check which port is being used on your controller
57  // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*"
58 
59 #define TORQUE_ENABLE 1 // Value for enabling the torque
60 #define TORQUE_DISABLE 0 // Value for disabling the torque
61 #define MCY_MINIMUM_POSITION_VALUE 100 // Mercury will rotate between this value
62 #define MCY_MAXIMUM_POSITION_VALUE 1000 // and this value (note that the Mercury would not move when the position value is out of movable range. Check e-manual about the range of the Mercury you use.)
63 #define MCY_MOVING_STATUS_THRESHOLD 2 // Mercury moving status threshold
64 
65 #define ESC_ASCII_VALUE 0x1b
66 
67 int getch()
68 {
69 #if defined(__linux__) || defined(__APPLE__)
70  struct termios oldt, newt;
71  int ch;
72  tcgetattr(STDIN_FILENO, &oldt);
73  newt = oldt;
74  newt.c_lflag &= ~(ICANON | ECHO);
75  tcsetattr(STDIN_FILENO, TCSANOW, &newt);
76  ch = getchar();
77  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
78  return ch;
79 #elif defined(_WIN32) || defined(_WIN64)
80  return _getch();
81 #endif
82 }
83 
84 int kbhit(void)
85 {
86 #if defined(__linux__) || defined(__APPLE__)
87  struct termios oldt, newt;
88  int ch;
89  int oldf;
90 
91  tcgetattr(STDIN_FILENO, &oldt);
92  newt = oldt;
93  newt.c_lflag &= ~(ICANON | ECHO);
94  tcsetattr(STDIN_FILENO, TCSANOW, &newt);
95  oldf = fcntl(STDIN_FILENO, F_GETFL, 0);
96  fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK);
97 
98  ch = getchar();
99 
100  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
101  fcntl(STDIN_FILENO, F_SETFL, oldf);
102 
103  if (ch != EOF)
104  {
105  ungetc(ch, stdin);
106  return 1;
107  }
108 
109  return 0;
110 #elif defined(_WIN32) || defined(_WIN64)
111  return _kbhit();
112 #endif
113 }
114 
115 int main()
116 {
117  // Initialize PortHandler instance
118  // Set the port path
119  // Get methods and members of PortHandlerLinux or PortHandlerWindows
121 
122  // Initialize PacketHandler instance
123  // Set the protocol version
124  // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler
126 
127  int index = 0;
128  int mcy_comm_result = COMM_TX_FAIL; // Communication result
129  int mcy_goal_position[2] = {MCY_MINIMUM_POSITION_VALUE, MCY_MAXIMUM_POSITION_VALUE}; // Goal position
130 
131  uint8_t mcy_error = 0; // Mercury error
132  uint32_t mcy_present_position = 0; // Present position
133 
134  // Open port
135  if (portHandler->openPort())
136  {
137  printf("Succeeded to open the port!\n");
138  }
139  else
140  {
141  printf("Failed to open the port!\n");
142  printf("Press any key to terminate...\n");
143  getch();
144  return 0;
145  }
146 
147  // Set port baudrate
148  if (portHandler->setBaudRate(BAUDRATE))
149  {
150  printf("Succeeded to change the baudrate!\n");
151  }
152  else
153  {
154  printf("Failed to change the baudrate!\n");
155  printf("Press any key to terminate...\n");
156  getch();
157  return 0;
158  }
159 
160  if (!synchroniseMotor(portHandler, packetHandler))
161  return 0;
162 
163  // Enable Mercury Torque
164  mcy_comm_result = packetHandler->write1ByteTxRx(portHandler, MCY_ID, ADDR_MCY_TORQUE_ENABLE, TORQUE_ENABLE, &mcy_error);
165  if (mcy_comm_result != COMM_SUCCESS)
166  {
167  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
168  }
169  else if (mcy_error != 0)
170  {
171  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
172  }
173  else
174  {
175  printf("Mercury has been successfully connected \n");
176  }
177 
178  while(1)
179  {
180  printf("Press any key to continue! (or press ESC to quit!)\n");
181  if (getch() == ESC_ASCII_VALUE)
182  break;
183 
184  // Write goal position
185  mcy_comm_result = packetHandler->write4ByteTxRx(portHandler, MCY_ID, ADDR_MCY_GOAL_POSITION, mcy_goal_position[index], &mcy_error);
186  if (mcy_comm_result != COMM_SUCCESS)
187  {
188  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
189  }
190  else if (mcy_error != 0)
191  {
192  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
193  }
194 
195  do
196  {
197  #if defined(__linux__)
198  usleep(10000);
199  #endif
200 
201  // Read present position
202  mcy_comm_result = packetHandler->read4ByteTxRx(portHandler, MCY_ID, ADDR_MCY_PRESENT_POSITION, &mcy_present_position, &mcy_error);
203  if (mcy_comm_result != COMM_SUCCESS)
204  {
205  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
206  }
207  else if (mcy_error != 0)
208  {
209  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
210  }
211 
212  printf("[ID:%03d] GoalPos:%03d PresPos:%03d\n", MCY_ID, mcy_goal_position[index], mcy_present_position);
213 
214  }while((labs(mcy_goal_position[index] - mcy_present_position) > MCY_MOVING_STATUS_THRESHOLD));
215 
216  // Change goal position
217  if (index == 0)
218  {
219  index = 1;
220  }
221  else
222  {
223  index = 0;
224  }
225  }
226 
227  // Disable Mercury Torque
228  mcy_comm_result = packetHandler->write1ByteTxRx(portHandler, MCY_ID, ADDR_MCY_TORQUE_ENABLE, TORQUE_DISABLE, &mcy_error);
229  if (mcy_comm_result != COMM_SUCCESS)
230  {
231  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
232  }
233  else if (mcy_error != 0)
234  {
235  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
236  }
237 
238  // Close port
239  portHandler->closePort();
240 
241  return 0;
242 }
243 
245 
246  // read the hardware status register to confirm
247  const uint8_t synchronise_enable = 0x02;
248  const uint8_t ADDR_MCY_HARDWARE_STATUS_L = 0x6b;
249 
250  uint8_t mcy_hardware_status = 0;
251  uint8_t mcy_error_l = 0; // Mercury error
252  int mcy_comm_result_l = COMM_TX_FAIL; // Communication result
253 
254  bool is_synchronising = false;
255  do {
256 
257  mcy_comm_result_l = packetHandler->read1ByteTxRx(portHandler, MCY_ID, ADDR_MCY_HARDWARE_STATUS_L, &mcy_hardware_status, &mcy_error_l);
258 
259  if (mcy_comm_result_l != COMM_SUCCESS)
260  {
261  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result_l));
262  return 0;
263  }
264  else if (mcy_error_l != 0)
265  {
266  printf("%s\n", packetHandler->getRxPacketError(mcy_error_l));
267  }
268  else {
269  if (mcy_hardware_status & 0x02) { // motor not synchronised
270  if (is_synchronising) {
271  printf("Mercury is synchronising... \n");
272 
273  #if defined(__linux__)
274  usleep(1000000);
275  #endif
276  continue;
277  }
278 
279  mcy_comm_result_l = packetHandler->write1ByteTxRx(portHandler, MCY_ID, ADDR_MCY_TORQUE_ENABLE, synchronise_enable, &mcy_error_l);
280  if (mcy_comm_result_l != COMM_SUCCESS)
281  {
282  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result_l));
283  return 0;
284  }
285  else if (mcy_error_l != 0)
286  {
287  printf("%s\n", packetHandler->getRxPacketError(mcy_error_l));
288  return 0;
289  }
290  else
291  {
292  printf("Mercury has been successfully connected \n");
293  is_synchronising = true;
294  }
295  }
296  }
297  } while (mcy_hardware_status & synchronise_enable);
298 
299  return 1;
300 }
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
virtual const char * getTxRxResult(int result)=0
The function that gets description of communication result.
virtual int write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0)=0
The function that calls PacketHandler::writeTxRx() for writing 1 byte data and receives the packet @d...
virtual const char * getRxPacketError(uint8_t error)=0
The function that gets description of hardware error.
virtual int read1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error=0)=0
The function that calls PacketHandler::readTxRx() function for reading 1 byte data @description The f...
virtual int read4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error=0)=0
The function that calls PacketHandler::readTxRx() function for reading 4 byte data @description The f...
virtual int write4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error=0)=0
The function that calls PacketHandler::writeTxRx() for writing 4 byte data and receives the packet @d...
static PacketHandler * getPacketHandler()
The function that returns PacketHandler instance.
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac,...
Definition: port_handler.h:56
static PortHandler * getPortHandler(const char *port_name)
The function that gets PortHandler class inheritance @description The function gets class inheritance...
virtual bool openPort()=0
The function that opens the port @description The function calls PortHandlerLinux::setBaudRate() to o...
virtual bool setBaudRate(const int baudrate)=0
The function that sets baudrate into the port handler @description The function sets baudrate into th...
virtual void closePort()=0
The function that closes the port @description The function closes the port.
#define COMM_SUCCESS
#define COMM_TX_FAIL
#define MCY_MAXIMUM_POSITION_VALUE
Definition: read_write.cpp:62
int getch()
Definition: read_write.cpp:67
#define MCY_MOVING_STATUS_THRESHOLD
Definition: read_write.cpp:63
bool synchroniseMotor(mercury::PortHandler *portHandler, mercury::PacketHandler *packetHandler)
Definition: read_write.cpp:244
#define ESC_ASCII_VALUE
Definition: read_write.cpp:65
#define BAUDRATE
Definition: read_write.cpp:55
#define TORQUE_ENABLE
Definition: read_write.cpp:59
int kbhit(void)
Definition: read_write.cpp:84
#define MCY_MINIMUM_POSITION_VALUE
Definition: read_write.cpp:61
#define MCY_ID
Definition: read_write.cpp:54
#define DEVICENAME
Definition: read_write.cpp:56
#define ADDR_MCY_TORQUE_ENABLE
Definition: read_write.cpp:48
#define ADDR_MCY_GOAL_POSITION
Definition: read_write.cpp:49
#define ADDR_MCY_PRESENT_POSITION
Definition: read_write.cpp:50
int main()
Definition: read_write.cpp:115
#define TORQUE_DISABLE
Definition: read_write.cpp:60