├── .gitignore
├── README-orig.md
├── README.md
└── ROSArduinoBridge
├── ROSArduinoBridge.ino
├── commands.h
├── diff_controller.h
├── encoder_driver.h
├── encoder_driver.ino
├── motor_driver.h
├── motor_driver.ino
├── sensors.h
├── servos.h
└── servos.ino
/.gitignore:
--------------------------------------------------------------------------------
1 | .vscode/
2 | build/
--------------------------------------------------------------------------------
/README-orig.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 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Arduino Motor Controller
2 |
3 | This code turns an Arduino into a motor controller!
4 | It provides a simple serial interface to communicate with a high-level computer (e.g. running ROS), and generates the appropriate PWM signals for a motor driver, to drive two motors.
5 |
6 | This is a fork of the original code, with some changes, and removal of the ROS nodes (see [this repo](https://github.com/joshnewans/serial_motor_demo) for an alternative). Check out `README-orig.md` for the original README.
7 |
8 | As I only have need for a subset of the functionality, I have no idea what does and doesn't work, beyond what is detailed below.
9 | Feedback/improvements are welcome (though no promises on how quickly I'll respond). I currently only use the L298N driver, and the Arduino encoder mode.
10 |
11 |
12 |
13 | TODO
14 | - Finish this README
15 |
16 |
17 | ## Functionality
18 |
19 | The main functionality provided is to receive motor speed requests over a serial connection, and provide encoder feedback.
20 | The original code has provisions for other features - e.g. read/write of digital/analog pins, servo control, but I've never used them.
21 |
22 | The main commands to know are
23 |
24 | - `e` - Motor responds with current encoder counts for each motor
25 | - `r` - Reset encoder values
26 | - `o ` - Set the raw PWM speed of each motor (-255 to 255)
27 | - `m ` - Set the closed-loop speed of each motor in *counts per loop* (Default loop rate is 30, so `(counts per sec)/30`
28 | - `p ` - Update the PID parameters
29 |
30 |
31 | ## Gotchas
32 |
33 | Some quick things to note
34 |
35 | - There is an auto timeout (default 2s) so you need to keep sending commands for it to keep moving
36 | - PID parameter order is PDI (?)
37 | - Motor speed is in counts per loop
38 | - Default baud rate 57600
39 | - Needs carriage return (CR)
40 | - Make sure serial is enabled (user in dialout group)
41 | - Check out the original readme for more
42 |
43 |
44 | ## TODO (maybe)
45 | - Document PID tuning
46 | - Make the speed input counts per second
47 | - Add/test more driver boards
48 | - Add/test other functionality
--------------------------------------------------------------------------------
/ROSArduinoBridge/ROSArduinoBridge.ino:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * ROSArduinoBridge
3 |
4 | A set of simple serial commands to control a differential drive
5 | robot and receive back sensor and odometry data. Default
6 | configuration assumes use of an Arduino Mega + Pololu motor
7 | controller shield + Robogaia Mega Encoder shield. Edit the
8 | readEncoder() and setMotorSpeed() wrapper functions if using
9 | different motor controller or encoder method.
10 |
11 | Created for the Pi Robot Project: http://www.pirobot.org
12 | and the Home Brew Robotics Club (HBRC): http://hbrobotics.org
13 |
14 | Authors: Patrick Goebel, James Nugen
15 |
16 | Inspired and modeled after the ArbotiX driver by Michael Ferguson
17 |
18 | Software License Agreement (BSD License)
19 |
20 | Copyright (c) 2012, Patrick Goebel.
21 | All rights reserved.
22 |
23 | Redistribution and use in source and binary forms, with or without
24 | modification, are permitted provided that the following conditions
25 | are met:
26 |
27 | * Redistributions of source code must retain the above copyright
28 | notice, this list of conditions and the following disclaimer.
29 | * Redistributions in binary form must reproduce the above
30 | copyright notice, this list of conditions and the following
31 | disclaimer in the documentation and/or other materials provided
32 | with the distribution.
33 |
34 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
35 | "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
36 | LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
37 | FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
38 | COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
39 | INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
40 | BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
41 | LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
42 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
43 | LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
44 | ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
45 | * POSSIBILITY OF SUCH DAMAGE.
46 | *********************************************************************/
47 |
48 | #define USE_BASE // Enable the base controller code
49 | //#undef USE_BASE // Disable the base controller code
50 |
51 | /* Define the motor controller and encoder library you are using */
52 | #ifdef USE_BASE
53 | /* The Pololu VNH5019 dual motor driver shield */
54 | //#define POLOLU_VNH5019
55 |
56 | /* The Pololu MC33926 dual motor driver shield */
57 | //#define POLOLU_MC33926
58 |
59 | /* The RoboGaia encoder shield */
60 | //#define ROBOGAIA
61 |
62 | /* Encoders directly attached to Arduino board */
63 | #define ARDUINO_ENC_COUNTER
64 |
65 | /* L298 Motor driver*/
66 | #define L298_MOTOR_DRIVER
67 | #endif
68 |
69 | //#define USE_SERVOS // Enable use of PWM servos as defined in servos.h
70 | #undef USE_SERVOS // Disable use of PWM servos
71 |
72 | /* Serial port baud rate */
73 | #define BAUDRATE 57600
74 |
75 | /* Maximum PWM signal */
76 | #define MAX_PWM 255
77 |
78 | #if defined(ARDUINO) && ARDUINO >= 100
79 | #include "Arduino.h"
80 | #else
81 | #include "WProgram.h"
82 | #endif
83 |
84 | /* Include definition of serial commands */
85 | #include "commands.h"
86 |
87 | /* Sensor functions */
88 | #include "sensors.h"
89 |
90 | /* Include servo support if required */
91 | #ifdef USE_SERVOS
92 | #include
93 | #include "servos.h"
94 | #endif
95 |
96 | #ifdef USE_BASE
97 | /* Motor driver function definitions */
98 | #include "motor_driver.h"
99 |
100 | /* Encoder driver function definitions */
101 | #include "encoder_driver.h"
102 |
103 | /* PID parameters and functions */
104 | #include "diff_controller.h"
105 |
106 | /* Run the PID loop at 30 times per second */
107 | #define PID_RATE 30 // Hz
108 |
109 | /* Convert the rate into an interval */
110 | const int PID_INTERVAL = 1000 / PID_RATE;
111 |
112 | /* Track the next time we make a PID calculation */
113 | unsigned long nextPID = PID_INTERVAL;
114 |
115 | /* Stop the robot if it hasn't received a movement command
116 | in this number of milliseconds */
117 | #define AUTO_STOP_INTERVAL 2000
118 | long lastMotorCommand = AUTO_STOP_INTERVAL;
119 | #endif
120 |
121 | /* Variable initialization */
122 |
123 | // A pair of varibles to help parse serial commands (thanks Fergs)
124 | int arg = 0;
125 | int index = 0;
126 |
127 | // Variable to hold an input character
128 | char chr;
129 |
130 | // Variable to hold the current single-character command
131 | char cmd;
132 |
133 | // Character arrays to hold the first and second arguments
134 | char argv1[16];
135 | char argv2[16];
136 |
137 | // The arguments converted to integers
138 | long arg1;
139 | long arg2;
140 |
141 | /* Clear the current command parameters */
142 | void resetCommand() {
143 | cmd = NULL;
144 | memset(argv1, 0, sizeof(argv1));
145 | memset(argv2, 0, sizeof(argv2));
146 | arg1 = 0;
147 | arg2 = 0;
148 | arg = 0;
149 | index = 0;
150 | }
151 |
152 | /* Run a command. Commands are defined in commands.h */
153 | int runCommand() {
154 | int i = 0;
155 | char *p = argv1;
156 | char *str;
157 | int pid_args[4];
158 | arg1 = atoi(argv1);
159 | arg2 = atoi(argv2);
160 |
161 | switch(cmd) {
162 | case GET_BAUDRATE:
163 | Serial.println(BAUDRATE);
164 | break;
165 | case ANALOG_READ:
166 | Serial.println(analogRead(arg1));
167 | break;
168 | case DIGITAL_READ:
169 | Serial.println(digitalRead(arg1));
170 | break;
171 | case ANALOG_WRITE:
172 | analogWrite(arg1, arg2);
173 | Serial.println("OK");
174 | break;
175 | case DIGITAL_WRITE:
176 | if (arg2 == 0) digitalWrite(arg1, LOW);
177 | else if (arg2 == 1) digitalWrite(arg1, HIGH);
178 | Serial.println("OK");
179 | break;
180 | case PIN_MODE:
181 | if (arg2 == 0) pinMode(arg1, INPUT);
182 | else if (arg2 == 1) pinMode(arg1, OUTPUT);
183 | Serial.println("OK");
184 | break;
185 | case PING:
186 | Serial.println(Ping(arg1));
187 | break;
188 | #ifdef USE_SERVOS
189 | case SERVO_WRITE:
190 | servos[arg1].setTargetPosition(arg2);
191 | Serial.println("OK");
192 | break;
193 | case SERVO_READ:
194 | Serial.println(servos[arg1].getServo().read());
195 | break;
196 | #endif
197 |
198 | #ifdef USE_BASE
199 | case READ_ENCODERS:
200 | Serial.print(readEncoder(LEFT));
201 | Serial.print(" ");
202 | Serial.println(readEncoder(RIGHT));
203 | break;
204 | case RESET_ENCODERS:
205 | resetEncoders();
206 | resetPID();
207 | Serial.println("OK");
208 | break;
209 | case MOTOR_SPEEDS:
210 | /* Reset the auto stop timer */
211 | lastMotorCommand = millis();
212 | if (arg1 == 0 && arg2 == 0) {
213 | setMotorSpeeds(0, 0);
214 | resetPID();
215 | moving = 0;
216 | }
217 | else moving = 1;
218 | leftPID.TargetTicksPerFrame = arg1;
219 | rightPID.TargetTicksPerFrame = arg2;
220 | Serial.println("OK");
221 | break;
222 | case MOTOR_RAW_PWM:
223 | /* Reset the auto stop timer */
224 | lastMotorCommand = millis();
225 | resetPID();
226 | moving = 0; // Sneaky way to temporarily disable the PID
227 | setMotorSpeeds(arg1, arg2);
228 | Serial.println("OK");
229 | break;
230 | case UPDATE_PID:
231 | while ((str = strtok_r(p, ":", &p)) != '\0') {
232 | pid_args[i] = atoi(str);
233 | i++;
234 | }
235 | Kp = pid_args[0];
236 | Kd = pid_args[1];
237 | Ki = pid_args[2];
238 | Ko = pid_args[3];
239 | Serial.println("OK");
240 | break;
241 | #endif
242 | default:
243 | Serial.println("Invalid Command");
244 | break;
245 | }
246 | }
247 |
248 | /* Setup function--runs once at startup. */
249 | void setup() {
250 | Serial.begin(BAUDRATE);
251 |
252 | // Initialize the motor controller if used */
253 | #ifdef USE_BASE
254 | #ifdef ARDUINO_ENC_COUNTER
255 | //set as inputs
256 | DDRD &= ~(1< 0) {
297 |
298 | // Read the next character
299 | chr = Serial.read();
300 |
301 | // Terminate a command with a CR
302 | if (chr == 13) {
303 | if (arg == 1) argv1[index] = NULL;
304 | else if (arg == 2) argv2[index] = NULL;
305 | runCommand();
306 | resetCommand();
307 | }
308 | // Use spaces to delimit parts of the command
309 | else if (chr == ' ') {
310 | // Step through the arguments
311 | if (arg == 0) arg = 1;
312 | else if (arg == 1) {
313 | argv1[index] = NULL;
314 | arg = 2;
315 | index = 0;
316 | }
317 | continue;
318 | }
319 | else {
320 | if (arg == 0) {
321 | // The first arg is the single-letter command
322 | cmd = chr;
323 | }
324 | else if (arg == 1) {
325 | // Subsequent arguments can be more than one character
326 | argv1[index] = chr;
327 | index++;
328 | }
329 | else if (arg == 2) {
330 | argv2[index] = chr;
331 | index++;
332 | }
333 | }
334 | }
335 |
336 | // If we are using base control, run a PID calculation at the appropriate intervals
337 | #ifdef USE_BASE
338 | if (millis() > nextPID) {
339 | updatePID();
340 | nextPID += PID_INTERVAL;
341 | }
342 |
343 | // Check to see if we have exceeded the auto-stop interval
344 | if ((millis() - lastMotorCommand) > AUTO_STOP_INTERVAL) {;
345 | setMotorSpeeds(0, 0);
346 | moving = 0;
347 | }
348 | #endif
349 |
350 | // Sweep servos
351 | #ifdef USE_SERVOS
352 | int i;
353 | for (i = 0; i < N_SERVOS; i++) {
354 | servos[i].doSweep();
355 | }
356 | #endif
357 | }
358 |
359 |
--------------------------------------------------------------------------------
/ROSArduinoBridge/commands.h:
--------------------------------------------------------------------------------
1 | /* Define single-letter commands that will be sent by the PC over the
2 | serial link.
3 | */
4 |
5 | #ifndef COMMANDS_H
6 | #define COMMANDS_H
7 |
8 | #define ANALOG_READ 'a'
9 | #define GET_BAUDRATE 'b'
10 | #define PIN_MODE 'c'
11 | #define DIGITAL_READ 'd'
12 | #define READ_ENCODERS 'e'
13 | #define MOTOR_SPEEDS 'm'
14 | #define MOTOR_RAW_PWM 'o'
15 | #define PING 'p'
16 | #define RESET_ENCODERS 'r'
17 | #define SERVO_WRITE 's'
18 | #define SERVO_READ 't'
19 | #define UPDATE_PID 'u'
20 | #define DIGITAL_WRITE 'w'
21 | #define ANALOG_WRITE 'x'
22 | #define LEFT 0
23 | #define RIGHT 1
24 |
25 | #endif
26 |
27 |
28 |
--------------------------------------------------------------------------------
/ROSArduinoBridge/diff_controller.h:
--------------------------------------------------------------------------------
1 | /* Functions and type-defs for PID control.
2 |
3 | Taken mostly from Mike Ferguson's ArbotiX code which lives at:
4 |
5 | http://vanadium-ros-pkg.googlecode.com/svn/trunk/arbotix/
6 | */
7 |
8 | /* PID setpoint info For a Motor */
9 | typedef struct {
10 | double TargetTicksPerFrame; // target speed in ticks per frame
11 | long Encoder; // encoder count
12 | long PrevEnc; // last encoder count
13 |
14 | /*
15 | * Using previous input (PrevInput) instead of PrevError to avoid derivative kick,
16 | * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-derivative-kick/
17 | */
18 | int PrevInput; // last input
19 | //int PrevErr; // last error
20 |
21 | /*
22 | * Using integrated term (ITerm) instead of integrated error (Ierror),
23 | * to allow tuning changes,
24 | * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/
25 | */
26 | //int Ierror;
27 | int ITerm; //integrated term
28 |
29 | long output; // last motor setting
30 | }
31 | SetPointInfo;
32 |
33 | SetPointInfo leftPID, rightPID;
34 |
35 | /* PID Parameters */
36 | int Kp = 20;
37 | int Kd = 12;
38 | int Ki = 0;
39 | int Ko = 50;
40 |
41 | unsigned char moving = 0; // is the base in motion?
42 |
43 | /*
44 | * Initialize PID variables to zero to prevent startup spikes
45 | * when turning PID on to start moving
46 | * In particular, assign both Encoder and PrevEnc the current encoder value
47 | * See http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-initialization/
48 | * Note that the assumption here is that PID is only turned on
49 | * when going from stop to moving, that's why we can init everything on zero.
50 | */
51 | void resetPID(){
52 | leftPID.TargetTicksPerFrame = 0.0;
53 | leftPID.Encoder = readEncoder(LEFT);
54 | leftPID.PrevEnc = leftPID.Encoder;
55 | leftPID.output = 0;
56 | leftPID.PrevInput = 0;
57 | leftPID.ITerm = 0;
58 |
59 | rightPID.TargetTicksPerFrame = 0.0;
60 | rightPID.Encoder = readEncoder(RIGHT);
61 | rightPID.PrevEnc = rightPID.Encoder;
62 | rightPID.output = 0;
63 | rightPID.PrevInput = 0;
64 | rightPID.ITerm = 0;
65 | }
66 |
67 | /* PID routine to compute the next motor commands */
68 | void doPID(SetPointInfo * p) {
69 | long Perror;
70 | long output;
71 | int input;
72 |
73 | //Perror = p->TargetTicksPerFrame - (p->Encoder - p->PrevEnc);
74 | input = p->Encoder - p->PrevEnc;
75 | Perror = p->TargetTicksPerFrame - input;
76 |
77 |
78 | /*
79 | * Avoid derivative kick and allow tuning changes,
80 | * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-derivative-kick/
81 | * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/
82 | */
83 | //output = (Kp * Perror + Kd * (Perror - p->PrevErr) + Ki * p->Ierror) / Ko;
84 | // p->PrevErr = Perror;
85 | output = (Kp * Perror - Kd * (input - p->PrevInput) + p->ITerm) / Ko;
86 | p->PrevEnc = p->Encoder;
87 |
88 | output += p->output;
89 | // Accumulate Integral error *or* Limit output.
90 | // Stop accumulating when output saturates
91 | if (output >= MAX_PWM)
92 | output = MAX_PWM;
93 | else if (output <= -MAX_PWM)
94 | output = -MAX_PWM;
95 | else
96 | /*
97 | * allow turning changes, see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/
98 | */
99 | p->ITerm += Ki * Perror;
100 |
101 | p->output = output;
102 | p->PrevInput = input;
103 | }
104 |
105 | /* Read the encoder values and call the PID routine */
106 | void updatePID() {
107 | /* Read the encoders */
108 | leftPID.Encoder = readEncoder(LEFT);
109 | rightPID.Encoder = readEncoder(RIGHT);
110 |
111 | /* If we're not moving there is nothing more to do */
112 | if (!moving){
113 | /*
114 | * Reset PIDs once, to prevent startup spikes,
115 | * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-initialization/
116 | * PrevInput is considered a good proxy to detect
117 | * whether reset has already happened
118 | */
119 | if (leftPID.PrevInput != 0 || rightPID.PrevInput != 0) resetPID();
120 | return;
121 | }
122 |
123 | /* Compute PID update for each motor */
124 | doPID(&rightPID);
125 | doPID(&leftPID);
126 |
127 | /* Set the motor speeds accordingly */
128 | setMotorSpeeds(leftPID.output, rightPID.output);
129 | }
130 |
131 |
--------------------------------------------------------------------------------
/ROSArduinoBridge/encoder_driver.h:
--------------------------------------------------------------------------------
1 | /* *************************************************************
2 | Encoder driver function definitions - by James Nugen
3 | ************************************************************ */
4 |
5 |
6 | #ifdef ARDUINO_ENC_COUNTER
7 | //below can be changed, but should be PORTD pins;
8 | //otherwise additional changes in the code are required
9 | #define LEFT_ENC_PIN_A PD2 //pin 2
10 | #define LEFT_ENC_PIN_B PD3 //pin 3
11 |
12 | //below can be changed, but should be PORTC pins
13 | #define RIGHT_ENC_PIN_A PC4 //pin A4
14 | #define RIGHT_ENC_PIN_B PC5 //pin A5
15 | #endif
16 |
17 | long readEncoder(int i);
18 | void resetEncoder(int i);
19 | void resetEncoders();
20 |
21 |
--------------------------------------------------------------------------------
/ROSArduinoBridge/encoder_driver.ino:
--------------------------------------------------------------------------------
1 | /* *************************************************************
2 | Encoder definitions
3 |
4 | Add an "#ifdef" block to this file to include support for
5 | a particular encoder board or library. Then add the appropriate
6 | #define near the top of the main ROSArduinoBridge.ino file.
7 |
8 | ************************************************************ */
9 |
10 | #ifdef USE_BASE
11 |
12 | #ifdef ROBOGAIA
13 | /* The Robogaia Mega Encoder shield */
14 | #include "MegaEncoderCounter.h"
15 |
16 | /* Create the encoder shield object */
17 | MegaEncoderCounter encoders = MegaEncoderCounter(4); // Initializes the Mega Encoder Counter in the 4X Count mode
18 |
19 | /* Wrap the encoder reading function */
20 | long readEncoder(int i) {
21 | if (i == LEFT) return encoders.YAxisGetCount();
22 | else return encoders.XAxisGetCount();
23 | }
24 |
25 | /* Wrap the encoder reset function */
26 | void resetEncoder(int i) {
27 | if (i == LEFT) return encoders.YAxisReset();
28 | else return encoders.XAxisReset();
29 | }
30 | #elif defined(ARDUINO_ENC_COUNTER)
31 | volatile long left_enc_pos = 0L;
32 | volatile long right_enc_pos = 0L;
33 | static const int8_t ENC_STATES [] = {0,1,-1,0,-1,0,0,1,1,0,0,-1,0,-1,1,0}; //encoder lookup table
34 |
35 | /* Interrupt routine for LEFT encoder, taking care of actual counting */
36 | ISR (PCINT2_vect){
37 | static uint8_t enc_last=0;
38 |
39 | enc_last <<=2; //shift previous state two places
40 | enc_last |= (PIND & (3 << 2)) >> 2; //read the current state into lowest 2 bits
41 |
42 | left_enc_pos += ENC_STATES[(enc_last & 0x0f)];
43 | }
44 |
45 | /* Interrupt routine for RIGHT encoder, taking care of actual counting */
46 | ISR (PCINT1_vect){
47 | static uint8_t enc_last=0;
48 |
49 | enc_last <<=2; //shift previous state two places
50 | enc_last |= (PINC & (3 << 4)) >> 4; //read the current state into lowest 2 bits
51 |
52 | right_enc_pos += ENC_STATES[(enc_last & 0x0f)];
53 | }
54 |
55 | /* Wrap the encoder reading function */
56 | long readEncoder(int i) {
57 | if (i == LEFT) return left_enc_pos;
58 | else return right_enc_pos;
59 | }
60 |
61 | /* Wrap the encoder reset function */
62 | void resetEncoder(int i) {
63 | if (i == LEFT){
64 | left_enc_pos=0L;
65 | return;
66 | } else {
67 | right_enc_pos=0L;
68 | return;
69 | }
70 | }
71 | #else
72 | #error A encoder driver must be selected!
73 | #endif
74 |
75 | /* Wrap the encoder reset function */
76 | void resetEncoders() {
77 | resetEncoder(LEFT);
78 | resetEncoder(RIGHT);
79 | }
80 |
81 | #endif
82 |
83 |
--------------------------------------------------------------------------------
/ROSArduinoBridge/motor_driver.h:
--------------------------------------------------------------------------------
1 | /***************************************************************
2 | Motor driver function definitions - by James Nugen
3 | *************************************************************/
4 |
5 | #ifdef L298_MOTOR_DRIVER
6 | #define RIGHT_MOTOR_BACKWARD 5
7 | #define LEFT_MOTOR_BACKWARD 6
8 | #define RIGHT_MOTOR_FORWARD 9
9 | #define LEFT_MOTOR_FORWARD 10
10 | #define RIGHT_MOTOR_ENABLE 12
11 | #define LEFT_MOTOR_ENABLE 13
12 | #endif
13 |
14 | void initMotorController();
15 | void setMotorSpeed(int i, int spd);
16 | void setMotorSpeeds(int leftSpeed, int rightSpeed);
17 |
--------------------------------------------------------------------------------
/ROSArduinoBridge/motor_driver.ino:
--------------------------------------------------------------------------------
1 | /***************************************************************
2 | Motor driver definitions
3 |
4 | Add a "#elif defined" block to this file to include support
5 | for a particular motor driver. Then add the appropriate
6 | #define near the top of the main ROSArduinoBridge.ino file.
7 |
8 | *************************************************************/
9 |
10 | #ifdef USE_BASE
11 |
12 | #ifdef POLOLU_VNH5019
13 | /* Include the Pololu library */
14 | #include "DualVNH5019MotorShield.h"
15 |
16 | /* Create the motor driver object */
17 | DualVNH5019MotorShield drive;
18 |
19 | /* Wrap the motor driver initialization */
20 | void initMotorController() {
21 | drive.init();
22 | }
23 |
24 | /* Wrap the drive motor set speed function */
25 | void setMotorSpeed(int i, int spd) {
26 | if (i == LEFT) drive.setM1Speed(spd);
27 | else drive.setM2Speed(spd);
28 | }
29 |
30 | // A convenience function for setting both motor speeds
31 | void setMotorSpeeds(int leftSpeed, int rightSpeed) {
32 | setMotorSpeed(LEFT, leftSpeed);
33 | setMotorSpeed(RIGHT, rightSpeed);
34 | }
35 | #elif defined POLOLU_MC33926
36 | /* Include the Pololu library */
37 | #include "DualMC33926MotorShield.h"
38 |
39 | /* Create the motor driver object */
40 | DualMC33926MotorShield drive;
41 |
42 | /* Wrap the motor driver initialization */
43 | void initMotorController() {
44 | drive.init();
45 | }
46 |
47 | /* Wrap the drive motor set speed function */
48 | void setMotorSpeed(int i, int spd) {
49 | if (i == LEFT) drive.setM1Speed(spd);
50 | else drive.setM2Speed(spd);
51 | }
52 |
53 | // A convenience function for setting both motor speeds
54 | void setMotorSpeeds(int leftSpeed, int rightSpeed) {
55 | setMotorSpeed(LEFT, leftSpeed);
56 | setMotorSpeed(RIGHT, rightSpeed);
57 | }
58 | #elif defined L298_MOTOR_DRIVER
59 | void initMotorController() {
60 | digitalWrite(RIGHT_MOTOR_ENABLE, HIGH);
61 | digitalWrite(LEFT_MOTOR_ENABLE, HIGH);
62 | }
63 |
64 | void setMotorSpeed(int i, int spd) {
65 | unsigned char reverse = 0;
66 |
67 | if (spd < 0)
68 | {
69 | spd = -spd;
70 | reverse = 1;
71 | }
72 | if (spd > 255)
73 | spd = 255;
74 |
75 | if (i == LEFT) {
76 | if (reverse == 0) { analogWrite(LEFT_MOTOR_FORWARD, spd); analogWrite(LEFT_MOTOR_BACKWARD, 0); }
77 | else if (reverse == 1) { analogWrite(LEFT_MOTOR_BACKWARD, spd); analogWrite(LEFT_MOTOR_FORWARD, 0); }
78 | }
79 | else /*if (i == RIGHT) //no need for condition*/ {
80 | if (reverse == 0) { analogWrite(RIGHT_MOTOR_FORWARD, spd); analogWrite(RIGHT_MOTOR_BACKWARD, 0); }
81 | else if (reverse == 1) { analogWrite(RIGHT_MOTOR_BACKWARD, spd); analogWrite(RIGHT_MOTOR_FORWARD, 0); }
82 | }
83 | }
84 |
85 | void setMotorSpeeds(int leftSpeed, int rightSpeed) {
86 | setMotorSpeed(LEFT, leftSpeed);
87 | setMotorSpeed(RIGHT, rightSpeed);
88 | }
89 | #else
90 | #error A motor driver must be selected!
91 | #endif
92 |
93 | #endif
94 |
--------------------------------------------------------------------------------
/ROSArduinoBridge/sensors.h:
--------------------------------------------------------------------------------
1 | /* Functions for various sensor types */
2 |
3 | float microsecondsToCm(long microseconds)
4 | {
5 | // The speed of sound is 340 m/s or 29 microseconds per cm.
6 | // The ping travels out and back, so to find the distance of the
7 | // object we take half of the distance travelled.
8 | return microseconds / 29 / 2;
9 | }
10 |
11 | long Ping(int pin) {
12 | long duration, range;
13 |
14 | // The PING))) is triggered by a HIGH pulse of 2 or more microseconds.
15 | // Give a short LOW pulse beforehand to ensure a clean HIGH pulse:
16 | pinMode(pin, OUTPUT);
17 | digitalWrite(pin, LOW);
18 | delayMicroseconds(2);
19 | digitalWrite(pin, HIGH);
20 | delayMicroseconds(5);
21 | digitalWrite(pin, LOW);
22 |
23 | // The same pin is used to read the signal from the PING))): a HIGH
24 | // pulse whose duration is the time (in microseconds) from the sending
25 | // of the ping to the reception of its echo off of an object.
26 | pinMode(pin, INPUT);
27 | duration = pulseIn(pin, HIGH);
28 |
29 | // convert the time into meters
30 | range = microsecondsToCm(duration);
31 |
32 | return(range);
33 | }
34 |
35 |
--------------------------------------------------------------------------------
/ROSArduinoBridge/servos.h:
--------------------------------------------------------------------------------
1 | #ifndef SERVOS_H
2 | #define SERVOS_H
3 |
4 |
5 | #define N_SERVOS 2
6 |
7 | // This delay in milliseconds determines the pause
8 | // between each one degree step the servo travels. Increasing
9 | // this number will make the servo sweep more slowly.
10 | // Decreasing this number will make the servo sweep more quickly.
11 | // Zero is the default number and will make the servos spin at
12 | // full speed. 150 ms makes them spin very slowly.
13 | int stepDelay [N_SERVOS] = { 0, 0 }; // ms
14 |
15 | // Pins
16 | byte servoPins [N_SERVOS] = { 3, 4 };
17 |
18 | // Initial Position
19 | byte servoInitPosition [N_SERVOS] = { 90, 90 }; // [0, 180] degrees
20 |
21 |
22 | class SweepServo
23 | {
24 | public:
25 | SweepServo();
26 | void initServo(
27 | int servoPin,
28 | int stepDelayMs,
29 | int initPosition);
30 | void doSweep();
31 | void setTargetPosition(int position);
32 | Servo getServo();
33 |
34 | private:
35 | Servo servo;
36 | int stepDelayMs;
37 | int currentPositionDegrees;
38 | int targetPositionDegrees;
39 | long lastSweepCommand;
40 | };
41 |
42 | SweepServo servos [N_SERVOS];
43 |
44 | #endif
45 |
--------------------------------------------------------------------------------
/ROSArduinoBridge/servos.ino:
--------------------------------------------------------------------------------
1 | /***************************************************************
2 | Servo Sweep - by Nathaniel Gallinger
3 |
4 | Sweep servos one degree step at a time with a user defined
5 | delay in between steps. Supports changing direction
6 | mid-sweep. Important for applications such as robotic arms
7 | where the stock servo speed is too fast for the strength
8 | of your system.
9 |
10 | *************************************************************/
11 |
12 | #ifdef USE_SERVOS
13 |
14 |
15 | // Constructor
16 | SweepServo::SweepServo()
17 | {
18 | this->currentPositionDegrees = 0;
19 | this->targetPositionDegrees = 0;
20 | this->lastSweepCommand = 0;
21 | }
22 |
23 |
24 | // Init
25 | void SweepServo::initServo(
26 | int servoPin,
27 | int stepDelayMs,
28 | int initPosition)
29 | {
30 | this->servo.attach(servoPin);
31 | this->stepDelayMs = stepDelayMs;
32 | this->currentPositionDegrees = initPosition;
33 | this->targetPositionDegrees = initPosition;
34 | this->lastSweepCommand = millis();
35 | }
36 |
37 |
38 | // Perform Sweep
39 | void SweepServo::doSweep()
40 | {
41 |
42 | // Get ellapsed time
43 | int delta = millis() - this->lastSweepCommand;
44 |
45 | // Check if time for a step
46 | if (delta > this->stepDelayMs) {
47 | // Check step direction
48 | if (this->targetPositionDegrees > this->currentPositionDegrees) {
49 | this->currentPositionDegrees++;
50 | this->servo.write(this->currentPositionDegrees);
51 | }
52 | else if (this->targetPositionDegrees < this->currentPositionDegrees) {
53 | this->currentPositionDegrees--;
54 | this->servo.write(this->currentPositionDegrees);
55 | }
56 | // if target == current position, do nothing
57 |
58 | // reset timer
59 | this->lastSweepCommand = millis();
60 | }
61 | }
62 |
63 |
64 | // Set a new target position
65 | void SweepServo::setTargetPosition(int position)
66 | {
67 | this->targetPositionDegrees = position;
68 | }
69 |
70 |
71 | // Accessor for servo object
72 | Servo SweepServo::getServo()
73 | {
74 | return this->servo;
75 | }
76 |
77 |
78 | #endif
79 |
--------------------------------------------------------------------------------