0) {
295 |
296 | // Read the next character
297 | chr = Serial.read();
298 |
299 | // Terminate a command with a CR
300 | if (chr == 13) {
301 | if (arg == 1) argv1[index] = NULL;
302 | else if (arg == 2) argv2[index] = NULL;
303 | runCommand();
304 | resetCommand();
305 | }
306 | // Use spaces to delimit parts of the command
307 | else if (chr == ' ') {
308 | // Step through the arguments
309 | if (arg == 0) arg = 1;
310 | else if (arg == 1) {
311 | argv1[index] = NULL;
312 | arg = 2;
313 | index = 0;
314 | }
315 | continue;
316 | }
317 | else {
318 | if (arg == 0) {
319 | // The first arg is the single-letter command
320 | cmd = chr;
321 | }
322 | else if (arg == 1) {
323 | // Subsequent arguments can be more than one character
324 | argv1[index] = chr;
325 | index++;
326 | }
327 | else if (arg == 2) {
328 | argv2[index] = chr;
329 | index++;
330 | }
331 | }
332 | }
333 |
334 | // If we are using base control, run a PID calculation at the appropriate intervals
335 | #ifdef USE_BASE
336 | if (millis() > nextPID) {
337 | updatePID();
338 | nextPID += PID_INTERVAL;
339 | }
340 | // Check to see if we have exceeded the auto-stop interval
341 | if ((millis() - lastMotorCommand) > AUTO_STOP_INTERVAL) {;
342 | setMotorSpeeds(0, 0);
343 | moving = 0;
344 | }
345 |
346 | #endif
347 |
348 | // Sweep servos
349 | #ifdef USE_SERVOS
350 | int i;
351 | for (i = 0; i < N_SERVOS; i++) {
352 | servos[i].doSweep();
353 | }
354 | #endif
355 |
356 |
357 |
358 | }
359 |
--------------------------------------------------------------------------------
/ros_arduino_bridge_Python3/ros_arduino_python/src/ros_arduino_python/arduino_driver.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | """
4 | A Python driver for the Arduino microcontroller running the
5 | ROSArduinoBridge firmware.
6 |
7 | Created for the Pi Robot Project: http://www.pirobot.org
8 | Copyright (c) 2012 Patrick Goebel. All rights reserved.
9 |
10 | This program is free software; you can redistribute it and/or modify
11 | it under the terms of the GNU General Public License as published by
12 | the Free Software Foundation; either version 2 of the License, or
13 | (at your option) any later version.
14 |
15 | This program is distributed in the hope that it will be useful,
16 | but WITHOUT ANY WARRANTY; without even the implied warranty of
17 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18 | GNU General Public License for more details at:
19 |
20 | http://www.gnu.org/licenses/gpl.html
21 |
22 | """
23 |
24 | import _thread as thread
25 | from math import pi as PI, degrees, radians
26 | import os
27 | import time
28 | import sys, traceback
29 | from serial.serialutil import SerialException
30 | from serial import Serial
31 |
32 | SERVO_MAX = 180
33 | SERVO_MIN = 0
34 |
35 | class Arduino:
36 | ''' Configuration Parameters
37 | '''
38 | N_ANALOG_PORTS = 6
39 | N_DIGITAL_PORTS = 12
40 |
41 | def __init__(self, port="/dev/ttyUSB0", baudrate=57600, timeout=0.5, motors_reversed=False):
42 |
43 | self.PID_RATE = 30 # Do not change this! It is a fixed property of the Arduino PID controller.
44 | self.PID_INTERVAL = 1000 / 30
45 |
46 | self.port = port
47 | self.baudrate = baudrate
48 | self.timeout = timeout
49 | self.encoder_count = 0
50 | self.writeTimeout = timeout
51 | self.interCharTimeout = timeout / 30.
52 | self.motors_reversed = motors_reversed
53 | # Keep things thread safe
54 | self.mutex = thread.allocate_lock()
55 |
56 | # An array to cache analog sensor readings
57 | self.analog_sensor_cache = [None] * self.N_ANALOG_PORTS
58 |
59 | # An array to cache digital sensor readings
60 | self.digital_sensor_cache = [None] * self.N_DIGITAL_PORTS
61 |
62 | def connect(self):
63 | try:
64 | print("Connecting to Arduino on port", self.port, "...")
65 | self.port = Serial(port=self.port, baudrate=self.baudrate, timeout=self.timeout, writeTimeout=self.writeTimeout)
66 | # The next line is necessary to give the firmware time to wake up.
67 | time.sleep(1)
68 | self.port.readline()
69 | self.port.write(b"b \r")
70 | print(self.port.readline())
71 | test = self.get_baud()
72 | if test != self.baudrate:
73 | time.sleep(1)
74 | test = self.get_baud()
75 | if test != self.baudrate:
76 | raise SerialException
77 | print("Connected at", self.baudrate)
78 | print("Arduino is ready.")
79 |
80 | except SerialException:
81 | print("Serial Exception:")
82 | print(sys.exc_info())
83 | print("Traceback follows:")
84 | traceback.print_exc(file=sys.stdout)
85 | print("Cannot connect to Arduino!")
86 | os._exit(1)
87 |
88 | def open(self):
89 | ''' Open the serial port.
90 | '''
91 | self.port.open()
92 |
93 | def close(self):
94 | ''' Close the serial port.
95 | '''
96 | self.port.close()
97 |
98 | def send(self, cmd):
99 | ''' This command should not be used on its own: it is called by the execute commands
100 | below in a thread safe manner.
101 | '''
102 | self.port.write(cmd.encode() + b'\r')
103 |
104 | def recv(self, timeout=0.5):
105 | timeout = min(timeout, self.timeout)
106 | ''' This command should not be used on its own: it is called by the execute commands
107 | below in a thread safe manner. Note: we use read() instead of readline() since
108 | readline() tends to return garbage characters from the Arduino
109 | '''
110 | c = ''
111 | value = ''
112 | attempts = 0
113 | while c != '\r':
114 | c = self.port.read(1).decode()
115 | value += c
116 | attempts += 1
117 | if attempts * self.interCharTimeout > timeout:
118 | return None
119 |
120 | value = value.strip('\r')
121 |
122 | return value
123 |
124 | def recv_ack(self):
125 | ''' This command should not be used on its own: it is called by the execute commands
126 | below in a thread safe manner.
127 | '''
128 | ack = self.recv(self.timeout)
129 | return ack == 'OK'
130 |
131 | def recv_int(self):
132 | ''' This command should not be used on its own: it is called by the execute commands
133 | below in a thread safe manner.
134 | '''
135 | value = self.recv(self.timeout)
136 | try:
137 | return int(value)
138 | except:
139 | return None
140 |
141 | def recv_array(self):
142 | ''' This command should not be used on its own: it is called by the execute commands
143 | below in a thread safe manner.
144 | '''
145 |
146 | try:
147 | values = self.recv(self.timeout * self.N_ANALOG_PORTS).split()
148 | return map(int, values)
149 | except:
150 | return []
151 |
152 | def execute(self, cmd):
153 | ''' Thread safe execution of "cmd" on the Arduino returning a single integer value.
154 | '''
155 | self.mutex.acquire()
156 |
157 | try:
158 | self.port.flushInput()
159 | except:
160 | pass
161 |
162 | ntries = 3
163 | attempts = 0
164 | command=(cmd +'\r').encode()
165 | print(command)
166 | try:
167 | self.port.write(command)
168 | value = self.recv(self.timeout)
169 | while attempts < ntries and (value == '' or value == 'Invalid Command' or value == None):
170 | try:
171 | self.port.flushInput()
172 | self.port.write(command)
173 | value = self.recv(self.timeout)
174 | except:
175 | print("Exception executing command: " + cmd)
176 | attempts += 1
177 | except:
178 | self.mutex.release()
179 | print("Exception executing command: " + cmd)
180 | value = None
181 |
182 | self.mutex.release()
183 | return int(value)
184 |
185 | def execute_array(self, cmd):
186 | ''' Thread safe execution of "cmd" on the Arduino returning an array.
187 | '''
188 | self.mutex.acquire()
189 |
190 | try:
191 | self.port.flushInput()
192 | except:
193 | pass
194 |
195 | ntries = 1
196 | attempts = 0
197 |
198 | try:
199 | self.port.write(cmd.encode() + b'\r')
200 | values = self.recv_array()
201 | while attempts < ntries and (values == '' or values == 'Invalid Command' or values == [] or values == None):
202 | try:
203 | self.port.flushInput()
204 | self.port.write(cmd.encode()+ b'\r')
205 | values = self.recv_array()
206 | except:
207 | print("Exception executing command: " + cmd)
208 | attempts += 1
209 | except:
210 | self.mutex.release()
211 | print("Exception executing command: " + cmd)
212 | raise SerialException
213 | return []
214 |
215 | try:
216 | values = map(int, values)
217 | except:
218 | values = []
219 |
220 | self.mutex.release()
221 | return values
222 |
223 | def execute_ack(self, cmd):
224 | ''' Thread safe execution of "cmd" on the Arduino returning True if response is ACK.
225 | '''
226 | self.mutex.acquire()
227 |
228 | try:
229 | self.port.flushInput()
230 | except:
231 | pass
232 |
233 | ntries = 1
234 | attempts = 0
235 |
236 | try:
237 | self.port.write(cmd.encode() + b'\r')
238 | ack = self.recv(self.timeout)
239 | while attempts < ntries and (ack == '' or ack == 'Invalid Command' or ack == None):
240 | try:
241 | self.port.flushInput()
242 | self.port.write(cmd.encode() + b'\r')
243 | ack = self.recv(self.timeout)
244 | except:
245 | print("Exception executing command: " + cmd)
246 | attempts += 1
247 | except:
248 | self.mutex.release()
249 | print("execute_ack exception when executing", cmd)
250 | print(sys.exc_info())
251 | return 0
252 |
253 | self.mutex.release()
254 | return ack == 'OK'
255 |
256 | def update_pid(self, Kp, Kd, Ki, Ko):
257 | ''' Set the PID parameters on the Arduino
258 | '''
259 | print("Updating PID parameters")
260 | cmd = 'u ' + str(Kp) + ':' + str(Kd) + ':' + str(Ki) + ':' + str(Ko)
261 | self.execute_ack(cmd)
262 |
263 | def get_baud(self):
264 | ''' Get the current baud rate on the serial port.
265 | '''
266 | try:
267 | return int(self.execute('b'));
268 | except:
269 | return None
270 |
271 | def get_encoder_counts(self):
272 | values = list(self.execute_array('e'))
273 | if len(values) != 2:
274 | print("Encoder count was not 2")
275 | raise SerialException
276 | return None
277 | else:
278 | if self.motors_reversed:
279 | values[0], values[1] = -values[0], -values[1]
280 | return values
281 |
282 | def reset_encoders(self):
283 | ''' Reset the encoder counts to 0
284 | '''
285 | return self.execute_ack('r')
286 |
287 | def drive(self, right, left):
288 | ''' Speeds are given in encoder ticks per PID interval
289 | '''
290 | if self.motors_reversed:
291 | left, right = -left, -right
292 | return self.execute_ack('m %d %d' %(right, left))
293 |
294 | def drive_m_per_s(self, right, left):
295 | ''' Set the motor speeds in meters per second.
296 | '''
297 | left_revs_per_second = float(left) / (self.wheel_diameter * PI)
298 | right_revs_per_second = float(right) / (self.wheel_diameter * PI)
299 |
300 | left_ticks_per_loop = int(left_revs_per_second * self.encoder_resolution * self.PID_INTERVAL * self.gear_reduction)
301 | right_ticks_per_loop = int(right_revs_per_second * self.encoder_resolution * self.PID_INTERVAL * self.gear_reduction)
302 |
303 | self.drive(right_ticks_per_loop , left_ticks_per_loop )
304 |
305 | def stop(self):
306 | ''' Stop both motors.
307 | '''
308 | self.drive(0, 0)
309 |
310 | def analog_read(self, pin):
311 | return self.execute('a %d' %pin)
312 |
313 | def analog_write(self, pin, value):
314 | return self.execute_ack('x %d %d' %(pin, value))
315 |
316 | def digital_read(self, pin):
317 | return self.execute('d %d' %pin)
318 |
319 | def digital_write(self, pin, value):
320 | return self.execute_ack('w %d %d' %(pin, value))
321 |
322 | def pin_mode(self, pin, mode):
323 | return self.execute_ack('c %d %d' %(pin, mode))
324 |
325 | def servo_write(self, id, pos):
326 | ''' Usage: servo_write(id, pos)
327 | Position is given in radians and converted to degrees before sending
328 | '''
329 | return self.execute_ack('s %d %d' %(id, min(SERVO_MAX, max(SERVO_MIN, degrees(pos)))))
330 |
331 | def servo_read(self, id):
332 | ''' Usage: servo_read(id)
333 | The returned position is converted from degrees to radians
334 | '''
335 | return radians(self.execute('t %d' %id))
336 |
337 | def ping(self, pin):
338 | ''' The srf05/Ping command queries an SRF05/Ping sonar sensor
339 | connected to the General Purpose I/O line pinId for a distance,
340 | and returns the range in cm. Sonar distance resolution is integer based.
341 | '''
342 | return self.execute('p %d' %pin);
343 |
344 | # def get_maxez1(self, triggerPin, outputPin):
345 | # ''' The maxez1 command queries a Maxbotix MaxSonar-EZ1 sonar
346 | # sensor connected to the General Purpose I/O lines, triggerPin, and
347 | # outputPin, for a distance, and returns it in Centimeters. NOTE: MAKE
348 | # SURE there's nothing directly in front of the MaxSonar-EZ1 upon
349 | # power up, otherwise it wont range correctly for object less than 6
350 | # inches away! The sensor reading defaults to use English units
351 | # (inches). The sensor distance resolution is integer based. Also, the
352 | # maxsonar trigger pin is RX, and the echo pin is PW.
353 | # '''
354 | # return self.execute('z %d %d' %(triggerPin, outputPin))
355 |
356 |
357 | """ Basic test for connectivity """
358 | if __name__ == "__main__":
359 | if os.name == "posix":
360 | portName = "/dev/ttyUSB0"
361 | else:
362 | portName = "COM43" # Windows style COM port.
363 |
364 | baudRate = 57600
365 |
366 | myArduino = Arduino(port=portName, baudrate=baudRate, timeout=0.5)
367 | myArduino.connect()
368 |
369 | print("Sleeping for 1 second...")
370 | time.sleep(1)
371 |
372 | print("Reading on analog port 0", myArduino.analog_read(0))
373 | print("Reading on digital port 0", myArduino.digital_read(0))
374 | print("Blinking the LED 3 times")
375 | for i in range(3):
376 | myArduino.digital_write(13, 1)
377 | time.sleep(1.0)
378 | #print "Current encoder counts", myArduino.encoders()
379 |
380 | print("Connection test successful.",)
381 |
382 | myArduino.stop()
383 | myArduino.close()
384 |
385 | print("Shutting down Arduino.")
386 |
--------------------------------------------------------------------------------
/ros_arduino_bridge_Python3/README.md:
--------------------------------------------------------------------------------
1 | Overview
2 | --------
3 | This branch (indigo-devel) is intended for ROS Indigo and above, and uses the Catkin buildsystem. It may also be compatible with ROS Hydro.
4 |
5 | This ROS stack includes an Arduino library (called ROSArduinoBridge) and a collection of ROS packages for controlling an Arduino-based robot using standard ROS messages and services. The stack does **not** depend on ROS Serial.
6 |
7 | Features of the stack include:
8 |
9 | * Direct support for Ping sonar and Sharp infrared (GP2D12) sensors
10 |
11 | * Can also read data from generic analog and digital sensors
12 |
13 | * Can control digital outputs (e.g. turn a switch or LED on and off)
14 |
15 | * Support for PWM servos
16 | * Configurable base controller if using the required hardware
17 |
18 | The stack includes a base controller for a differential drive
19 | robot that accepts ROS Twist messages and publishes odometry data back to
20 | the PC. The base controller requires the use of a motor controller and encoders for reading odometry data. The current version of the stack provides support for the following base controller hardware:
21 |
22 | * Pololu VNH5019 dual motor controller shield (http://www.pololu.com/catalog/product/2502) or Pololu MC33926 dual motor shield (http://www.pololu.com/catalog/product/2503).
23 |
24 | * Robogaia Mega Encoder shield
25 | (http://www.robogaia.com/two-axis-encoder-counter-mega-shield-version-2.html) or on-board wheel encoder counters.
26 |
27 | **NOTE:** The Robogaia Mega Encoder shield can only be used with an Arduino Mega. The on-board wheel encoder counters are currently only supported by Arduino Uno.
28 |
29 | * L298 motor driver
30 |
31 | * The library can be easily extended to include support for other motor controllers and encoder hardware or libraries.
32 |
33 | Official ROS Documentation
34 | --------------------------
35 | A standard ROS-style version of this documentation can be found on the ROS wiki at:
36 |
37 | http://www.ros.org/wiki/ros_arduino_bridge
38 |
39 |
40 | System Requirements
41 | -------------------
42 | **Python Serial:** To install the python-serial package under Ubuntu, use the command:
43 |
44 | $ sudo apt-get install python-serial
45 |
46 | On non-Ubuntu systems, use either:
47 |
48 | $ sudo pip install --upgrade pyserial
49 |
50 | or
51 |
52 | $ sudo easy_install -U pyserial
53 |
54 | **Arduino IDE 1.6.6 or Higher:**
55 | Note that the preprocessing of conditional #include statements is broken in earlier versions of the Arduino IDE. To ensure that the ROS Arduino Bridge firmware compiles correctly, be sure to install version 1.6.6 or higher of the Arduino IDE. You can download the IDE from https://www.arduino.cc/en/Main/Software.
56 |
57 | **Hardware:**
58 | The firmware should work with any Arduino-compatible controller for reading sensors and controlling PWM servos. However, to use the base controller, you will need a supported motor controller and encoder hardware as described above. If you do not have this hardware, you can still try the package for reading sensors and controlling servos. See the NOTES section at the end of this document for instructions on how to do this.
59 |
60 | To use the base controller you must also install the appropriate libraries for your motor controller and encoders. For the Pololu VNH5019 Dual Motor Shield, the library can be found at:
61 |
62 | https://github.com/pololu/Dual-VNH5019-Motor-Shield
63 |
64 | For the Pololu MC33926 Dual Motor Shield, the library can be found at:
65 |
66 | https://github.com/pololu/dual-mc33926-motor-shield
67 |
68 | The Robogaia Mega Encoder library can be found at:
69 |
70 | http://www.robogaia.com/uploads/6/8/0/9/6809982/__megaencodercounter-1.3.tar.gz
71 |
72 | L298 Motor Driver doesn't require any libraries
73 |
74 | These libraries should be installed in your standard Arduino
75 | sketchbook/libraries directory.
76 |
77 | Finally, it is assumed you are using version 1.0 or greater of the
78 | Arduino IDE.
79 |
80 | Preparing your Serial Port under Linux
81 | --------------------------------------
82 | Your Arduino will likely connect to your Linux computer as port /dev/ttyACM# or /dev/ttyUSB# where # is a number like 0, 1, 2, etc., depending on how many other devices are connected. The easiest way to make the determination is to unplug all other USB devices, plug in your Arduino, then run the command:
83 |
84 | $ ls /dev/ttyACM*
85 |
86 | or
87 |
88 | $ ls /dev/ttyUSB*
89 |
90 | Hopefully, one of these two commands will return the result you're looking for (e.g. /dev/ttyACM0) and the other will return the error "No such file or directory".
91 |
92 | Next you need to make sure you have read/write access to the port. Assuming your Arduino is connected on /dev/ttyACM0, run the command:
93 |
94 | $ ls -l /dev/ttyACM0
95 |
96 | and you should see an output similar to the following:
97 |
98 | crw-rw---- 1 root dialout 166, 0 2013-02-24 08:31 /dev/ttyACM0
99 |
100 | Note that only root and the "dialout" group have read/write access. Therefore, you need to be a member of the dialout group. You only have to do this once and it should then work for all USB devices you plug in later on.
101 |
102 | To add yourself to the dialout group, run the command:
103 |
104 | $ sudo usermod -a -G dialout your_user_name
105 |
106 | where your\_user\_name is your Linux login name. You will likely have to log out of your X-window session then log in again, or simply reboot your machine if you want to be sure.
107 |
108 | When you log back in again, try the command:
109 |
110 | $ groups
111 |
112 | and you should see a list of groups you belong to including dialout.
113 |
114 | Installation of the ros\_arduino\_bridge Stack
115 | ----------------------------------------------
116 |
117 | $ cd ~/catkin_workspace/src
118 | $ git clone https://github.com/hbrobotics/ros_arduino_bridge.git
119 | $ cd ~/catkin_workspace
120 | $ catkin_make
121 |
122 | The provided Arduino library is called ROSArduinoBridge and is
123 | located in the ros\_arduino\_firmware package. This sketch is
124 | specific to the hardware requirements above but it can also be used
125 | with other Arduino-type boards (e.g. Uno) by turning off the base
126 | controller as described in the NOTES section at the end of this
127 | document.
128 |
129 | To install the ROSArduinoBridge library, follow these steps:
130 |
131 | $ cd SKETCHBOOK_PATH
132 |
133 | where SKETCHBOOK_PATH is the path to your Arduino sketchbook directory.
134 |
135 | $ cp -rp `rospack find ros_arduino_firmware`/src/libraries/ROSArduinoBridge ROSArduinoBridge
136 |
137 | This last command copies the ROSArduinoBridge sketch files into your sketchbook folder. The next section describes how to configure, compile and upload this sketch.
138 |
139 |
140 | Loading the ROSArduinoBridge Sketch
141 | -----------------------------------
142 |
143 | * If you are using the base controller, make sure you have already installed the appropriate motor controller and encoder libraries into your Arduino sketchbook/librariesfolder.
144 |
145 | * Launch the Arduino 1.0 IDE and load the ROSArduinoBridge sketch.
146 | You should be able to find it by going to:
147 |
148 | File->Sketchbook->ROSArduinoBridge
149 |
150 | NOTE: If you don't have the required base controller hardware but
151 | still want to try the code, see the notes at the end of the file.
152 |
153 | Choose one of the supported motor controllers by uncommenting its #define statement and commenting out any others. By default, the Pololu VNH5019 driver is chosen.
154 |
155 | Choose a supported encoder library by by uncommenting its #define statement and commenting out any others. the Robogaia Mega Encoder shield is chosen by default.
156 |
157 | If you want to control PWM servos attached to your controller, look for the line:
158 |
159 |
160 | #define USE_SERVOS
161 |
162 |
163 | and make sure it is not commented out like this:
164 |
165 |
166 | //#define USE_SERVOS
167 |
168 |
169 | You must then edit the include file servos.h and change the N_SERVOS
170 | parameter as well as the pin numbers for the servos you have attached.
171 |
172 | * Compile and upload the sketch to your Arduino.
173 |
174 | Firmware Commands
175 | -----------------
176 | The ROSArduinoLibrary accepts single-letter commands over the serial port for polling sensors, controlling servos, driving the robot, and reading encoders. These commands can be sent to the Arduino over any serial interface, including the Serial Monitor in the Arduino IDE.
177 |
178 | **NOTE:** Before trying these commands, set the Serial Monitor baudrate to 57600 and the line terminator to "Carriage return" or "Both NL & CR" using the two pulldown menus on the lower right of the Serial Monitor window.
179 |
180 | The list of commands can be found in the file commands.h. The current list includes:
181 |
182 |
183 | #define ANALOG_READ 'a'
184 | #define GET_BAUDRATE 'b'
185 | #define PIN_MODE 'c'
186 | #define DIGITAL_READ 'd'
187 | #define READ_ENCODERS 'e'
188 | #define MOTOR_SPEEDS 'm'
189 | #define PING 'p'
190 | #define RESET_ENCODERS 'r'
191 | #define SERVO_WRITE 's'
192 | #define SERVO_READ 't'
193 | #define UPDATE_PID 'u'
194 | #define DIGITAL_WRITE 'w'
195 | #define ANALOG_WRITE 'x'
196 |
197 |
198 | For example, to get the analog reading on pin 3, use the command:
199 |
200 | a 3
201 |
202 | To change the mode of digital pin 3 to OUTPUT, send the command:
203 |
204 | c 3 1
205 |
206 | To get the current encoder counts:
207 |
208 | e
209 |
210 | To move the robot forward at 20 encoder ticks per second:
211 |
212 | m 20 20
213 |
214 |
215 | Testing your Wiring Connections
216 | -------------------------------
217 | On a differential drive robot, the motors are connected to the motor controller terminals with opposite polarities to each other. Similarly, the A/B leads from the encoders are connected in the reverse sense to each other. However, you still need to make sure that (a) the wheels move forward when given a positive motor speed and (b) that the encoder counts increase when the wheels move forward.
218 |
219 | After **placing your robot on blocks**, you can use the Serial Monitor in the Arduino IDE to test both requirements. Use the 'm' command to activate the motors, the 'e' command to get the encoder counts, and the 'r' command to reset the encoders to 0. Remember that at the firmware level, motor speeds are given in encoder ticks per second so that for an encoder resolution of, say 4000 counts per wheel revolution, a command such as 'm 20 20' should move the wheels fairly slowly. (The wheels will only move for 2 seconds which is the default setting for the AUTO\_STOP\_INTERVAL.) Also remember that the first argument is the left motor speed and the second argument is the right motor speed. Similarly, when using the 'e' command, the first number returned is the left encoder count and the second number is the right encoder count.
220 |
221 | Finally, you can use the 'r' and 'e' commands to verify the expected encoder counts by rotating the wheels by hand roughly one full turn and checking the reported counts.
222 |
223 |
224 | Configuring the ros\_arduino\_python Node
225 | -----------------------------------------
226 | Now that your Arduino is running the required sketch, you can
227 | configure the ROS side of things on your PC. You define your robot's
228 | dimensions, PID parameters, and sensor configuration by editing the
229 | YAML file in the directory ros\_arduino\_python/config. So first move
230 | into that directory:
231 |
232 | $ roscd ros_arduino_python/config
233 |
234 | Now copy the provided config file to one you can modify:
235 |
236 | $ cp arduino_params.yaml my_arduino_params.yaml
237 |
238 | Bring up your copy of the params file (my\_arduino\_params.yaml) in
239 | your favorite text editor. It should start off looking like this:
240 |
241 |
242 | port: /dev/ttyUSB0
243 | baud: 57600
244 | timeout: 0.1
245 |
246 | rate: 50
247 | sensorstate_rate: 10
248 |
249 | use_base_controller: False
250 | base_controller_rate: 10
251 |
252 | # === Robot drivetrain parameters
253 | #wheel_diameter: 0.146
254 | #wheel_track: 0.2969
255 | #encoder_resolution: 8384 # from Pololu for 131:1 motors
256 | #gear_reduction: 1.0
257 | #motors_reversed: True
258 |
259 | # === PID parameters
260 | #Kp: 20
261 | #Kd: 12
262 | #Ki: 0
263 | #Ko: 50
264 | #accel_limit: 1.0
265 |
266 | # === Sensor definitions. Examples only - edit for your robot.
267 | # Sensor type can be one of the follow (case sensitive!):
268 | # * Ping
269 | # * GP2D12
270 | # * Analog
271 | # * Digital
272 | # * PololuMotorCurrent
273 | # * PhidgetsVoltage
274 | # * PhidgetsCurrent (20 Amp, DC)
275 |
276 | sensors: {
277 | #motor_current_left: {pin: 0, type: PololuMotorCurrent, rate: 5},
278 | #motor_current_right: {pin: 1, type: PololuMotorCurrent, rate: 5},
279 | #ir_front_center: {pin: 2, type: GP2D12, rate: 10},
280 | #sonar_front_center: {pin: 5, type: Ping, rate: 10},
281 | arduino_led: {pin: 13, type: Digital, rate: 5, direction: output}
282 | }
283 |
284 |
285 | **NOTE**: Do not use tabs in your .yaml file or the parser will barf it back out when it tries to load it. Always use spaces instead. **ALSO**: When defining your sensor parameters, the last sensor in the list does **not** get a comma (,) at the end of the line but all the rest **must** have a comma.
286 |
287 | Let's now look at each section of this file.
288 |
289 | _Port Settings_
290 |
291 | The port will likely be either /dev/ttyACM0 or /dev/ttyUSB0. Set accordingly.
292 |
293 | The MegaRobogaiaPololu Arudino sketch connects at 57600 baud by default.
294 |
295 | _Polling Rates_
296 |
297 | The main *rate* parameter (50 Hz by default) determines how fast the
298 | outside ROS loop runs. The default should suffice in most cases. In
299 | any event, it should be at least as fast as your fastest sensor rate
300 | (defined below).
301 |
302 | The *sensorstate\_rate* determines how often to publish an aggregated
303 | list of all sensor readings. Each sensor also publishes on its own
304 | topic and rate.
305 |
306 | The *use\_base\_controller* parameter is set to False by default. Set it to True to use base control (assuming you have the required hardware.) You will also have to set the PID paramters that follow.
307 |
308 | The *base\_controller\_rate* determines how often to publish odometry readings.
309 |
310 | _Defining Sensors_
311 |
312 | The *sensors* parameter defines a dictionary of sensor names and
313 | sensor parameters. (You can name each sensor whatever you like but
314 | remember that the name for a sensor will also become the topic name
315 | for that sensor.)
316 |
317 | The four most important parameters are *pin*, *type*, *rate* and *direction*.
318 | The *rate* defines how many times per second you want to poll that
319 | sensor. For example, a voltage sensor might only be polled once a
320 | second (or even once every 2 seconds: rate=0.5), whereas a sonar
321 | sensor might be polled at 20 times per second. The *type* must be one
322 | of those listed (case sensitive!). The default *direction* is input so
323 | to define an output pin, set the direction explicitly to output. In
324 | the example above, the Arduino LED (pin 13) will be turned on and off
325 | at a rate of 2 times per second.
326 |
327 | _Setting Drivetrain and PID Parameters_
328 |
329 | To use the base controller, you will have to uncomment and set the
330 | robot drivetrain and PID parameters. The sample drivetrain parameters
331 | are for 6" drive wheels that are 11.5" apart. Note that ROS uses
332 | meters for distance so convert accordingly. The sample encoder
333 | resolution (ticks per revolution) is from the specs for the Pololu
334 | 131:1 motor. Set the appropriate number for your motor/encoder
335 | combination. Set the motors_reversed to True if you find your wheels
336 | are turning backward, otherwise set to False.
337 |
338 | The PID parameters are trickier to set. You can start with the sample
339 | values but be sure to place your robot on blocks before sending it
340 | your first Twist command.
341 |
342 | Launching the ros\_arduino\_python Node
343 | ---------------------------------------
344 | Take a look at the launch file arduino.launch in the
345 | ros\_arduino\_python/launch directory. As you can see, it points to a
346 | config file called my\_arduino\_params.yaml. If you named your config
347 | file something different, change the name in the launch file.
348 |
349 | With your Arduino connected and running the MegaRobogaiaPololu sketch,
350 | launch the ros\_arduino\_python node with your parameters:
351 |
352 | $ roslaunch ros_arduino_python arduino.launch
353 |
354 | You should see something like the following output:
355 |
356 |
357 | process[arduino-1]: started with pid [6098]
358 | Connecting to Arduino on port /dev/ttyUSB0 ...
359 | Connected at 57600
360 | Arduino is ready.
361 | [INFO] [WallTime: 1355498525.954491] Connected to Arduino on port /dev/ttyUSB0 at 57600 baud
362 | [INFO] [WallTime: 1355498525.966825] motor_current_right {'rate': 5, 'type': 'PololuMotorCurrent', 'pin': 1}
363 | [INFO]
364 | etc
365 |
366 |
367 | If you have any Ping sonar sensors on your robot and you defined them
368 | in your config file, they should start flashing to indicate you have
369 | made the connection.
370 |
371 | Viewing Sensor Data
372 | -------------------
373 | To see the aggregated sensor data, echo the sensor state topic:
374 |
375 | $ rostopic echo /arduino/sensor_state
376 |
377 | To see the data on any particular sensor, echo its topic name:
378 |
379 | $ rostopic echo /arduino/sensor/sensor_name
380 |
381 | For example, if you have a sensor called ir\_front\_center, you can see
382 | its data using:
383 |
384 | $ rostopic echo /arduino/sensor/ir_front_center
385 |
386 | You can also graph the range data using rxplot:
387 |
388 | $ rxplot -p 60 /arduino/sensor/ir_front_center/range
389 |
390 |
391 | Sending Twist Commands and Viewing Odometry Data
392 | ------------------------------------------------
393 |
394 | Place your robot on blocks, then try publishing a Twist command:
395 |
396 | $ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{ angular: {z: 0.5} }'
397 |
398 | The wheels should turn in a direction consistent with a
399 | counter-clockwise rotation (right wheel forward, left wheel backward).
400 | If they turn in the opposite direction, set the motors_reversed
401 | parameter in your config file to the opposite of its current setting,
402 | then kill and restart the arduino.launch file.
403 |
404 | Stop the robot with the command:
405 |
406 | $ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{}'
407 |
408 | To view odometry data:
409 |
410 | $ rostopic echo /odom
411 |
412 | or
413 |
414 | $ rxplot -p 60 /odom/pose/pose/position/x:y, /odom/twist/twist/linear/x, /odom/twist/twist/angular/z
415 |
416 | ROS Services
417 | ------------
418 | The ros\_arduino\_python package also defines a few ROS services as follows:
419 |
420 | **digital\_set\_direction** - set the direction of a digital pin
421 |
422 | $ rosservice call /arduino/digital_set_direction pin direction
423 |
424 | where pin is the pin number and direction is 0 for input and 1 for output.
425 |
426 | **digital\_write** - send a LOW (0) or HIGH (1) signal to a digital pin
427 |
428 | $ rosservice call /arduino/digital_write pin value
429 |
430 | where pin is the pin number and value is 0 for LOW and 1 for HIGH.
431 |
432 | **servo\_write** - set the position of a servo
433 |
434 | $ rosservice call /arduino/servo_write id pos
435 |
436 | where id is the index of the servo as defined in the Arduino sketch (servos.h) and pos is the position in radians (0 - 3.14).
437 |
438 | **servo\_read** - read the position of a servo
439 |
440 | $ rosservice call /arduino/servo_read id
441 |
442 | where id is the index of the servo as defined in the Arduino sketch (servos.h)
443 |
444 | Using the on-board wheel encoder counters (Arduino Uno only)
445 | ------------------------------------------------------------
446 | The firmware supports on-board wheel encoder counters for Arduino Uno.
447 | This allows connecting wheel encoders directly to the Arduino board, without the need for any additional wheel encoder counter equipment (such as a RoboGaia encoder shield).
448 |
449 | For speed, the code is directly addressing specific Atmega328p ports and interrupts, making this implementation Atmega328p (Arduino Uno) dependent. (It should be easy to adapt for other boards/AVR chips though.)
450 |
451 | To use the on-board wheel encoder counters, connect your wheel encoders to Arduino Uno as follows:
452 |
453 | Left wheel encoder A output -- Arduino UNO pin 2
454 | Left wheel encoder B output -- Arduino UNO pin 3
455 |
456 | Right wheel encoder A output -- Arduino UNO pin A4
457 | Right wheel encoder B output -- Arduino UNO pin A5
458 |
459 | Make the following changes in the ROSArduinoBridge sketch to disable the RoboGaia encoder shield, and enable the on-board one:
460 |
461 | /* The RoboGaia encoder shield */
462 | //#define ROBOGAIA
463 | /* Encoders directly attached to Arduino board */
464 | #define ARDUINO_ENC_COUNTER
465 |
466 | Compile the changes and upload to your controller.
467 |
468 | Using L298 Motor driver
469 | -----------------------
470 | the wiring between the L298 motor driver and arduino board is defined in motor_driver.h in the firmware as follow:
471 |
472 | #define RIGHT_MOTOR_BACKWARD 5
473 | #define LEFT_MOTOR_BACKWARD 6
474 | #define RIGHT_MOTOR_FORWARD 9
475 | #define LEFT_MOTOR_FORWARD 10
476 | #define RIGHT_MOTOR_ENABLE 12
477 | #define LEFT_MOTOR_ENABLE 13
478 |
479 | wire them this way or change them if you want, and make sure that the L298 motor driver is defined then compile and upload the firmware.
480 |
481 | NOTES
482 | -----
483 | If you do not have the hardware required to run the base controller,
484 | follow the instructions below so that you can still use your
485 | Arduino-compatible controller to read sensors and control PWM servos.
486 |
487 | First, you need to edit the ROSArduinoBridge sketch. At the top of
488 | the file comment out the line:
489 |
490 |
491 | #define USE_BASE
492 |
493 |
494 | so that it looks like this:
495 |
496 |
497 | //#define USE_BASE
498 |
499 |
500 | **NOTE:** If you are using a version of the Arduino IDE previous to 1.6.6, you also need to comment out the line that looks like this in the file encoder_driver.ino:
501 |
502 | #include "MegaEncoderCounter.h"
503 |
504 | so it looks like this:
505 |
506 | //#include "MegaEncoderCounter.h"
507 |
508 | Compile the changes and upload to your controller.
509 |
510 | Next, edit your my\_arduino_params.yaml file and make sure the
511 | use\_base\_controller parameter is set to False. That's all there is to it.
512 |
--------------------------------------------------------------------------------