MercurySDK
Software development kit for Mercury digital servos
ping.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright (C) 2021 <Robot Articulation/code@robotarticulation.com>
3 *
4 * Source files modified to support the Mercury range of digital servo motors from Robot Articulation
5 *******************************************************************************/
6 
7 /*******************************************************************************
8 * Copyright 2017 ROBOTIS CO., LTD.
9 *
10 * Licensed under the Apache License, Version 2.0 (the "License");
11 * you may not use this file except in compliance with the License.
12 * You may obtain a copy of the License at
13 *
14 * http://www.apache.org/licenses/LICENSE-2.0
15 *
16 * Unless required by applicable law or agreed to in writing, software
17 * distributed under the License is distributed on an "AS IS" BASIS,
18 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
19 * See the License for the specific language governing permissions and
20 * limitations under the License.
21 *******************************************************************************/
22 
23 /* Original author: Zerom, Leon (RyuWoon Jung) */
24 
25 //
26 // ********* ping Example *********
27 //
28 // This example is tested with a Mercury M1, and a USB2Mercury
29 //
30 
31 #if defined(__linux__) || defined(__APPLE__)
32 #include <fcntl.h>
33 #include <termios.h>
34 #define STDIN_FILENO 0
35 #elif defined(_WIN32) || defined(_WIN64)
36 #include <conio.h>
37 #endif
38 
39 #include <vector>
40 #include <algorithm>
41 
42 #include <stdio.h>
43 #include "mercury_sdk.h" // Uses Mercury SDK library
44 
45 // Default setting
46 #define MCY_ID 1 // Mercury ID: 1
47 #define BAUDRATE 1000000
48 #define DEVICENAME "/dev/ttyACM0" // Check which port is being used on your controller
49  // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*"
50 //#define USE_BROADCAST_PING
51 
52 int getch()
53 {
54 #if defined(__linux__) || defined(__APPLE__)
55  struct termios oldt, newt;
56  int ch;
57  tcgetattr(STDIN_FILENO, &oldt);
58  newt = oldt;
59  newt.c_lflag &= ~(ICANON | ECHO);
60  tcsetattr(STDIN_FILENO, TCSANOW, &newt);
61  ch = getchar();
62  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
63  return ch;
64 #elif defined(_WIN32) || defined(_WIN64)
65  return _getch();
66 #endif
67 }
68 
69 int kbhit(void)
70 {
71 #if defined(__linux__) || defined(__APPLE__)
72  struct termios oldt, newt;
73  int ch;
74  int oldf;
75 
76  tcgetattr(STDIN_FILENO, &oldt);
77  newt = 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);
82 
83  ch = getchar();
84 
85  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
86  fcntl(STDIN_FILENO, F_SETFL, oldf);
87 
88  if (ch != EOF)
89  {
90  ungetc(ch, stdin);
91  return 1;
92  }
93 
94  return 0;
95 #elif defined(_WIN32) || defined(_WIN64)
96  return _kbhit();
97 #endif
98 }
99 
100 int main()
101 {
102  // Initialize PortHandler instance
103  // Set the port path
104  // Get methods and members of PortHandlerLinux or PortHandlerWindows
106 
107  // Initialize PacketHandler instance
108  // Set the protocol version
109  // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler
111 
112  int mcy_comm_result = COMM_TX_FAIL; // Communication result
113 
114  uint8_t mcy_error = 0; // Mercury error
115  uint16_t mcy_model_number; // Mercury model number
116 
117  // Open port
118  if (portHandler->openPort())
119  {
120  printf("Succeeded to open the port!\n");
121  }
122  else
123  {
124  printf("Failed to open the port!\n");
125  printf("Press any key to terminate...\n");
126  getch();
127  return 0;
128  }
129 
130  // Set port baudrate
131  if (portHandler->setBaudRate(BAUDRATE))
132  {
133  printf("Succeeded to change the baudrate!\n");
134  }
135  else
136  {
137  printf("Failed to change the baudrate!\n");
138  printf("Press any key to terminate...\n");
139  getch();
140  return 0;
141  }
142 
143 #ifdef USE_BROADCAST_PING
144 
145  std::vector<uint8_t> id_list {};
146  mcy_comm_result = packetHandler->broadcastPing(portHandler, id_list);
147  if (mcy_comm_result != COMM_SUCCESS)
148  {
149  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
150  }
151  else
152  {
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);
155  });
156  }
157 
158  return 0;
159 
160 #endif
161 
162  // Try to ping the Mercury
163  // Get Mercury model number
164  mcy_comm_result = packetHandler->ping(portHandler, MCY_ID, &mcy_model_number, &mcy_error);
165  if (mcy_comm_result != COMM_SUCCESS)
166  {
167  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
168  }
169  else if (mcy_error != 0)
170  {
171  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
172  }
173  else
174  {
175  printf("[ID:%03d] ping Succeeded. Mercury model number : %d\n", MCY_ID, mcy_model_number);
176  }
177 
178  // Close port
179  portHandler->closePort();
180 
181  return 0;
182 }
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,...
Definition: port_handler.h:56
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 COMM_SUCCESS
#define COMM_TX_FAIL
int getch()
Definition: ping.cpp:52
#define BAUDRATE
Definition: ping.cpp:47
int kbhit(void)
Definition: ping.cpp:69
#define MCY_ID
Definition: ping.cpp:46
#define DEVICENAME
Definition: ping.cpp:48
int main()
Definition: ping.cpp:100