31 #if defined(__linux__) || defined(__APPLE__)
34 #define STDIN_FILENO 0
35 #elif defined(_WIN32) || defined(_WIN64)
47 #define BAUDRATE 1000000
48 #define DEVICENAME "/dev/ttyACM0"
54 #if defined(__linux__) || defined(__APPLE__)
55 struct termios oldt, newt;
57 tcgetattr(STDIN_FILENO, &oldt);
59 newt.c_lflag &= ~(ICANON | ECHO);
60 tcsetattr(STDIN_FILENO, TCSANOW, &newt);
62 tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
64 #elif defined(_WIN32) || defined(_WIN64)
71 #if defined(__linux__) || defined(__APPLE__)
72 struct termios oldt, newt;
76 tcgetattr(STDIN_FILENO, &oldt);
78 newt.c_lflag &= ~(ICANON | ECHO);
79 tcsetattr(STDIN_FILENO, TCSANOW, &newt);
80 oldf = fcntl(STDIN_FILENO, F_GETFL, 0);
81 fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK);
85 tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
86 fcntl(STDIN_FILENO, F_SETFL, oldf);
95 #elif defined(_WIN32) || defined(_WIN64)
114 uint8_t mcy_error = 0;
115 uint16_t mcy_model_number;
120 printf(
"Succeeded to open the port!\n");
124 printf(
"Failed to open the port!\n");
125 printf(
"Press any key to terminate...\n");
133 printf(
"Succeeded to change the baudrate!\n");
137 printf(
"Failed to change the baudrate!\n");
138 printf(
"Press any key to terminate...\n");
143 #ifdef USE_BROADCAST_PING
145 std::vector<uint8_t> id_list {};
146 mcy_comm_result = packetHandler->
broadcastPing(portHandler, id_list);
149 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
153 std::for_each(id_list.begin(), id_list.end(), [](uint8_t
id) {
154 printf(
"[ID:%03d] ping Succeeded. Mercury model number : %hhu\n", id);
164 mcy_comm_result = packetHandler->
ping(portHandler,
MCY_ID, &mcy_model_number, &mcy_error);
167 printf(
"%s\n", packetHandler->
getTxRxResult(mcy_comm_result));
169 else if (mcy_error != 0)
175 printf(
"[ID:%03d] ping Succeeded. Mercury model number : %d\n",
MCY_ID, mcy_model_number);
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 const char * getRxPacketError(uint8_t error)=0
The function that gets description of hardware error.
virtual int ping(PortHandler *port, uint8_t id, uint8_t *error=0)=0
The function that pings Mercury but doesn't take its model number @description The function calls Pac...
virtual int broadcastPing(PortHandler *port, std::vector< uint8_t > &id_list)=0
(Available only in Protocol 2.0) The function that pings all connected Mercury
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.