From f03fad0d5a405d40255bb1f5f3a0864f2e65349d Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Fri, 22 Feb 2013 06:43:52 -0800 Subject: [PATCH 01/14] Updated README.md --- README.md | 44 +++++++++++++++++++++++++------------------- 1 file changed, 25 insertions(+), 19 deletions(-) diff --git a/README.md b/README.md index f15ca5f..e7f3dff 100644 --- a/README.md +++ b/README.md @@ -25,6 +25,12 @@ the PC. The base controller requires the use of a motor controller and encoders * The library can be easily extended to include support for other motor controllers and encoder hardware or libraries. +Official ROS Documentation +-------------------------- +A standard ROS-style version of this documentation can be found on the ROS wiki at: + +http://www.ros.org/wiki/ros_arduino_bridge + System Requirements ------------------- @@ -114,7 +120,7 @@ parameter as well as the pin numbers for the servos you have attached. Firmware Commands ----------------- -The ROSArduionLibrary 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. +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. The list of commands can be found in the file commands.h. The current list includes: @@ -155,7 +161,7 @@ Testing your Wiring Connections ------------------------------- 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. -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. +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. 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. @@ -172,7 +178,7 @@ into that directory: Now copy the provided config file to one you can modify: - $ cp arduino_params.yaml my_arduino_params.yaml + $ cp arduino\_params.yaml my_arduino_params.yaml Bring up your copy of the params file (my\_arduino\_params.yaml) in your favorite text editor. It should start off looking like this: @@ -286,9 +292,9 @@ config file called my\_arduino\_params.yaml. If you named your config file something different, change the name in the launch file. With your Arduino connected and running the MegaRobogaiaPololu sketch, -launch the ros\_arduiono\_python node with your parameters: +launch the ros\_arduino\_python node with your parameters: - $ roslaunch ros_arduino_python arduino.launch + $ roslaunch ros\_arduino\_python arduino.launch You should see something like the following output: @@ -298,7 +304,7 @@ Connecting to Arduino on port /dev/ttyUSB0 ... Connected at 57600 Arduino is ready. [INFO] [WallTime: 1355498525.954491] Connected to Arduino on port /dev/ttyUSB0 at 57600 baud -[INFO] [WallTime: 1355498525.966825] motor_current_right {'rate': 5, 'type': 'PololuMotorCurrent', 'pin': 1} +[INFO] [WallTime: 1355498525.966825] motor\_current\_right {'rate': 5, 'type': 'PololuMotorCurrent', 'pin': 1} [INFO] etc @@ -311,20 +317,20 @@ Viewing Sensor Data ------------------- To see the aggregated sensor data, echo the sensor state topic: - $ rostopic echo /arduino/sensor_state + $ rostopic echo /arduino/sensor\_state To see the data on any particular sensor, echo its topic name: $ rostopic echo /arduino/sensor/sensor_name -For example, if you have a sensor called ir_front_center, you can see +For example, if you have a sensor called ir\_front\_center, you can see its data using: - $ rostopic echo /arduino/sensor/ir_front_center + $ rostopic echo /arduino/sensor/ir\_front\_center You can also graph the range data using rxplot: - $ rxplot -p 60 /arduino/sensor/ir_front_center/range + $ rxplot -p 60 /arduino/sensor/ir\_front\_center/range Sending Twist Commands and Viewing Odometry Data @@ -332,7 +338,7 @@ Sending Twist Commands and Viewing Odometry Data Place your robot on blocks, then try publishing a Twist command: - $ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{ angular: {z: 0.5} }' + $ rostopic pub -1 /cmd\_vel geometry\_msgs/Twist '{ angular: {z: 0.5} }' The wheels should turn in a direction consistent with a counter-clockwise rotation (right wheel forward, left wheel backward). @@ -342,7 +348,7 @@ then kill and restart the arduino.launch file. Stop the robot with the command: - $ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{}' + $ rostopic pub -1 /cmd\_vel geometry\_msgs/Twist '{}' To view odometry data: @@ -354,29 +360,29 @@ or ROS Services ------------ -The ros_arduino_python package also defines a few ROS services as follows: +The ros\_arduino\_python package also defines a few ROS services as follows: **digital\_set\_direction** - set the direction of a digital pin - $ rosservice call /arduino/digital_set_direction pin direction + $ rosservice call /arduino/digital\_set\_direction pin direction where pin is the pin number and direction is 0 for input and 1 for output. **digital\_write** - send a LOW (0) or HIGH (1) signal to a digital pin - $ rosservice call /arduino/digital_write pin value + $ rosservice call /arduino/digital\_write pin value where pin is the pin number and value is 0 for LOW and 1 for HIGH. **servo\_write** - set the position of a servo - $ rosservice call /arduino/servo_write id pos + $ rosservice call /arduino/servo\_write id pos where id is the index of the servo as defined in the Arduino sketch (servos.h) and pos is the position in degrees (0 - 180). **servo\_read** - read the position of a servo - $ rosservice call /arduino/servo_read id + $ rosservice call /arduino/servo\_read id where id is the index of the servo as defined in the Arduino sketch (servos.h) @@ -401,7 +407,7 @@ to this: #undef USE_BASE -You also need to comment out the line that looks like this in the file encoder_driver.ino: +**NOTE:** You also need to comment out the line that looks like this in the file encoder_driver.ino: #include "MegaEncoderCounter.h" @@ -412,4 +418,4 @@ so it looks like this: Compile the changes and upload to your controller. Next, edit your my\_arduino_params.yaml file and make sure the -use\_base\_controller parameter is set to False. That's all there is to it. \ No newline at end of file +use\_base\_controller parameter is set to False. That's all there is to it. From d9d0c8b2a87f5e0171052d5a418b30de43cd188a Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Sun, 24 Feb 2013 08:14:42 -0800 Subject: [PATCH 02/14] Changed default port in arduino_params.yaml from /dev/ttyUSB0 to /dev/ttyACM0 --- ros_arduino_python/config/arduino_params.yaml | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/ros_arduino_python/config/arduino_params.yaml b/ros_arduino_python/config/arduino_params.yaml index 23bfca8..84f9b77 100644 --- a/ros_arduino_python/config/arduino_params.yaml +++ b/ros_arduino_python/config/arduino_params.yaml @@ -1,4 +1,9 @@ -port: /dev/ttyUSB0 +# For a direct USB cable connection, the port name is typically +# /dev/ttyACM# where is # is a number such as 0, 1, 2, etc +# For a wireless connection like XBee, the port is typically +# /dev/ttyUSB# where # is a number such as 0, 1, 2, etc. + +port: /dev/ttyACM0 baud: 57600 timeout: 0.1 From e0fcbbfec843dacaecd5bd463d2fc210c4cbfe46 Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Sun, 24 Feb 2013 17:40:51 -0800 Subject: [PATCH 03/14] Updated README file to include instructions on setting permissions on the serial port --- README.md | 45 +++++++++++++++++++++--- ros_arduino_python/src/arduino_driver.py | 9 +++-- 2 files changed, 46 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index e7f3dff..f73ae6d 100644 --- a/README.md +++ b/README.md @@ -29,7 +29,7 @@ Official ROS Documentation -------------------------- A standard ROS-style version of this documentation can be found on the ROS wiki at: -http://www.ros.org/wiki/ros_arduino_bridge +http://www.ros.org/wiki/ros\_arduino\_bridge System Requirements @@ -54,13 +54,46 @@ sketchbook/libraries directory. Finally, it is assumed you are using version 1.0 or greater of the Arduino IDE. +Preparing your Serial Port under Linux +-------------------------------------- +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: -Installation ------------- + $ ls /dev/ttyACM* + +or + + $ ls /dev/ttyUSB* + +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". + +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: + + $ ls -l /dev/ttyACM0 + +and you should see an output similar to the following: + + crw-rw---- 1 root dialout 166, 0 2013-02-24 08:31 /dev/ttyACM0 + +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. + +To add yourself to the dialout group, run the command: + + $ sudo usermod -a -G dialout your\_user\_name + +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. + +When you log back in again, try the command: + + $ groups + +and you should see a list of groups you belong to including dialout. + +Installation of the ros\_arduino\_bridge Stack +---------------------------------------------- $ cd ~/ros_workspace - $ git clone https://github.com/hbrobotics/ros_arduino_bridge.git - $ cd ros_arduino_bridge + $ git clone https://github.com/hbrobotics/ros\_arduino\_bridge.git + $ cd ros\_arduino\_bridge $ rosmake The provided Arduino library is called ROSArduinoBridge and is @@ -122,6 +155,8 @@ Firmware Commands ----------------- 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. +**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. + The list of commands can be found in the file commands.h. The current list includes:
diff --git a/ros_arduino_python/src/arduino_driver.py b/ros_arduino_python/src/arduino_driver.py
index c5f0e43..8eedc8c 100755
--- a/ros_arduino_python/src/arduino_driver.py
+++ b/ros_arduino_python/src/arduino_driver.py
@@ -25,7 +25,7 @@ import thread
 from math import pi as PI, degrees, radians
 import os
 import time
