31 #if defined(__linux__) || defined(__APPLE__)
35 #define STDIN_FILENO 0
36 #elif defined(_WIN32) || defined(_WIN64)
45 #define ADDR_MX_TORQUE_ENABLE 0x30
46 #define ADDR_MX_GOAL_POSITION 0x4e
47 #define ADDR_MX_PRESENT_POSITION 0x56
51 #define BAUDRATE 1000000
52 #define DEVICENAME "/dev/ttyACM0"
55 #define TORQUE_ENABLE 1
56 #define TORQUE_DISABLE 0
57 #define MCY_POSITION_VALUE 0x02cd
59 #define ESC_ASCII_VALUE 0x1b
63 #if defined(__linux__)
64 struct termios oldt, newt;
66 tcgetattr(STDIN_FILENO, &oldt);
68 newt.c_lflag &= ~(ICANON | ECHO);
69 tcsetattr(STDIN_FILENO, TCSANOW, &newt);
71 tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
80 #if defined(__linux__)
81 struct termios oldt, newt;
85 tcgetattr(STDIN_FILENO, &oldt);
87 newt.c_lflag &= ~(ICANON | ECHO);
88 tcsetattr(STDIN_FILENO, TCSANOW, &newt);
89 oldf = fcntl(STDIN_FILENO, F_GETFL, 0);
90 fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK);
94 tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
95 fcntl(STDIN_FILENO, F_SETFL, oldf);
104 #elif defined(_WIN32) || defined(_WIN64)
124 uint8_t mcy_error = 0;
129 printf(
"Succeeded to open the port!\n");
133 printf(
"Failed to open the port!\n");
134 printf(
"Press any key to terminate...\n");
142 printf(
"Succeeded to change the baudrate!\n");
146 printf(
"Failed to change the baudrate!\n");
147 printf(
"Press any key to terminate...\n");
156 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
158 else if (mcy_error != 0)
164 printf(
"Mercury has been successfully connected \n");
170 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
172 else if (mcy_error != 0)
181 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
183 else if (mcy_error != 0)
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 regWriteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)=0
The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Mercur...
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.
#define ADDR_MX_GOAL_POSITION
#define ADDR_MX_TORQUE_ENABLE
#define MCY_POSITION_VALUE