31 #if defined(__linux__) || defined(__APPLE__)
35 #define STDIN_FILENO 0
36 #elif defined(_WIN32) || defined(_WIN64)
44 #define ADDR_PRO_BAUDRATE 4
48 #define BAUDRATE 1000000
49 #define DEVICENAME "/dev/ttyACM0"
52 #define FACTORYRST_DEFAULTBAUDRATE 1000000
54 #define OPERATION_MODE 0x01
60 #if defined(__linux__) || defined(__APPLE__)
61 struct termios oldt, newt;
63 tcgetattr(STDIN_FILENO, &oldt);
65 newt.c_lflag &= ~(ICANON | ECHO);
66 tcsetattr(STDIN_FILENO, TCSANOW, &newt);
68 tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
70 #elif defined(_WIN32) || defined(_WIN64)
77 #if defined(__linux__) || defined(__APPLE__)
78 struct termios oldt, newt;
82 tcgetattr(STDIN_FILENO, &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);
91 tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
92 fcntl(STDIN_FILENO, F_SETFL, oldf);
101 #elif defined(_WIN32) || defined(_WIN64)
108 #if defined(__linux__) || defined(__APPLE__)
109 usleep(waitTime * 1000);
110 #elif defined(_WIN32) || defined(_WIN64)
129 uint8_t mcy_error = 0;
130 uint8_t mcy_baudnum_read;
135 printf(
"Succeeded to open the port!\n");
139 printf(
"Failed to open the port!\n");
140 printf(
"Press any key to terminate...\n");
148 printf(
"Succeeded to change the baudrate!\n");
152 printf(
"Failed to change the baudrate!\n");
153 printf(
"Press any key to terminate...\n");
159 printf(
"Now the controller baudrate is : %d\n", portHandler->
getBaudRate());
162 printf(
"[ID:%03d] Try factoryreset : ",
MCY_ID);
167 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
170 else if (mcy_error != 0)
176 printf(
"Wait for reset...\n");
179 printf(
"[ID:%03d] factoryReset Success!\n",
MCY_ID);
188 printf(
"Failed to change the controller baudrate\n");
189 printf(
"Press any key to terminate...\n");
198 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
200 else if (mcy_error != 0)
206 printf(
"[ID:%03d] DXL baudnum is now : %d\n",
MCY_ID, mcy_baudnum_read);
213 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
215 else if (mcy_error != 0)
227 printf(
"Succeed to change the controller baudrate to : %d\n",
BAUDRATE);
231 printf(
"Failed to change the controller baudrate\n");
232 printf(
"Press any key to terminate...\n");
243 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
245 else if (mcy_error != 0)
251 printf(
"[ID:%03d] Mercury Baudnum is now : %d\n",
MCY_ID, mcy_baudnum_read);
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,...
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.
void msecSleep(int waitTime)
#define ADDR_PRO_BAUDRATE
#define FACTORYRST_DEFAULTBAUDRATE