-import sys
+import sys, traceback
 from serial.serialutil import SerialException
 from serial import Serial
 
@@ -68,15 +68,18 @@ class Arduino:
             test = self.get_baud()
             if test != self.baudrate:
                 time.sleep(1)
-                test = self.get_baud()
+                test = self.get_baud()   
                 if test != self.baudrate:
                     raise SerialException
             print "Connected at", self.baudrate
             print "Arduino is ready."
 
         except SerialException:
+            print "Serial Exception:"
+            print sys.exc_info()
+            print "Traceback follows:"
+            traceback.print_exc(file=sys.stdout)
             print "Cannot connect to Arduino!"
-            print "Make sure you are plugged in and turned on."
             os._exit(1)
 
     def open(self): 

From 44632157f3a21a32f738fd98cbbe8fe7de738eb6 Mon Sep 17 00:00:00 2001
From: Patrick Goebel 
Date: Sun, 24 Feb 2013 17:47:21 -0800
Subject: [PATCH 04/14] Fixed extraneous backslash characters in README file

---
 README.md | 32 ++++++++++++++++----------------
 1 file changed, 16 insertions(+), 16 deletions(-)

diff --git a/README.md b/README.md
index f73ae6d..8cbdfa4 100644
--- a/README.md
+++ b/README.md
@@ -29,7 +29,7 @@ Official ROS Documentation
 --------------------------
 A standard ROS-style version of this documentation can be found on the ROS wiki at:
 
-http://www.ros.org/wiki/ros\_arduino\_bridge
+http://www.ros.org/wiki/ros_arduino_bridge
 
 
 System Requirements
@@ -78,7 +78,7 @@ Note that only root and the "dialout" group have read/write access.  Therefore,
 
 To add yourself to the dialout group, run the command:
 
-    $ sudo usermod -a -G dialout your\_user\_name
+    $ sudo usermod -a -G dialout your_user_name
 
 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.
 
@@ -92,8 +92,8 @@ Installation of the ros\_arduino\_bridge Stack
 ----------------------------------------------
 
     $ cd ~/ros_workspace
-    $ git clone https://github.com/hbrobotics/ros\_arduino\_bridge.git
-    $ cd ros\_arduino\_bridge
+    $ git clone https://github.com/hbrobotics/ros_arduino_bridge.git
+    $ cd ros_arduino_bridge
     $ rosmake
 
 The provided Arduino library is called ROSArduinoBridge and is
@@ -213,7 +213,7 @@ into that directory:
 
 Now copy the provided config file to one you can modify:
 
-    $ cp arduino\_params.yaml my_arduino_params.yaml
+    $ cp arduino_params.yaml my_arduino_params.yaml
 
 Bring up your copy of the params file (my\_arduino\_params.yaml) in
 your favorite text editor.  It should start off looking like this:
@@ -329,7 +329,7 @@ file something different, change the name in the launch file.
 With your Arduino connected and running the MegaRobogaiaPololu sketch,
 launch the ros\_arduino\_python node with your parameters:
 
-    $ roslaunch ros\_arduino\_python arduino.launch
+    $ roslaunch ros_arduino_python arduino.launch
 
 You should see something like the following output:
 
@@ -339,7 +339,7 @@ Connecting to Arduino on port /dev/ttyUSB0 ...
 Connected at 57600
 Arduino is ready.
 [INFO] [WallTime: 1355498525.954491] Connected to Arduino on port /dev/ttyUSB0 at 57600 baud
-[INFO] [WallTime: 1355498525.966825] motor\_current\_right {'rate': 5, 'type': 'PololuMotorCurrent', 'pin': 1}
+[INFO] [WallTime: 1355498525.966825] motor_current_right {'rate': 5, 'type': 'PololuMotorCurrent', 'pin': 1}
 [INFO]
 etc
 
