MercurySDK
Software development kit for Mercury digital servos
action.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 // ********* Action Example *********
27 //
28 // This example is tested with a Mercury M65, and a USB2Mercury
29 //
30 
31 #if defined(__linux__) || defined(__APPLE__)
32 #include <fcntl.h>
33 #include <termios.h>
34 #include <unistd.h>
35 #define STDIN_FILENO 0
36 #elif defined(_WIN32) || defined(_WIN64)
37 #include <conio.h>
38 #endif
39 
40 #include <stdlib.h>
41 #include <stdio.h>
42 
43 #include "mercury_sdk.h" // Uses Mercury SDK library
44 
45 #define ADDR_MX_TORQUE_ENABLE 0x30 // Mercury Control table register addresses
46 
47 // Default setting
48 #define MCY_ID 1 // Mercury ID: 1
49 #define BAUDRATE 1000000
50 #define DEVICENAME "/dev/ttyACM0" // Check which port is being used on your controller
51  // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*"
52 
53 #define TORQUE_ENABLE 1 // Value for enabling the torque
54 #define TORQUE_DISABLE 0 // Value for disabling the torque
55 
56 #define ESC_ASCII_VALUE 0x1b
57 
58 int getch()
59 {
60 #if defined(__linux__)
61  struct termios oldt, newt;
62  int ch;
63  tcgetattr(STDIN_FILENO, &oldt);
64  newt = oldt;
65  newt.c_lflag &= ~(ICANON | ECHO);
66  tcsetattr(STDIN_FILENO, TCSANOW, &newt);
67  ch = getchar();
68  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
69  return ch;
70 #elif defined(_WIN64)
71  return _getch();
72 #endif
73 }
74 
75 int kbhit(void)
76 {
77 #if defined(__linux__)
78  struct termios oldt, newt;
79  int ch;
80  int oldf;
81 
82  tcgetattr(STDIN_FILENO, &oldt);
83  newt = 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);
88 
89  ch = getchar();
90 
91  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
92  fcntl(STDIN_FILENO, F_SETFL, oldf);
93 
94  if (ch != EOF)
95  {
96  ungetc(ch, stdin);
97  return 1;
98  }
99 
100  return 0;
101 #elif defined(_WIN32) || defined(_WIN64)
102  return _kbhit();
103 #endif
104 }
105 
106 int main()
107 {
108  // Initialize PortHandler instance
109  // Set the port path
110  // Get methods and members of PortHandlerLinux or PortHandlerWindows
112 
113  // Initialize PacketHandler instance
114  // Set the protocol version
115  // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler
117 
118  int mcy_comm_result = COMM_TX_FAIL; // Communication result
119 
120  uint8_t mcy_error = 0; // Mercury error
121 
122  // Open port
123  if (portHandler->openPort())
124  {
125  printf("Succeeded to open the port!\n");
126  }
127  else
128  {
129  printf("Failed to open the port!\n");
130  printf("Press any key to terminate...\n");
131  getch();
132  return 0;
133  }
134 
135  // Set port baudrate
136  if (portHandler->setBaudRate(BAUDRATE))
137  {
138  printf("Succeeded to change the baudrate!\n");
139  }
140  else
141  {
142  printf("Failed to change the baudrate!\n");
143  printf("Press any key to terminate...\n");
144  getch();
145  return 0;
146  }
147 
148  // Enable Mercury Torque
149  mcy_comm_result = packetHandler->write1ByteTxRx(portHandler, MCY_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &mcy_error);
150  if (mcy_comm_result != COMM_SUCCESS)
151  {
152  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
153  }
154  else if (mcy_error != 0)
155  {
156  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
157  }
158  else
159  {
160  printf("Mercury has been successfully connected \n");
161  }
162 
163  mcy_comm_result = packetHandler->action(portHandler, MCY_ID);
164  if (mcy_comm_result != COMM_SUCCESS)
165  {
166  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
167  }
168  else if (mcy_error != 0)
169  {
170  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
171  }
172 
173  // Close port
174  portHandler->closePort();
175 
176  return 0;
177 }
int getch()
Definition: action.cpp:58
#define BAUDRATE
Definition: action.cpp:49
#define TORQUE_ENABLE
Definition: action.cpp:53
int kbhit(void)
Definition: action.cpp:75
#define MCY_ID
Definition: action.cpp:48
#define DEVICENAME
Definition: action.cpp:50
#define ADDR_MX_TORQUE_ENABLE
Definition: action.cpp:45
int main()
Definition: action.cpp:106
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,...
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