31 #if defined(__linux__) || defined(__APPLE__)
35 #define STDIN_FILENO 0
36 #elif defined(_WIN32) || defined(_WIN64)
45 #define ADDR_MX_TORQUE_ENABLE 0x30
49 #define BAUDRATE 1000000
50 #define DEVICENAME "/dev/ttyACM0"
53 #define TORQUE_ENABLE 1
54 #define TORQUE_DISABLE 0
56 #define ESC_ASCII_VALUE 0x1b
60 #if defined(__linux__)
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);
77 #if defined(__linux__)
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)
120 uint8_t mcy_error = 0;
125 printf(
"Succeeded to open the port!\n");
129 printf(
"Failed to open the port!\n");
130 printf(
"Press any key to terminate...\n");
138 printf(
"Succeeded to change the baudrate!\n");
142 printf(
"Failed to change the baudrate!\n");
143 printf(
"Press any key to terminate...\n");
152 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
154 else if (mcy_error != 0)
160 printf(
"Mercury has been successfully connected \n");
163 mcy_comm_result = packetHandler->
action(portHandler,
MCY_ID);
166 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
168 else if (mcy_error != 0)
#define ADDR_MX_TORQUE_ENABLE
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 int action(PortHandler *port, uint8_t id)=0
The function that makes Mercurys run as written in the Mercury register @description The function mak...
virtual const char * getRxPacketError(uint8_t error)=0
The function that gets description of hardware error.
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 void closePort()=0
The function that closes the port @description The function closes the port.