@@ -352,7 +352,7 @@ Viewing Sensor Data ------------------- To see the aggregated sensor data, echo the sensor state topic: - $ rostopic echo /arduino/sensor\_state + $ rostopic echo /arduino/sensor_state To see the data on any particular sensor, echo its topic name: @@ -361,11 +361,11 @@ To see the data on any particular sensor, echo its topic name: For example, if you have a sensor called ir\_front\_center, you can see its data using: - $ rostopic echo /arduino/sensor/ir\_front\_center + $ rostopic echo /arduino/sensor/ir_front_center You can also graph the range data using rxplot: - $ rxplot -p 60 /arduino/sensor/ir\_front\_center/range + $ rxplot -p 60 /arduino/sensor/ir_front_center/range Sending Twist Commands and Viewing Odometry Data @@ -373,7 +373,7 @@ Sending Twist Commands and Viewing Odometry Data Place your robot on blocks, then try publishing a Twist command: - $ rostopic pub -1 /cmd\_vel geometry\_msgs/Twist '{ angular: {z: 0.5} }' + $ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{ angular: {z: 0.5} }' The wheels should turn in a direction consistent with a counter-clockwise rotation (right wheel forward, left wheel backward). @@ -383,7 +383,7 @@ then kill and restart the arduino.launch file. Stop the robot with the command: - $ rostopic pub -1 /cmd\_vel geometry\_msgs/Twist '{}' + $ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{}' To view odometry data: @@ -399,25 +399,25 @@ The ros\_arduino\_python package also defines a few ROS services as follows: **digital\_set\_direction** - set the direction of a digital pin - $ rosservice call /arduino/digital\_set\_direction pin direction + $ rosservice call /arduino/digital_set_direction pin direction where pin is the pin number and direction is 0 for input and 1 for output. **digital\_write** - send a LOW (0) or HIGH (1) signal to a digital pin - $ rosservice call /arduino/digital\_write pin value + $ rosservice call /arduino/digital_write pin value where pin is the pin number and value is 0 for LOW and 1 for HIGH. **servo\_write** - set the position of a servo - $ rosservice call /arduino/servo\_write id pos + $ rosservice call /arduino/servo_write id pos where id is the index of the servo as defined in the Arduino sketch (servos.h) and pos is the position in degrees (0 - 180). **servo\_read** - read the position of a servo - $ rosservice call /arduino/servo\_read id + $ rosservice call /arduino/servo_read id where id is the index of the servo as defined in the Arduino sketch (servos.h) From 373946600850461f7a714ddad13b2edb733253d0 Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Sun, 24 Feb 2013 17:47:21 -0800 Subject: [PATCH 05/14] Added traceback call to arduino_driver.py to better diagnose serial port problems. --- README.md | 32 ++++++++++++++++---------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/README.md b/README.md index f73ae6d..8cbdfa4 100644 --- a/README.md +++ b/README.md @@ -29,7 +29,7 @@ Official ROS Documentation -------------------------- A standard ROS-style version of this documentation can be found on the ROS wiki at: -http://www.ros.org/wiki/ros\_arduino\_bridge +http://www.ros.org/wiki/ros_arduino_bridge System Requirements @@ -78,7 +78,7 @@ Note that only root and the "dialout" group have read/write access. Therefore, To add yourself to the dialout group, run the command: - $ sudo usermod -a -G dialout your\_user\_name + $ sudo usermod -a -G dialout your_user_name 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. @@ -92,8 +92,8 @@ Installation of the ros\_arduino\_bridge Stack ---------------------------------------------- $ cd ~/ros_workspace - $ git clone https://github.com/hbrobotics/ros\_arduino\_bridge.git - $ cd ros\_arduino\_bridge + $ git clone https://github.com/hbrobotics/ros_arduino_bridge.git + $ cd ros_arduino_bridge $ rosmake The provided Arduino library is called ROSArduinoBridge and is @@ -213,7 +213,7 @@ into that directory: Now copy the provided config file to one you can modify: - $ cp arduino\_params.yaml my_arduino_params.yaml + $ cp arduino_params.yaml my_arduino_params.yaml Bring up your copy of the params file (my\_arduino\_params.yaml) in your favorite text editor. It should start off looking like this: @@ -329,7 +329,7 @@ file something different, change the name in the launch file. With your Arduino connected and running the MegaRobogaiaPololu sketch, launch the ros\_arduino\_python node with your parameters: - $ roslaunch ros\_arduino\_python arduino.launch + $ roslaunch ros_arduino_python arduino.launch You should see something like the following output: @@ -339,7 +339,7 @@ Connecting to Arduino on port /dev/ttyUSB0 ... Connected at 57600 Arduino is ready. [INFO] [WallTime: 1355498525.954491] Connected to Arduino on port /dev/ttyUSB0 at 57600 baud -[INFO] [WallTime: 1355498525.966825] motor\_current\_right {'rate': 5, 'type': 'PololuMotorCurrent', 'pin': 1} +[INFO] [WallTime: 1355498525.966825] motor_current_right {'rate': 5, 'type': 'PololuMotorCurrent', 'pin': 1} [INFO] etc @@ -352,7 +352,7 @@ Viewing Sensor Data ------------------- To see the aggregated sensor data, echo the sensor state topic: - $ rostopic echo /arduino/sensor\_state + $ rostopic echo /arduino/sensor_state To see the data on any particular sensor, echo its topic name: @@ -361,11 +361,11 @@ To see the data on any particular sensor, echo its topic name: For example, if you have a sensor called ir\_front\_center, you can see its data using: - $ rostopic echo /arduino/sensor/ir\_front\_center + $ rostopic echo /arduino/sensor/ir_front_center You can also graph the range data using rxplot: - $ rxplot -p 60 /arduino/sensor/ir\_front\_center/range + $ rxplot -p 60 /arduino/sensor/ir_front_center/range Sending Twist Commands and Viewing Odometry Data @@ -373,7 +373,7 @@ Sending Twist Commands and Viewing Odometry Data Place your robot on blocks, then try publishing a Twist command: - $ rostopic pub -1 /cmd\_vel geometry\_msgs/Twist '{ angular: {z: 0.5} }' + $ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{ angular: {z: 0.5} }' The wheels should turn in a direction consistent with a counter-clockwise rotation (right wheel forward, left wheel backward). @@ -383,7 +383,7 @@ then kill and restart the arduino.launch file. Stop the robot with the command: - $ rostopic pub -1 /cmd\_vel geometry\_msgs/Twist '{}' + $ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{}' To view odometry data: @@ -399,25 +399,25 @@ The ros\_arduino\_python package also defines a few ROS services as follows: **digital\_set\_direction** - set the direction of a digital pin - $ rosservice call /arduino/digital\_set\_direction pin direction + $ rosservice call /arduino/digital_set_direction pin direction where pin is the pin number and direction is 0 for input and 1 for output. **digital\_write** - send a LOW (0) or HIGH (1) signal to a digital pin - $ rosservice call /arduino/digital\_write pin value + $ rosservice call /arduino/digital_write pin value where pin is the pin number and value is 0 for LOW and 1 for HIGH. **servo\_write** - set the position of a servo - $ rosservice call /arduino/servo\_write id pos + $ rosservice call /arduino/servo_write id pos where id is the index of the servo as defined in the Arduino sketch (servos.h) and pos is the position in degrees (0 - 180). **servo\_read** - read the position of a servo - $ rosservice call /arduino/servo\_read id + $ rosservice call /arduino/servo_read id where id is the index of the servo as defined in the Arduino sketch (servos.h) From 4607c1cf8ec232e13ad0dc7961c885bd051123f8 Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Tue, 5 Mar 2013 08:14:16 -0800 Subject: [PATCH 06/14] Added rosdep on python-serial to manifest.xml in ros_arduino_python package --- ros_arduino_python/manifest.xml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ros_arduino_python/manifest.xml b/ros_arduino_python/manifest.xml index 1d04908..11276df 100644 --- a/ros_arduino_python/manifest.xml +++ b/ros_arduino_python/manifest.xml @@ -16,7 +16,9 @@ - + + + From 317a9757d122fbfdf7b19f7d0eb568ebdc1c967a Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Tue, 5 Mar 2013 08:19:39 -0800 Subject: [PATCH 07/14] Updated README to include dependency on python-serial --- README.md | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/README.md b/README.md index 8cbdfa4..421d1c6 100644 --- a/README.md +++ b/README.md @@ -34,6 +34,19 @@ http://www.ros.org/wiki/ros_arduino_bridge System Requirements ------------------- +**Python Serial:** To install the python-serial package under Ubuntu, use the command: + + $ sudo apt-get install python-serial + +On non-Ubuntu systems, use either: + + $ sudo pip install --upgrade pyserial + +or + + $ sudo easy_install -U pyserial + + The stack 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. 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: @@ -94,6 +107,7 @@ Installation of the ros\_arduino\_bridge Stack $ cd ~/ros_workspace $ git clone https://github.com/hbrobotics/ros_arduino_bridge.git $ cd ros_arduino_bridge + $ rosdep install ros_arduino_bridge $ rosmake The provided Arduino library is called ROSArduinoBridge and is From 71b8c5876e3ae3a82f56d500668518adc0f5b7be Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Tue, 19 Mar 2013 18:15:02 -0700 Subject: [PATCH 08/14] Updated README to remove the 'rosdep install' command as it is not working on some setups --- README.md | 1 - 1 file changed, 1 deletion(-) diff --git a/README.md b/README.md index 421d1c6..ee16379 100644 --- a/README.md +++ b/README.md @@ -107,7 +107,6 @@ Installation of the ros\_arduino\_bridge Stack $ cd ~/ros_workspace $ git clone https://github.com/hbrobotics/ros_arduino_bridge.git $ cd ros_arduino_bridge - $ rosdep install ros_arduino_bridge $ rosmake The provided Arduino library is called ROSArduinoBridge and is From dad031ee2c0c70ec6634d899587cac83c00cc6f6 Mon Sep 17 00:00:00 2001 From: Kristof Date: Fri, 16 Aug 2013 10:52:57 +0200 Subject: [PATCH 09/14] Enhanced PID algorithm Enhanced PID algorithm based on the series of blog posts at http://brettbeauregard.com/blog/2011/04/improving-the-beginners-pid-introduction/ Specifically: 1. Avoid derivative kickback - http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-derivative-kick/ 2. Allow smooth on-the-fly tuning changes - http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/ 3. Reset windup mitigation - http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-reset-windup/ 4. Bumpless initialization - http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-initialization/ --- .../ROSArduinoBridge/ROSArduinoBridge.ino | 1 + .../ROSArduinoBridge/diff_controller.h | 82 +++++++++++++++++-- 2 files changed, 74 insertions(+), 9 deletions(-) diff --git a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.ino b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.ino index 14ffbe7..dd9a8f8 100644 --- a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.ino +++ b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.ino @@ -236,6 +236,7 @@ void setup() { // Initialize the motor controller if used */ #ifdef USE_BASE initMotorController(); + resetPID(); #endif /* Attach servos if used */ diff --git a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/diff_controller.h b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/diff_controller.h index 0284681..bbb6e58 100644 --- a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/diff_controller.h +++ b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/diff_controller.h @@ -10,8 +10,22 @@ typedef struct { double TargetTicksPerFrame; // target speed in ticks per frame long Encoder; // encoder count long PrevEnc; // last encoder count - int PrevErr; // last error - int Ierror; // integrated error + + /* + * Using previous input (PrevInput) instead of PrevError to avoid derivative kick, + * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-derivative-kick/ + */ + long PrevInput; // last input + //int PrevErr; // last error + + /* + * Using integrated term (ITerm) instead of integrated error (Ierror), + * to allow tuning changes, + * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/ + */ + //int Ierror; + long ITerm; //integrated term + int output; // last motor setting } SetPointInfo; @@ -26,16 +40,56 @@ int Ko = 50; unsigned char moving = 0; // is the base in motion? +/* +* Initialize PID variables to zero to prevent startup spikes +* when turning PID on to start moving +* In particular, assign both Encoder and PrevEnc the current encoder value +* See http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-initialization/ +* Note that the assumption here is that PID is only turned on +* when going from stop to moving, that's why we can init everything on zero. +*/ +void resetPID(){ + leftPID.TargetTicksPerFrame = 0.0; + leftPID.Encoder = readEncoder(0); + leftPID.PrevEnc = leftPID.Encoder; + leftPID.output = 0; + leftPID.PrevInput = 0; + leftPID.ITerm = 0; + + rightPID.TargetTicksPerFrame = 0.0; + rightPID.Encoder = readEncoder(1); + rightPID.PrevEnc = rightPID.Encoder; + rightPID.output = 0; + rightPID.PrevInput = 0; + rightPID.ITerm = 0; +} + /* PID routine to compute the next motor commands */ void doPID(SetPointInfo * p) { long Perror; long output; + long input; - Perror = p->TargetTicksPerFrame - (p->Encoder - p->PrevEnc); + //Perror = p->TargetTicksPerFrame - (p->Encoder - p->PrevEnc); + input = p->Encoder - p->PrevEnc; + Perror = p->TargetTicksPerFrame - input; - // Derivative error is the delta Perror - output = (Kp * Perror + Kd * (Perror - p->PrevErr) + Ki * p->Ierror) / Ko; - p->PrevErr = Perror; + /* + * Avoid reset windup, + * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-reset-windup/ + */ + p->ITerm += (Ki * Perror); + if (p->ITerm > MAX_PWM) p->ITerm = MAX_PWM; + else if (p->ITerm < -MAX_PWM) p->ITerm = MAX_PWM; + + /* + * Avoid derivative kick and allow tuning changes, + * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-derivative-kick/ + * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/ + */ + //output = (Kp * Perror + Kd * (Perror - p->PrevErr) + Ki * p->Ierror) / Ko; + // p->PrevErr = Perror; + output = (Kp * Perror - Kd * (input - p->PrevInput) + p->ITerm) / Ko; p->PrevEnc = p->Encoder; output += p->output; @@ -45,10 +99,12 @@ void doPID(SetPointInfo * p) { output = MAX_PWM; else if (output <= -MAX_PWM) output = -MAX_PWM; - else - p->Ierror += Perror; + //else + // p->Ierror += Perror; + p->output = output; + p->PrevInput = input; } /* Read the encoder values and call the PID routine */ @@ -58,8 +114,16 @@ void updatePID() { rightPID.Encoder = readEncoder(1); /* If we're not moving there is nothing more to do */ - if (!moving) + if (!moving){ + /* + * Reset PIDs once, to prevent startup spikes, + * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-initialization/ + * PrevInput is considered a good proxy to detect + * whether reset has already happened + */ + if (leftPID.PrevInput != 0 || rightPID.PrevInput != 0) resetPID(); return; + } /* Compute PID update for each motor */ doPID(&rightPID); From 2c9881552bc939fc4231328ebc148ebbc2530ba1 Mon Sep 17 00:00:00 2001 From: Kristof Robot Date: Fri, 16 Aug 2013 15:04:33 +0200 Subject: [PATCH 10/14] Bugfix: added resetPID() call in RESET_ENCODERS statement, to ensure that PID gets reset when encoders get reset. --- .../src/libraries/ROSArduinoBridge/ROSArduinoBridge.ino | 1 + 1 file changed, 1 insertion(+) diff --git a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.ino b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.ino index dd9a8f8..77322d2 100644 --- a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.ino +++ b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.ino @@ -197,6 +197,7 @@ int runCommand() { break; case RESET_ENCODERS: resetEncoders(); + resetPID(); Serial.println("OK"); break; case MOTOR_SPEEDS: From 7887d639f3d65f59f13de942b710db70aad19092 Mon Sep 17 00:00:00 2001 From: Kristof Robot Date: Fri, 16 Aug 2013 16:16:48 +0200 Subject: [PATCH 11/14] Bugfix - removed reset wind-up fix Removed the reset windup prevention code, as the old code already took care of that by only incrementing Ierror when output was not being clamped. --- .../ROSArduinoBridge/diff_controller.h | 27 ++++++++----------- 1 file changed, 11 insertions(+), 16 deletions(-) diff --git a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/diff_controller.h b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/diff_controller.h index bbb6e58..6bb1002 100644 --- a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/diff_controller.h +++ b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/diff_controller.h @@ -15,7 +15,7 @@ typedef struct { * Using previous input (PrevInput) instead of PrevError to avoid derivative kick, * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-derivative-kick/ */ - long PrevInput; // last input + int PrevInput; // last input //int PrevErr; // last error /* @@ -24,9 +24,9 @@ typedef struct { * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/ */ //int Ierror; - long ITerm; //integrated term + int ITerm; //integrated term - int output; // last motor setting + long output; // last motor setting } SetPointInfo; @@ -45,8 +45,8 @@ unsigned char moving = 0; // is the base in motion? * when turning PID on to start moving * In particular, assign both Encoder and PrevEnc the current encoder value * See http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-initialization/ -* Note that the assumption here is that PID is only turned on -* when going from stop to moving, that's why we can init everything on zero. +* Note that the assumption here is that PID is only turned on +* when going from stop to moving, that's why we can init everything on zero. */ void resetPID(){ leftPID.TargetTicksPerFrame = 0.0; @@ -68,19 +68,12 @@ void resetPID(){ void doPID(SetPointInfo * p) { long Perror; long output; - long input; + int input; //Perror = p->TargetTicksPerFrame - (p->Encoder - p->PrevEnc); input = p->Encoder - p->PrevEnc; Perror = p->TargetTicksPerFrame - input; - /* - * Avoid reset windup, - * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-reset-windup/ - */ - p->ITerm += (Ki * Perror); - if (p->ITerm > MAX_PWM) p->ITerm = MAX_PWM; - else if (p->ITerm < -MAX_PWM) p->ITerm = MAX_PWM; /* * Avoid derivative kick and allow tuning changes, @@ -99,9 +92,11 @@ void doPID(SetPointInfo * p) { output = MAX_PWM; else if (output <= -MAX_PWM) output = -MAX_PWM; - //else - // p->Ierror += Perror; - + else + /* + * allow turning changes, see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/ + */ + p->ITerm += Ki * Perror; p->output = output; p->PrevInput = input; From 0a4cccca50ec98ee9f39d4dd3e5b547d17b52aaf Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Sat, 17 Aug 2013 16:53:45 -0700 Subject: [PATCH 12/14] Fixed spelling typo in arduino_node.py --- .../ROSArduinoBridge/ROSArduinoBridge.cpp | 439 ++++++++++++++++++ ros_arduino_python/nodes/arduino_node.py | 2 +- 2 files changed, 440 insertions(+), 1 deletion(-) create mode 100644 ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.cpp diff --git a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.cpp b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.cpp new file mode 100644 index 0000000..50d2076 --- /dev/null +++ b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.cpp @@ -0,0 +1,439 @@ +/********************************************************************* + * ROSArduinoBridge + + A set of simple serial commands to control a differential drive + robot and receive back sensor and odometry data. Default + configuration assumes use of an Arduino Mega + Pololu motor + controller shield + Robogaia Mega Encoder shield. Edit the + readEncoder() and setMotorSpeed() wrapper functions if using + different motor controller or encoder method. + + Created for the Pi Robot Project: http://www.pirobot.org + and the Home Brew Robotics Club (HBRC): http://hbrobotics.org + + Authors: Patrick Goebel, James Nugen + + Inspired and modeled after the ArbotiX driver by Michael Ferguson + + Software License Agreement (BSD License) + + Copyright (c) 2012, Patrick Goebel. + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions + are met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above + copyright notice, this list of conditions and the following + disclaimer in the documentation and/or other materials provided + with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#define USE_BASE // Enable the base controller code +//#undef USE_BASE // Disable the base controller code + +/* Define the motor controller and encoder library you are using */ +#ifdef USE_BASE + /* The Pololu VNH5019 dual motor driver shield */ + #define POLOLU_VNH5019 + + /* The Pololu MC33926 dual motor driver shield */ + //#define POLOLU_MC33926 + + /* The RoboGaia encoder shield */ + #define ROBOGAIA +#endif + +//#define USE_SERVOS // Enable use of PWM servos as defined in servos.h +#undef USE_SERVOS // Disable use of PWM servos + +/* Serial port baud rate */ +#define BAUDRATE 57600 + +/* Maximum PWM signal */ +#define MAX_PWM 255 + +#if defined(ARDUINO) && ARDUINO >= 100 +#include "Arduino.h" +#else +#include "WProgram.h" +#endif + +/* Include definition of serial commands */ +#include "commands.h" + +/* Sensor functions */ +#include "sensors.h" + +/* Include servo support if required */ +#ifdef USE_SERVOS + #include + #include "servos.h" +#endif + +#ifdef USE_BASE + /* Motor driver function definitions */ + #include "motor_driver.h" + + /* Encoder driver function definitions */ + #include "encoder_driver.h" + + /* PID parameters and functions */ + #include "diff_controller.h" + + /* Run the PID loop at 30 times per second */ + #define PID_RATE 30 // Hz + + /* Convert the rate into an interval */ + const int PID_INTERVAL = 1000 / PID_RATE; + + /* Track the next time we make a PID calculation */ + unsigned long nextPID = PID_INTERVAL; + + /* Stop the robot if it hasn't received a movement command + in this number of milliseconds */ + #define AUTO_STOP_INTERVAL 2000 + long lastMotorCommand = AUTO_STOP_INTERVAL; +#endif + +/* Variable initialization */ + +// A pair of varibles to help parse serial commands (thanks Fergs) +int arg = 0; +int index = 0; + +// Variable to hold an input character +char chr; + +// Variable to hold the current single-character command +char cmd; + +// Character arrays to hold the first and second arguments +char argv1[16]; +char argv2[16]; + +// The arguments converted to integers +long arg1; +long arg2; + +/* Clear the current command parameters */ +void resetCommand() { + cmd = NULL; + memset(argv1, 0, sizeof(argv1)); + memset(argv2, 0, sizeof(argv2)); + arg1 = 0; + arg2 = 0; + arg = 0; + index = 0; +} + +/* Run a command. Commands are defined in commands.h */ +int runCommand() { + int i = 0; + char *p = argv1; + char *str; + int pid_args[4]; + + if (cmd == SET_PID_TARGET) { + arg1 = atol(argv1); + arg2 = atol(argv2); + } else { + arg1 = atoi(argv1); + arg2 = atoi(argv2); + } + + switch(cmd) { + case GET_BAUDRATE: + Serial.println(BAUDRATE); + break; + case ANALOG_READ: + Serial.println(analogRead(arg1)); + break; + case DIGITAL_READ: + Serial.println(digitalRead(arg1)); + break; + case ANALOG_WRITE: + analogWrite(arg1, arg2); + Serial.println("OK"); + break; + case DIGITAL_WRITE: + if (arg2 == 0) digitalWrite(arg1, LOW); + else if (arg2 == 1) digitalWrite(arg1, HIGH); + Serial.println("OK"); + break; + case PIN_MODE: + if (arg2 == 0) pinMode(arg1, INPUT); + else if (arg2 == 1) pinMode(arg1, OUTPUT); + Serial.println("OK"); + break; + case PING: + Serial.println(Ping(arg1)); + break; +#ifdef USE_SERVOS + case SERVO_WRITE: + servos[arg1].write(arg2); + Serial.println("OK"); + break; + case SERVO_READ: + Serial.println(servos[arg1].read()); + break; +#endif + +#ifdef USE_BASE + case READ_ENCODERS: + Serial.print(readEncoder(LEFT)); + Serial.print(" "); + Serial.println(readEncoder(RIGHT)); + break; + case RESET_ENCODERS: + resetEncoders(); + Serial.println("OK"); + break; + case MOTOR_SPEEDS: + /* Reset the auto stop timer */ + lastMotorCommand = millis(); + if (arg1 == 0 && arg2 == 0) { + setMotorSpeeds(0, 0); + moving = 0; + } + else moving = 1; + leftPID.TargetTicksPerFrame = arg1; + rightPID.TargetTicksPerFrame = arg2; + Serial.println("OK"); + break; + case UPDATE_PID: + while ((str = strtok_r(p, ":", &p)) != '\0') { + pid_args[i] = atoi(str); + i++; + } + Kp = pid_args[0]; + Kd = pid_args[1]; + Ki = pid_args[2]; + Ko = pid_args[3]; + Serial.println("OK"); + break; + case SET_PID_TARGET: + resetEncoders(); + leftMotorPIDTarget = arg1; + rightMotorPIDTarget = arg2; + leftPIDTargetComplete = 0; + rightPIDTargetComplete = 0; + Serial.println("OK"); + break; +#endif + default: + Serial.println("Invalid Command"); + break; + } +} + +/* Setup function--runs once at startup. */ +void setup() { + Serial.begin(BAUDRATE); + +// Initialize the motor controller if used */ +#ifdef USE_BASE + initMotorController(); +#endif + +/* Attach servos if used */ +#ifdef USE_SERVOS + int i; + for (i = 0; i < N_SERVOS; i++) { + servos[i].attach(servoPins[i]); + } +#endif +} + +/* Enter the main loop. Read and parse input from the serial port + and run any valid commands. Run a PID calculation at the target + interval and check for auto-stop conditions. +*/ +void loop() { + while (Serial.available() > 0) { + + // Read the next character + chr = Serial.read(); + + // Terminate a command with a CR + if (chr == 13) { + if (arg == 1) argv1[index] = NULL; + else if (arg == 2) argv2[index] = NULL; + runCommand(); + resetCommand(); + } + // Use spaces to delimit parts of the command + else if (chr == ' ') { + // Step through the arguments + if (arg == 0) arg = 1; + else if (arg == 1) { + argv1[index] = NULL; + arg = 2; + index = 0; + } + continue; + } + else { + if (arg == 0) { + // The first arg is the single-letter command + cmd = chr; + } + else if (arg == 1) { + // Subsequent arguments can be more than one character + argv1[index] = chr; + index++; + } + else if (arg == 2) { + argv2[index] = chr; + index++; + } + } + } + +// If we are using base control, run a PID calculation at the appropriate intervals +#ifdef USE_BASE + if (millis() > nextPID) { + updatePID(); + nextPID += PID_INTERVAL; + } + + // Check to see if we have exceeded the auto-stop interval + if ((millis() - lastMotorCommand) > AUTO_STOP_INTERVAL) {; + setMotorSpeeds(0, 0); + moving = 0; + } + +#endif +} + +// Variables to hold Encoder Targets - Keep moving until at this target +long leftMotorTarget; +long rightMotorTarget; +long targetError = 100; // How far away can I be before it is okay? Keeps jitter on low + +long targetLeftErrorMin; +long targetRightErrorMin; +long targetLeftErrorMax; +long targetRightErrorMax; +long rightToGo; // How far do we have left to go? +long leftToGo; +long leftSpeed; // How fast do we need to go to get there? +long rightSpeed; +long leftTargetComplete = 0; +long rightTargetComplete = 0; +long startSpeed = 35; // Acceleration starting value to break traction. +long endSpeed = 25; // Won't decelerate below this number +float accel = 0.05; // Acceleartion ramp value to get to top speed. +float decel = 0.01; // Deceleration value to slow down and stop without overshooting. + +void checkTargets() { + long leftEncoder = readEncoder(LEFT); + long rightEncoder = readEncoder(RIGHT); + + targetLeftErrorMin = leftMotorTarget - targetError; + targetRightErrorMin = rightMotorTarget - targetError; + targetLeftErrorMax = leftMotorTarget + targetError; + targetRightErrorMax = rightMotorTarget + targetError; + + if (leftTargetComplete == 0) { + if (leftEncoder <= targetLeftErrorMax && leftEncoder >= targetLeftErrorMin) { + if (leftTargetComplete == 0) { + leftTargetComplete = 1; + leftSpeed = 0; + leftPID.TargetTicksPerFrame = 0; + moving = 0; + } + } else { + if (leftEncoder >= leftMotorTarget) { + leftToGo = leftEncoder - leftMotorTarget; + leftSpeed = abs(leftToGo) * decel; + if (leftSpeed < EndSpeed) { leftSpeed = EndSpeed; } + if (leftEncoder <= 10000) { + if (leftEncoder < (StartSpeed * 20)) { + leftSpeed = StartSpeed; + } else { + leftSpeed = leftEncoder * accel; + } + } + if (leftSpeed > 500) { leftSpeed = 500; } + leftPID.TargetTicksPerFrame = leftSpeed; + moving = 1; + } else { + leftToGo = leftMotorTarget - leftEncoder; + leftSpeed = abs(leftToGo) * decel; + if (leftSpeed < EndSpeed) { leftSpeed = EndSpeed; } + if (leftEncoder < 10000) { + if (leftEncoder < (StartSpeed * 20)) { + leftSpeed = StartSpeed; + } else { + leftSpeed = leftEncoder * accel; + } + } + if (leftSpeed > 500) { leftSpeed = 500; } + leftPID.TargetTicksPerFrame = -leftSpeed; + moving = 1; + } + } + } + + if (RightTargetComplete == 0) { + if (rightEncoder <= targetRightErrorMax && rightEncoder >= targetRightErrorMin) { + if (RightTargetComplete == 0) { + RightTargetComplete = 1; + rightspeed = 0; + rightPID.TargetTicksPerFrame = 0; + moving = 0; + } + } else { + if (rightEncoder >= rightMotorTarget) { + rightToGo = rightEncoder - rightMotorTarget; + rightspeed = abs(rightToGo) * decel; + if(rightspeed < EndSpeed) { rightspeed = EndSpeed; } + if(rightEncoder <= 10000) { + if(rightEncoder < (StartSpeed * 20)) { + rightspeed = StartSpeed; + } else { + rightspeed = rightEncoder * accel; + } + } + if(rightspeed > 500) { rightspeed = 500; } + rightPID.TargetTicksPerFrame = rightspeed; + moving = 1; + } else { + rightToGo = rightMotorTarget - rightEncoder; + rightspeed = abs(rightToGo) * decel; + if (rightspeed < EndSpeed) { rightspeed = EndSpeed; } + if (rightEncoder < 10000) { + if (rightEncoder < (StartSpeed * 20)) { + rightspeed = StartSpeed; + } else { + rightspeed = rightEncoder * accel; + } + } + if (rightspeed > 500) { rightspeed = 500; } + rightPID.TargetTicksPerFrame = -rightspeed; + moving = 1; + } + } + } +} + + + + diff --git a/ros_arduino_python/nodes/arduino_node.py b/ros_arduino_python/nodes/arduino_node.py index e9c65f0..15f0ac5 100755 --- a/ros_arduino_python/nodes/arduino_node.py +++ b/ros_arduino_python/nodes/arduino_node.py @@ -85,7 +85,7 @@ class ArduinoROS(): rospy.loginfo("Connected to Arduino on port " + self.port + " at " + str(self.baud) + " baud") - # Reservce a thread lock + # Reserve a thread lock mutex = thread.allocate_lock() # Initialize any sensors From 91b80921e612ff48073571c39a0c313a49799d25 Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Sat, 17 Aug 2013 16:55:57 -0700 Subject: [PATCH 13/14] Deleted extraneous ROSArduinoBridge.cpp file --- .../ROSArduinoBridge/ROSArduinoBridge.cpp | 439 ------------------ 1 file changed, 439 deletions(-) delete mode 100644 ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.cpp diff --git a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.cpp b/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.cpp deleted file mode 100644 index 50d2076..0000000 --- a/ros_arduino_firmware/src/libraries/ROSArduinoBridge/ROSArduinoBridge.cpp +++ /dev/null @@ -1,439 +0,0 @@ -/********************************************************************* - * ROSArduinoBridge - - A set of simple serial commands to control a differential drive - robot and receive back sensor and odometry data. Default - configuration assumes use of an Arduino Mega + Pololu motor - controller shield + Robogaia Mega Encoder shield. Edit the - readEncoder() and setMotorSpeed() wrapper functions if using - different motor controller or encoder method. - - Created for the Pi Robot Project: http://www.pirobot.org - and the Home Brew Robotics Club (HBRC): http://hbrobotics.org - - Authors: Patrick Goebel, James Nugen - - Inspired and modeled after the ArbotiX driver by Michael Ferguson - - Software License Agreement (BSD License) - - Copyright (c) 2012, Patrick Goebel. - All rights reserved. - - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions - are met: - - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above - copyright notice, this list of conditions and the following - disclaimer in the documentation and/or other materials provided - with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -#define USE_BASE // Enable the base controller code -//#undef USE_BASE // Disable the base controller code - -/* Define the motor controller and encoder library you are using */ -#ifdef USE_BASE - /* The Pololu VNH5019 dual motor driver shield */ - #define POLOLU_VNH5019 - - /* The Pololu MC33926 dual motor driver shield */ - //#define POLOLU_MC33926 - - /* The RoboGaia encoder shield */ - #define ROBOGAIA -#endif - -//#define USE_SERVOS // Enable use of PWM servos as defined in servos.h -#undef USE_SERVOS // Disable use of PWM servos - -/* Serial port baud rate */ -#define BAUDRATE 57600 - -/* Maximum PWM signal */ -#define MAX_PWM 255 - -#if defined(ARDUINO) && ARDUINO >= 100 -#include "Arduino.h" -#else -#include "WProgram.h" -#endif - -/* Include definition of serial commands */ -#include "commands.h" - -/* Sensor functions */ -#include "sensors.h" - -/* Include servo support if required */ -#ifdef USE_SERVOS - #include - #include "servos.h" -#endif - -#ifdef USE_BASE - /* Motor driver function definitions */ - #include "motor_driver.h" - - /* Encoder driver function definitions */ - #include "encoder_driver.h" - - /* PID parameters and functions */ - #include "diff_controller.h" - - /* Run the PID loop at 30 times per second */ - #define PID_RATE 30 // Hz - - /* Convert the rate into an interval */ - const int PID_INTERVAL = 1000 / PID_RATE; - - /* Track the next time we make a PID calculation */ - unsigned long nextPID = PID_INTERVAL; - - /* Stop the robot if it hasn't received a movement command - in this number of milliseconds */ - #define AUTO_STOP_INTERVAL 2000 - long lastMotorCommand = AUTO_STOP_INTERVAL; -#endif - -/* Variable initialization */ - -// A pair of varibles to help parse serial commands (thanks Fergs) -int arg = 0; -int index = 0; - -// Variable to hold an input character -char chr; - -// Variable to hold the current single-character command -char cmd; - -// Character arrays to hold the first and second arguments -char argv1[16]; -char argv2[16]; - -// The arguments converted to integers -long arg1; -long arg2; - -/* Clear the current command parameters */ -void resetCommand() { - cmd = NULL; - memset(argv1, 0, sizeof(argv1)); - memset(argv2, 0, sizeof(argv2)); - arg1 = 0; - arg2 = 0; - arg = 0; - index = 0; -} - -/* Run a command. Commands are defined in commands.h */ -int runCommand() { - int i = 0; - char *p = argv1; - char *str; - int pid_args[4]; - - if (cmd == SET_PID_TARGET) { - arg1 = atol(argv1); - arg2 = atol(argv2); - } else { - arg1 = atoi(argv1); - arg2 = atoi(argv2); - } - - switch(cmd) { - case GET_BAUDRATE: - Serial.println(BAUDRATE); - break; - case ANALOG_READ: - Serial.println(analogRead(arg1)); - break; - case DIGITAL_READ: - Serial.println(digitalRead(arg1)); - break; - case ANALOG_WRITE: - analogWrite(arg1, arg2); - Serial.println("OK"); - break; - case DIGITAL_WRITE: - if (arg2 == 0) digitalWrite(arg1, LOW); - else if (arg2 == 1) digitalWrite(arg1, HIGH); - Serial.println("OK"); - break; - case PIN_MODE: - if (arg2 == 0) pinMode(arg1, INPUT); - else if (arg2 == 1) pinMode(arg1, OUTPUT); - Serial.println("OK"); - break; - case PING: - Serial.println(Ping(arg1)); - break; -#ifdef USE_SERVOS - case SERVO_WRITE: - servos[arg1].write(arg2); - Serial.println("OK"); - break; - case SERVO_READ: - Serial.println(servos[arg1].read()); - break; -#endif - -#ifdef USE_BASE - case READ_ENCODERS: - Serial.print(readEncoder(LEFT)); - Serial.print(" "); - Serial.println(readEncoder(RIGHT)); - break; - case RESET_ENCODERS: - resetEncoders(); - Serial.println("OK"); - break; - case MOTOR_SPEEDS: - /* Reset the auto stop timer */ - lastMotorCommand = millis(); - if (arg1 == 0 && arg2 == 0) { - setMotorSpeeds(0, 0); - moving = 0; - } - else moving = 1; - leftPID.TargetTicksPerFrame = arg1; - rightPID.TargetTicksPerFrame = arg2; - Serial.println("OK"); - break; - case UPDATE_PID: - while ((str = strtok_r(p, ":", &p)) != '\0') { - pid_args[i] = atoi(str); - i++; - } - Kp = pid_args[0]; - Kd = pid_args[1]; - Ki = pid_args[2]; - Ko = pid_args[3]; - Serial.println("OK"); - break; - case SET_PID_TARGET: - resetEncoders(); - leftMotorPIDTarget = arg1; - rightMotorPIDTarget = arg2; - leftPIDTargetComplete = 0; - rightPIDTargetComplete = 0; - Serial.println("OK"); - break; -#endif - default: - Serial.println("Invalid Command"); - break; - } -} - -/* Setup function--runs once at startup. */ -void setup() { - Serial.begin(BAUDRATE); - -// Initialize the motor controller if used */ -#ifdef USE_BASE - initMotorController(); -#endif - -/* Attach servos if used */ -#ifdef USE_SERVOS - int i; - for (i = 0; i < N_SERVOS; i++) { - servos[i].attach(servoPins[i]); - } -#endif -} - -/* Enter the main loop. Read and parse input from the serial port - and run any valid commands. Run a PID calculation at the target - interval and check for auto-stop conditions. -*/ -void loop() { - while (Serial.available() > 0) { - - // Read the next character - chr = Serial.read(); - - // Terminate a command with a CR - if (chr == 13) { - if (arg == 1) argv1[index] = NULL; - else if (arg == 2) argv2[index] = NULL; - runCommand(); - resetCommand(); - } - // Use spaces to delimit parts of the command - else if (chr == ' ') { - // Step through the arguments - if (arg == 0) arg = 1; - else if (arg == 1) { - argv1[index] = NULL; - arg = 2; - index = 0; - } - continue; - } - else { - if (arg == 0) { - // The first arg is the single-letter command - cmd = chr; - } - else if (arg == 1) { - // Subsequent arguments can be more than one character - argv1[index] = chr; - index++; - } - else if (arg == 2) { - argv2[index] = chr; - index++; - } - } - } - -// If we are using base control, run a PID calculation at the appropriate intervals -#ifdef USE_BASE - if (millis() > nextPID) { - updatePID(); - nextPID += PID_INTERVAL; - } - - // Check to see if we have exceeded the auto-stop interval - if ((millis() - lastMotorCommand) > AUTO_STOP_INTERVAL) {; - setMotorSpeeds(0, 0); - moving = 0; - } - -#endif -} - -// Variables to hold Encoder Targets - Keep moving until at this target -long leftMotorTarget; -long rightMotorTarget; -long targetError = 100; // How far away can I be before it is okay? Keeps jitter on low - -long targetLeftErrorMin; -long targetRightErrorMin; -long targetLeftErrorMax; -long targetRightErrorMax; -long rightToGo; // How far do we have left to go? -long leftToGo; -long leftSpeed; // How fast do we need to go to get there? -long rightSpeed; -long leftTargetComplete = 0; -long rightTargetComplete = 0; -long startSpeed = 35; // Acceleration starting value to break traction. -long endSpeed = 25; // Won't decelerate below this number -float accel = 0.05; // Acceleartion ramp value to get to top speed. -float decel = 0.01; // Deceleration value to slow down and stop without overshooting. - -void checkTargets() { - long leftEncoder = readEncoder(LEFT); - long rightEncoder = readEncoder(RIGHT); - - targetLeftErrorMin = leftMotorTarget - targetError; - targetRightErrorMin = rightMotorTarget - targetError; - targetLeftErrorMax = leftMotorTarget + targetError; - targetRightErrorMax = rightMotorTarget + targetError; - - if (leftTargetComplete == 0) { - if (leftEncoder <= targetLeftErrorMax && leftEncoder >= targetLeftErrorMin) { - if (leftTargetComplete == 0) { - leftTargetComplete = 1; - leftSpeed = 0; - leftPID.TargetTicksPerFrame = 0; - moving = 0; - } - } else { - if (leftEncoder >= leftMotorTarget) { - leftToGo = leftEncoder - leftMotorTarget; - leftSpeed = abs(leftToGo) * decel; - if (leftSpeed < EndSpeed) { leftSpeed = EndSpeed; } - if (leftEncoder <= 10000) { - if (leftEncoder < (StartSpeed * 20)) { - leftSpeed = StartSpeed; - } else { - leftSpeed = leftEncoder * accel; - } - } - if (leftSpeed > 500) { leftSpeed = 500; } - leftPID.TargetTicksPerFrame = leftSpeed; - moving = 1; - } else { - leftToGo = leftMotorTarget - leftEncoder; - leftSpeed = abs(leftToGo) * decel; - if (leftSpeed < EndSpeed) { leftSpeed = EndSpeed; } - if (leftEncoder < 10000) { - if (leftEncoder < (StartSpeed * 20)) { - leftSpeed = StartSpeed; - } else { - leftSpeed = leftEncoder * accel; - } - } - if (leftSpeed > 500) { leftSpeed = 500; } - leftPID.TargetTicksPerFrame = -leftSpeed; - moving = 1; - } - } - } - - if (RightTargetComplete == 0) { - if (rightEncoder <= targetRightErrorMax && rightEncoder >= targetRightErrorMin) { - if (RightTargetComplete == 0) { - RightTargetComplete = 1; - rightspeed = 0; - rightPID.TargetTicksPerFrame = 0; - moving = 0; - } - } else { - if (rightEncoder >= rightMotorTarget) { - rightToGo = rightEncoder - rightMotorTarget; - rightspeed = abs(rightToGo) * decel; - if(rightspeed < EndSpeed) { rightspeed = EndSpeed; } - if(rightEncoder <= 10000) { - if(rightEncoder < (StartSpeed * 20)) { - rightspeed = StartSpeed; - } else { - rightspeed = rightEncoder * accel; - } - } - if(rightspeed > 500) { rightspeed = 500; } - rightPID.TargetTicksPerFrame = rightspeed; - moving = 1; - } else { - rightToGo = rightMotorTarget - rightEncoder; - rightspeed = abs(rightToGo) * decel; - if (rightspeed < EndSpeed) { rightspeed = EndSpeed; } - if (rightEncoder < 10000) { - if (rightEncoder < (StartSpeed * 20)) { - rightspeed = StartSpeed; - } else { - rightspeed = rightEncoder * accel; - } - } - if (rightspeed > 500) { rightspeed = 500; } - rightPID.TargetTicksPerFrame = -rightspeed; - moving = 1; - } - } - } -} - - - - From 481760bd42c7a5a6c157cde5f951aee5fdda2603 Mon Sep 17 00:00:00 2001 From: Patrick Goebel Date: Sat, 17 Aug 2013 17:15:43 -0700 Subject: [PATCH 14/14] Removed unused self.shutdown variable in arduino_driver.py --- ros_arduino_python/src/arduino_driver.py | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/ros_arduino_python/src/arduino_driver.py b/ros_arduino_python/src/arduino_driver.py index 8eedc8c..f210d14 100755 --- a/ros_arduino_python/src/arduino_driver.py +++ b/ros_arduino_python/src/arduino_driver.py @@ -171,8 +171,7 @@ class Arduino: attempts += 1 except: self.mutex.release() - if not self.shutdown: - print "Exception executing command: " + cmd + print "Exception executing command: " + cmd value = None self.mutex.release() @@ -205,8 +204,7 @@ class Arduino: except: self.mutex.release() print "Exception executing command: " + cmd - if not self.shutdown: - raise SerialException + raise SerialException return [] try: @@ -243,9 +241,8 @@ class Arduino: attempts += 1 except: self.mutex.release() - if not self.shutdown: - print "execute_ack exception when executing", cmd - print sys.exc_info() + print "execute_ack exception when executing", cmd + print sys.exc_info() return 0 self.mutex.release()