MercurySDK
Software development kit for Mercury digital servos
factory_reset.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 // ********* Factory Reset Example *********
27 //
28 // This example was tested with a Mercury M65, and a USB2Mercury
29 //
30 
31 #if defined(__linux__) || defined(__APPLE__)
32 #include <fcntl.h>
33 #include <termios.h>
34 #include <unistd.h>
35 #define STDIN_FILENO 0
36 #elif defined(_WIN32) || defined(_WIN64)
37 #include <conio.h>
38 #endif
39 #include <stdio.h>
40 
41 #include "mercury_sdk.h" // Uses Mercury SDK library
42 
43 // Control table address
44 #define ADDR_PRO_BAUDRATE 4 // Control table address is different in Mercury model
45 
46 // Default setting
47 #define MCY_ID 1 // Mercury ID: 1
48 #define BAUDRATE 1000000
49 #define DEVICENAME "/dev/ttyACM0" // Check which port is being used on your controller
50  // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*"
51 
52 #define FACTORYRST_DEFAULTBAUDRATE 1000000 // Mercury baudrate set by factoryreset
53 #define NEW_BAUDNUM 3 // New baudnum to recover Mercury baudrate as it was
54 #define OPERATION_MODE 0x01 // 0xFF : reset all values
55  // 0x01 : reset all values except ID
56  // 0x02 : reset all values except ID and baudrate
57 
58 int getch()
59 {
60 #if defined(__linux__) || defined(__APPLE__)
61  struct termios oldt, newt;
62  int ch;
63  tcgetattr(STDIN_FILENO, &oldt);
64  newt = oldt;
65  newt.c_lflag &= ~(ICANON | ECHO);
66  tcsetattr(STDIN_FILENO, TCSANOW, &newt);
67  ch = getchar();
68  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
69  return ch;
70 #elif defined(_WIN32) || defined(_WIN64)
71  return _getch();
72 #endif
73 }
74 
75 int kbhit(void)
76 {
77 #if defined(__linux__) || defined(__APPLE__)
78  struct termios oldt, newt;
79  int ch;
80  int oldf;
81 
82  tcgetattr(STDIN_FILENO, &oldt);
83  newt = oldt;
84  newt.c_lflag &= ~(ICANON | ECHO);
85  tcsetattr(STDIN_FILENO, TCSANOW, &newt);
86  oldf = fcntl(STDIN_FILENO, F_GETFL, 0);
87  fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK);
88 
89  ch = getchar();
90 
91  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
92  fcntl(STDIN_FILENO, F_SETFL, oldf);
93 
94  if (ch != EOF)
95  {
96  ungetc(ch, stdin);
97  return 1;
98  }
99 
100  return 0;
101 #elif defined(_WIN32) || defined(_WIN64)
102  return _kbhit();
103 #endif
104 }
105 
106 void msecSleep(int waitTime)
107 {
108 #if defined(__linux__) || defined(__APPLE__)
109  usleep(waitTime * 1000);
110 #elif defined(_WIN32) || defined(_WIN64)
111  _sleep(waitTime);
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 mcy_comm_result = COMM_TX_FAIL; // Communication result
128 
129  uint8_t mcy_error = 0; // Mercury error
130  uint8_t mcy_baudnum_read; // Read baudnum
131 
132  // Open port
133  if (portHandler->openPort())
134  {
135  printf("Succeeded to open the port!\n");
136  }
137  else
138  {
139  printf("Failed to open the port!\n");
140  printf("Press any key to terminate...\n");
141  getch();
142  return 0;
143  }
144 
145  // Set port baudrate
146  if (portHandler->setBaudRate(BAUDRATE))
147  {
148  printf("Succeeded to change the baudrate!\n");
149  }
150  else
151  {
152  printf("Failed to change the baudrate!\n");
153  printf("Press any key to terminate...\n");
154  getch();
155  return 0;
156  }
157 
158  // Read present baudrate of the controller
159  printf("Now the controller baudrate is : %d\n", portHandler->getBaudRate());
160 
161  // Try factoryreset
162  printf("[ID:%03d] Try factoryreset : ", MCY_ID);
163  mcy_comm_result = packetHandler->factoryReset(portHandler, MCY_ID, OPERATION_MODE, &mcy_error);
164  if (mcy_comm_result != COMM_SUCCESS)
165  {
166  printf("Aborted\n");
167  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
168  return 0;
169  }
170  else if (mcy_error != 0)
171  {
172  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
173  }
174 
175  // Wait for reset
176  printf("Wait for reset...\n");
177  msecSleep(2000);
178 
179  printf("[ID:%03d] factoryReset Success!\n", MCY_ID);
180 
181  // Set controller baudrate to Mercury default baudrate
182  if (portHandler->setBaudRate(FACTORYRST_DEFAULTBAUDRATE))
183  {
184  printf("Succeed to change the controller baudrate to : %d\n", FACTORYRST_DEFAULTBAUDRATE);
185  }
186  else
187  {
188  printf("Failed to change the controller baudrate\n");
189  printf("Press any key to terminate...\n");
190  getch();
191  return 0;
192  }
193 
194  // Read Mercury baudnum
195  mcy_comm_result = packetHandler->read1ByteTxRx(portHandler, MCY_ID, ADDR_PRO_BAUDRATE, &mcy_baudnum_read, &mcy_error);
196  if (mcy_comm_result != COMM_SUCCESS)
197  {
198  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
199  }
200  else if (mcy_error != 0)
201  {
202  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
203  }
204  else
205  {
206  printf("[ID:%03d] DXL baudnum is now : %d\n", MCY_ID, mcy_baudnum_read);
207  }
208 
209  // Write new baudnum
210  mcy_comm_result = packetHandler->write1ByteTxRx(portHandler, MCY_ID, ADDR_PRO_BAUDRATE, NEW_BAUDNUM, &mcy_error);
211  if (mcy_comm_result != COMM_SUCCESS)
212  {
213  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
214  }
215  else if (mcy_error != 0)
216  {
217  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
218  }
219  else
220  {
221  printf("[ID:%03d] Set Mercury baudnum to : %d\n", MCY_ID, NEW_BAUDNUM);
222  }
223 
224  // Set port baudrate to BAUDRATE
225  if (portHandler->setBaudRate(BAUDRATE))
226  {
227  printf("Succeed to change the controller baudrate to : %d\n", BAUDRATE);
228  }
229  else
230  {
231  printf("Failed to change the controller baudrate\n");
232  printf("Press any key to terminate...\n");
233  getch();
234  return 0;
235  }
236 
237  msecSleep(200);
238 
239  // Read Mercury baudnum
240  mcy_comm_result = packetHandler->read1ByteTxRx(portHandler, MCY_ID, ADDR_PRO_BAUDRATE, &mcy_baudnum_read, &mcy_error);
241  if (mcy_comm_result != COMM_SUCCESS)
242  {
243  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
244  }
245  else if (mcy_error != 0)
246  {
247  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
248  }
249  else
250  {
251  printf("[ID:%03d] Mercury Baudnum is now : %d\n", MCY_ID, mcy_baudnum_read);
252  }
253 
254  // Close port
255  portHandler->closePort();
256 
257  return 0;
258 }
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
virtual int factoryReset(PortHandler *port, uint8_t id, uint8_t option=0, uint8_t *error=0)=0
The function that makes Mercury reset as it was produced in the factory @description The function mak...
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...
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 int getBaudRate()=0
The function that returns current baudrate set into the port handler @description The function return...
virtual void closePort()=0
The function that closes the port @description The function closes the port.
int getch()
void msecSleep(int waitTime)
#define ADDR_PRO_BAUDRATE
#define FACTORYRST_DEFAULTBAUDRATE
#define BAUDRATE
int kbhit(void)
#define MCY_ID
#define OPERATION_MODE
#define DEVICENAME
#define NEW_BAUDNUM
int main()
#define COMM_SUCCESS
#define COMM_TX_FAIL