MercurySDK
Software development kit for Mercury digital servos
reg_write.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 // ********* Reg Write 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 #define ADDR_MX_GOAL_POSITION 0x4e
47 #define ADDR_MX_PRESENT_POSITION 0x56
48 
49 // Default setting
50 #define MCY_ID 1 // Mercury ID: 1
51 #define BAUDRATE 1000000
52 #define DEVICENAME "/dev/ttyACM0" // Check which port is being used on your controller
53  // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*"
54 
55 #define TORQUE_ENABLE 1 // Value for enabling the torque
56 #define TORQUE_DISABLE 0 // Value for disabling the torque
57 #define MCY_POSITION_VALUE 0x02cd // Mercury will rotate between this value
58 
59 #define ESC_ASCII_VALUE 0x1b
60 
61 int getch()
62 {
63 #if defined(__linux__)
64  struct termios oldt, newt;
65  int ch;
66  tcgetattr(STDIN_FILENO, &oldt);
67  newt = oldt;
68  newt.c_lflag &= ~(ICANON | ECHO);
69  tcsetattr(STDIN_FILENO, TCSANOW, &newt);
70  ch = getchar();
71  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
72  return ch;
73 #elif defined(_WIN64)
74  return _getch();
75 #endif
76 }
77 
78 int kbhit(void)
79 {
80 #if defined(__linux__)
81  struct termios oldt, newt;
82  int ch;
83  int oldf;
84 
85  tcgetattr(STDIN_FILENO, &oldt);
86  newt = 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);
91 
92  ch = getchar();
93 
94  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
95  fcntl(STDIN_FILENO, F_SETFL, oldf);
96 
97  if (ch != EOF)
98  {
99  ungetc(ch, stdin);
100  return 1;
101  }
102 
103  return 0;
104 #elif defined(_WIN32) || defined(_WIN64)
105  return _kbhit();
106 #endif
107 }
108 
109 int main()
110 {
111  // Initialize PortHandler instance
112  // Set the port path
113  // Get methods and members of PortHandlerLinux or PortHandlerWindows
115 
116  // Initialize PacketHandler instance
117  // Set the protocol version
118  // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler
120 
121  int mcy_comm_result = COMM_TX_FAIL; // Communication result
122  int mcy_goal_position = MCY_POSITION_VALUE; // Goal position
123 
124  uint8_t mcy_error = 0; // Mercury error
125 
126  // Open port
127  if (portHandler->openPort())
128  {
129  printf("Succeeded to open the port!\n");
130  }
131  else
132  {
133  printf("Failed to open the port!\n");
134  printf("Press any key to terminate...\n");
135  getch();
136  return 0;
137  }
138 
139  // Set port baudrate
140  if (portHandler->setBaudRate(BAUDRATE))
141  {
142  printf("Succeeded to change the baudrate!\n");
143  }
144  else
145  {
146  printf("Failed to change the baudrate!\n");
147  printf("Press any key to terminate...\n");
148  getch();
149  return 0;
150  }
151 
152  // Enable Mercury Torque
153  mcy_comm_result = packetHandler->write1ByteTxRx(portHandler, MCY_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &mcy_error);
154  if (mcy_comm_result != COMM_SUCCESS)
155  {
156  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
157  }
158  else if (mcy_error != 0)
159  {
160  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
161  }
162  else
163  {
164  printf("Mercury has been successfully connected \n");
165  }
166 
167  mcy_comm_result = packetHandler->regWriteTxRx(portHandler, MCY_ID, ADDR_MX_GOAL_POSITION, 4, (uint8_t*)&mcy_goal_position, &mcy_error);
168  if (mcy_comm_result != COMM_SUCCESS)
169  {
170  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
171  }
172  else if (mcy_error != 0)
173  {
174  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
175  }
176 
177  //Disable Mercury Torque
178  mcy_comm_result = packetHandler->write1ByteTxRx(portHandler, MCY_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE, &mcy_error);
179  if (mcy_comm_result != COMM_SUCCESS)
180  {
181  printf("%s\n", packetHandler->getTxRxResult(mcy_comm_result));
182  }
183  else if (mcy_error != 0)
184  {
185  printf("%s\n", packetHandler->getRxPacketError(mcy_error));
186  }
187 
188  // Close port
189  portHandler->closePort();
190 
191  return 0;
192 }
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,...
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: reg_write.cpp:61
#define ADDR_MX_GOAL_POSITION
Definition: reg_write.cpp:46
#define BAUDRATE
Definition: reg_write.cpp:51
#define TORQUE_ENABLE
Definition: reg_write.cpp:55
int kbhit(void)
Definition: reg_write.cpp:78
#define MCY_ID
Definition: reg_write.cpp:50
#define DEVICENAME
Definition: reg_write.cpp:52
#define ADDR_MX_TORQUE_ENABLE
Definition: reg_write.cpp:45
int main()
Definition: reg_write.cpp:109
#define MCY_POSITION_VALUE
Definition: reg_write.cpp:57
#define TORQUE_DISABLE
Definition: reg_write.cpp:56