32 #if defined(__linux__) || defined(__APPLE__)
36 #define STDIN_FILENO 0
37 #elif defined(_WIN32) || defined(_WIN64)
48 #define ADDR_MCY_TORQUE_ENABLE 0x30
49 #define ADDR_MCY_GOAL_POSITION 0x4e
50 #define ADDR_MCY_PRESENT_POSITION 0x56
51 #define ADDR_MCY_HARDWARE_STATUS 0x6b
55 #define BAUDRATE 1000000
56 #define DEVICENAME "/dev/ttyACM1"
59 #define TORQUE_ENABLE 1
60 #define TORQUE_DISABLE 0
61 #define MCY_MINIMUM_POSITION_VALUE 100
62 #define MCY_MAXIMUM_POSITION_VALUE 1000
63 #define MCY_MOVING_STATUS_THRESHOLD 2
65 #define ESC_ASCII_VALUE 0x1b
69 #if defined(__linux__) || defined(__APPLE__)
70 struct termios oldt, newt;
72 tcgetattr(STDIN_FILENO, &oldt);
74 newt.c_lflag &= ~(ICANON | ECHO);
75 tcsetattr(STDIN_FILENO, TCSANOW, &newt);
77 tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
79 #elif defined(_WIN32) || defined(_WIN64)
86 #if defined(__linux__) || defined(__APPLE__)
87 struct termios oldt, newt;
91 tcgetattr(STDIN_FILENO, &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);
100 tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
101 fcntl(STDIN_FILENO, F_SETFL, oldf);
110 #elif defined(_WIN32) || defined(_WIN64)
131 uint8_t mcy_error = 0;
132 uint32_t mcy_present_position = 0;
137 printf(
"Succeeded to open the port!\n");
141 printf(
"Failed to open the port!\n");
142 printf(
"Press any key to terminate...\n");
150 printf(
"Succeeded to change the baudrate!\n");
154 printf(
"Failed to change the baudrate!\n");
155 printf(
"Press any key to terminate...\n");
167 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
169 else if (mcy_error != 0)
175 printf(
"Mercury has been successfully connected \n");
180 printf(
"Press any key to continue! (or press ESC to quit!)\n");
188 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
190 else if (mcy_error != 0)
197 #if defined(__linux__)
205 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
207 else if (mcy_error != 0)
212 printf(
"[ID:%03d] GoalPos:%03d PresPos:%03d\n",
MCY_ID, mcy_goal_position[index], mcy_present_position);
231 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
233 else if (mcy_error != 0)
247 const uint8_t synchronise_enable = 0x02;
248 const uint8_t ADDR_MCY_HARDWARE_STATUS_L = 0x6b;
250 uint8_t mcy_hardware_status = 0;
251 uint8_t mcy_error_l = 0;
254 bool is_synchronising =
false;
257 mcy_comm_result_l = packetHandler->
read1ByteTxRx(portHandler,
MCY_ID, ADDR_MCY_HARDWARE_STATUS_L, &mcy_hardware_status, &mcy_error_l);
261 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result_l));
264 else if (mcy_error_l != 0)
269 if (mcy_hardware_status & 0x02) {
270 if (is_synchronising) {
271 printf(
"Mercury is synchronising... \n");
273 #if defined(__linux__)
282 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result_l));
285 else if (mcy_error_l != 0)
292 printf(
"Mercury has been successfully connected \n");
293 is_synchronising =
true;
297 }
while (mcy_hardware_status & synchronise_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 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,...
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 MCY_MAXIMUM_POSITION_VALUE
#define MCY_MOVING_STATUS_THRESHOLD
bool synchroniseMotor(mercury::PortHandler *portHandler, mercury::PacketHandler *packetHandler)
#define MCY_MINIMUM_POSITION_VALUE
#define ADDR_MCY_TORQUE_ENABLE
#define ADDR_MCY_GOAL_POSITION
#define ADDR_MCY_PRESENT_POSITION