1+ /*******************************************************************************
2+ * Copyright 2017 ROBOTIS CO., LTD.
3+ *
4+ * Licensed under the Apache License, Version 2.0 (the "License");
5+ * you may not use this file except in compliance with the License.
6+ * You may obtain a copy of the License at
7+ *
8+ * http://www.apache.org/licenses/LICENSE-2.0
9+ *
10+ * Unless required by applicable law or agreed to in writing, software
11+ * distributed under the License is distributed on an "AS IS" BASIS,
12+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+ * See the License for the specific language governing permissions and
14+ * limitations under the License.
15+ *******************************************************************************/
16+
17+ /* Author: Ki Jong Gil (Gilbert) */
18+
19+ //
20+ // ********* Clear Multi-Turn Example *********
21+ //
22+ //
23+ // Available Dynamixel model on this example : Dynamixel X-series (firmware v42 or above)
24+ // This example is designed for using a Dynamixel XM430-W350-R, and an U2D2.
25+ // To use another Dynamixel model, such as MX series, see their details in E-Manual(emanual.robotis.com) and edit below "#define"d variables yourself.
26+ // Be sure that Dynamixel properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600)
27+ //
28+
29+ using System ;
30+ using System . Runtime . InteropServices ;
31+ using dynamixel_sdk ;
32+
33+ namespace clear_multi_turn
34+ {
35+ class ClearMultiTurn
36+ {
37+ // Control table address
38+ public const int ADDR_OPERATING_MODE = 11 ; // Control table address is different in Dynamixel model
39+ public const int ADDR_TORQUE_ENABLE = 64 ;
40+ public const int ADDR_GOAL_POSITION = 116 ;
41+ public const int ADDR_PRESENT_POSITION = 132 ;
42+
43+ // Protocol version
44+ public const int PROTOCOL_VERSION = 2 ; // See which protocol version is used in the Dynamixel
45+
46+ // Default setting
47+ public const int DXL_ID = 1 ; // Dynamixel ID: 1
48+ public const int BAUDRATE = 57600 ;
49+ public const string DEVICENAME = "COM1" ; // Check which port is being used on your controller
50+ // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*"
51+
52+ public const int TORQUE_ENABLE = 1 ; // Value for enabling the torque
53+ public const int TORQUE_DISABLE = 0 ; // Value for disabling the torque
54+ public const int MAX_POSITION_VALUE = 1048575 ; //
55+ public const int DXL_MOVING_STATUS_THRESHOLD = 20 ; // Dynamixel moving status threshold
56+ public const int EXT_POSITION_CONTROL_MODE = 4 ; // Value for extended position control mode (operating mode)
57+
58+ public const byte ESC_ASCII_VALUE = 0x1b ;
59+ public const byte SPACE_ASCII_VALUE = 0x20 ;
60+
61+ public const int COMM_SUCCESS = 0 ; // Communication Success result value
62+ public const int COMM_TX_FAIL = - 1001 ; // Communication Tx Failed
63+
64+ static void Main ( string [ ] args )
65+ {
66+ int port_num = dynamixel . portHandler ( DEVICENAME ) ;
67+
68+ // Initialize PacketHandler Structs
69+ dynamixel . packetHandler ( ) ;
70+
71+ int index = 0 ;
72+ int dxl_comm_result = COMM_TX_FAIL ; // Communication result
73+
74+ byte dxl_error = 0 ; // Dynamixel error
75+ Int32 dxl_present_position = 0 ; // Present position
76+
77+ // Open port
78+ if ( dynamixel . openPort ( port_num ) )
79+ {
80+ Console . WriteLine ( "Succeeded to open the port!" ) ;
81+ }
82+ else
83+ {
84+ Console . WriteLine ( "Failed to open the port!" ) ;
85+ Console . WriteLine ( "Press any key to terminate..." ) ;
86+ Console . ReadKey ( ) ;
87+ return ;
88+ }
89+
90+ // Set port baudrate
91+ if ( dynamixel . setBaudRate ( port_num , BAUDRATE ) )
92+ {
93+ Console . WriteLine ( "Succeeded to change the baudrate!" ) ;
94+ }
95+ else
96+ {
97+ Console . WriteLine ( "Failed to change the baudrate!" ) ;
98+ Console . WriteLine ( "Press any key to terminate..." ) ;
99+ Console . ReadKey ( ) ;
100+ return ;
101+ }
102+
103+ dynamixel . write1ByteTxRx ( port_num , PROTOCOL_VERSION , DXL_ID , ADDR_OPERATING_MODE , EXT_POSITION_CONTROL_MODE ) ;
104+ if ( ( dxl_comm_result = dynamixel . getLastTxRxResult ( port_num , PROTOCOL_VERSION ) ) != COMM_SUCCESS )
105+ {
106+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getTxRxResult ( PROTOCOL_VERSION , dxl_comm_result ) ) ) ;
107+ }
108+ else if ( ( dxl_error = dynamixel . getLastRxPacketError ( port_num , PROTOCOL_VERSION ) ) != 0 )
109+ {
110+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getRxPacketError ( PROTOCOL_VERSION , dxl_error ) ) ) ;
111+ }
112+ else
113+ {
114+ Console . WriteLine ( "Operating mode changed to extended position control mode." ) ;
115+ }
116+
117+ // Enable Dynamixel Torque
118+ dynamixel . write1ByteTxRx ( port_num , PROTOCOL_VERSION , DXL_ID , ADDR_TORQUE_ENABLE , TORQUE_ENABLE ) ;
119+ if ( ( dxl_comm_result = dynamixel . getLastTxRxResult ( port_num , PROTOCOL_VERSION ) ) != COMM_SUCCESS )
120+ {
121+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getTxRxResult ( PROTOCOL_VERSION , dxl_comm_result ) ) ) ;
122+ }
123+ else if ( ( dxl_error = dynamixel . getLastRxPacketError ( port_num , PROTOCOL_VERSION ) ) != 0 )
124+ {
125+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getRxPacketError ( PROTOCOL_VERSION , dxl_error ) ) ) ;
126+ }
127+ else
128+ {
129+ Console . WriteLine ( "Dynamixel has been successfully connected" ) ;
130+ }
131+
132+ while ( true )
133+ {
134+ Console . WriteLine ( "Press any key to continue! (or press ESC to quit!)" ) ;
135+ if ( Console . ReadKey ( true ) . KeyChar == ESC_ASCII_VALUE )
136+ break ;
137+
138+ Console . WriteLine ( " Press SPACE key to clear multi-turn information! (or press ESC to stop!)" ) ;
139+
140+ // Write goal position
141+ dynamixel . write4ByteTxRx ( port_num , PROTOCOL_VERSION , DXL_ID , ADDR_GOAL_POSITION , MAX_POSITION_VALUE ) ;
142+ if ( ( dxl_comm_result = dynamixel . getLastTxRxResult ( port_num , PROTOCOL_VERSION ) ) != COMM_SUCCESS )
143+ {
144+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getTxRxResult ( PROTOCOL_VERSION , dxl_comm_result ) ) ) ;
145+ }
146+ else if ( ( dxl_error = dynamixel . getLastRxPacketError ( port_num , PROTOCOL_VERSION ) ) != 0 )
147+ {
148+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getRxPacketError ( PROTOCOL_VERSION , dxl_error ) ) ) ;
149+ }
150+
151+ do
152+ {
153+ // Read present position
154+ dxl_present_position = ( Int32 ) dynamixel . read4ByteTxRx ( port_num , PROTOCOL_VERSION , DXL_ID , ADDR_PRESENT_POSITION ) ;
155+ if ( ( dxl_comm_result = dynamixel . getLastTxRxResult ( port_num , PROTOCOL_VERSION ) ) != COMM_SUCCESS )
156+ {
157+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getTxRxResult ( PROTOCOL_VERSION , dxl_comm_result ) ) ) ;
158+ }
159+ else if ( ( dxl_error = dynamixel . getLastRxPacketError ( port_num , PROTOCOL_VERSION ) ) != 0 )
160+ {
161+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getRxPacketError ( PROTOCOL_VERSION , dxl_error ) ) ) ;
162+ }
163+
164+ Console . Write ( string . Format ( " [ID: {0}] GoalPos: {1} PresPos: {2}" , DXL_ID , MAX_POSITION_VALUE , dxl_present_position , Environment . NewLine ) ) ;
165+ Console . Write ( "\r " . PadLeft ( Console . WindowWidth - Console . CursorLeft - 1 ) ) ;
166+ if ( Console . KeyAvailable )
167+ {
168+ char c = Console . ReadKey ( ) . KeyChar ;
169+ if ( c == SPACE_ASCII_VALUE )
170+ {
171+ Console . WriteLine ( "\n Stop & Clear Multi-Turn Information!" ) ;
172+
173+ // Write the present position to the goal position to stop moving
174+ dynamixel . write4ByteTxRx ( port_num , PROTOCOL_VERSION , DXL_ID , ADDR_GOAL_POSITION , ( UInt32 ) dxl_present_position ) ;
175+ if ( ( dxl_comm_result = dynamixel . getLastTxRxResult ( port_num , PROTOCOL_VERSION ) ) != COMM_SUCCESS )
176+ {
177+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getTxRxResult ( PROTOCOL_VERSION , dxl_comm_result ) ) ) ;
178+ }
179+ else if ( ( dxl_error = dynamixel . getLastRxPacketError ( port_num , PROTOCOL_VERSION ) ) != 0 )
180+ {
181+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getRxPacketError ( PROTOCOL_VERSION , dxl_error ) ) ) ;
182+ }
183+
184+ System . Threading . Thread . Sleep ( 300 ) ;
185+
186+ // Clear Multi-Turn Information
187+ dynamixel . clearMultiTurn ( port_num , PROTOCOL_VERSION , DXL_ID ) ;
188+ if ( ( dxl_comm_result = dynamixel . getLastTxRxResult ( port_num , PROTOCOL_VERSION ) ) != COMM_SUCCESS )
189+ {
190+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getTxRxResult ( PROTOCOL_VERSION , dxl_comm_result ) ) ) ;
191+ }
192+ else if ( ( dxl_error = dynamixel . getLastRxPacketError ( port_num , PROTOCOL_VERSION ) ) != 0 )
193+ {
194+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getRxPacketError ( PROTOCOL_VERSION , dxl_error ) ) ) ;
195+ }
196+
197+ // Read present position
198+ dxl_present_position = ( Int32 ) dynamixel . read4ByteTxRx ( port_num , PROTOCOL_VERSION , DXL_ID , ADDR_PRESENT_POSITION ) ;
199+ if ( ( dxl_comm_result = dynamixel . getLastTxRxResult ( port_num , PROTOCOL_VERSION ) ) != COMM_SUCCESS )
200+ {
201+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getTxRxResult ( PROTOCOL_VERSION , dxl_comm_result ) ) ) ;
202+ }
203+ else if ( ( dxl_error = dynamixel . getLastRxPacketError ( port_num , PROTOCOL_VERSION ) ) != 0 )
204+ {
205+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getRxPacketError ( PROTOCOL_VERSION , dxl_error ) ) ) ;
206+ }
207+
208+ Console . WriteLine ( " Present Position has been reset. : {0} \n " , dxl_present_position ) ;
209+
210+ break ;
211+ }
212+ else if ( c == ESC_ASCII_VALUE )
213+ {
214+ Console . WriteLine ( "\n Stopped!! \n " ) ;
215+
216+ // Write the present position to the goal position to stop moving
217+ dynamixel . write4ByteTxRx ( port_num , PROTOCOL_VERSION , DXL_ID , ADDR_GOAL_POSITION , ( UInt32 ) dxl_present_position ) ;
218+ if ( ( dxl_comm_result = dynamixel . getLastTxRxResult ( port_num , PROTOCOL_VERSION ) ) != COMM_SUCCESS )
219+ {
220+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getTxRxResult ( PROTOCOL_VERSION , dxl_comm_result ) ) ) ;
221+ }
222+ else if ( ( dxl_error = dynamixel . getLastRxPacketError ( port_num , PROTOCOL_VERSION ) ) != 0 )
223+ {
224+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getRxPacketError ( PROTOCOL_VERSION , dxl_error ) ) ) ;
225+ }
226+
227+ break ;
228+ }
229+ }
230+ } while ( ( Math . Abs ( MAX_POSITION_VALUE - dxl_present_position ) > DXL_MOVING_STATUS_THRESHOLD ) ) ;
231+ }
232+
233+ // Disable Dynamixel Torque
234+ dynamixel . write1ByteTxRx ( port_num , PROTOCOL_VERSION , DXL_ID , ADDR_TORQUE_ENABLE , TORQUE_DISABLE ) ;
235+ if ( ( dxl_comm_result = dynamixel . getLastTxRxResult ( port_num , PROTOCOL_VERSION ) ) != COMM_SUCCESS )
236+ {
237+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getTxRxResult ( PROTOCOL_VERSION , dxl_comm_result ) ) ) ;
238+ }
239+ else if ( ( dxl_error = dynamixel . getLastRxPacketError ( port_num , PROTOCOL_VERSION ) ) != 0 )
240+ {
241+ Console . WriteLine ( Marshal . PtrToStringAnsi ( dynamixel . getRxPacketError ( PROTOCOL_VERSION , dxl_error ) ) ) ;
242+ }
243+
244+ // Close port
245+ dynamixel . closePort ( port_num ) ;
246+
247+ return ;
248+ }
249+ }
250+ }
0 commit comments