浏览代码

提交代码

corvin 4 年之前
父节点
当前提交
a2ffc8ca3b
共有 44 个文件被更改,包括 2323 次插入0 次删除
  1. 598 0
      src/ros_arduino_bridge/README.md
  2. 4 0
      src/ros_arduino_bridge/ros_arduino_bridge/CMakeLists.txt
  3. 21 0
      src/ros_arduino_bridge/ros_arduino_bridge/package.xml
  4. 46 0
      src/ros_arduino_bridge/ros_arduino_msgs/CMakeLists.txt
  5. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/msg/Analog.msg
  6. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/msg/AnalogFloat.msg
  7. 5 0
      src/ros_arduino_bridge/ros_arduino_msgs/msg/ArduinoConstants.msg
  8. 4 0
      src/ros_arduino_bridge/ros_arduino_msgs/msg/Digital.msg
  9. 4 0
      src/ros_arduino_bridge/ros_arduino_msgs/msg/SensorState.msg
  10. 20 0
      src/ros_arduino_bridge/ros_arduino_msgs/package.xml
  11. 2 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogFloatSensorRead.srv
  12. 2 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogFloatSensorWrite.srv
  13. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogPinMode.srv
  14. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogRead.srv
  15. 2 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogSensorRead.srv
  16. 2 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogSensorWrite.srv
  17. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogWrite.srv
  18. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalPinMode.srv
  19. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalRead.srv
  20. 2 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalSensorPinMode.srv
  21. 2 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalSensorRead.srv
  22. 2 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalSensorWrite.srv
  23. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalSetDirection.srv
  24. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalWrite.srv
  25. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/Enable.srv
  26. 2 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/Relax.srv
  27. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/ServoAttach.srv
  28. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/ServoDetach.srv
  29. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/ServoRead.srv
  30. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/ServoWrite.srv
  31. 3 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/SetServoSpeed.srv
  32. 2 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/SetSpeed.srv
  33. 5 0
      src/ros_arduino_bridge/ros_arduino_msgs/srv/UpdatePID.srv
  34. 26 0
      src/ros_arduino_bridge/ros_arduino_python/CMakeLists.txt
  35. 23 0
      src/ros_arduino_bridge/ros_arduino_python/cfg/ROSArduinoBridge.cfg
  36. 61 0
      src/ros_arduino_bridge/ros_arduino_python/config/my_arduino_params.yaml
  37. 13 0
      src/ros_arduino_bridge/ros_arduino_python/launch/arduino.launch
  38. 176 0
      src/ros_arduino_bridge/ros_arduino_python/nodes/arduino_node.py
  39. 32 0
      src/ros_arduino_bridge/ros_arduino_python/package.xml
  40. 11 0
      src/ros_arduino_bridge/ros_arduino_python/setup.py
  41. 0 0
      src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/__init__.py
  42. 601 0
      src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/arduino_driver.py
  43. 290 0
      src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/arduino_sensors.py
  44. 320 0
      src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/base_controller.py

+ 598 - 0
src/ros_arduino_bridge/README.md

@@ -0,0 +1,598 @@
+For ROS Kinetic, Ubuntu 16.04 and Python2 (might work with ROS Indigo and Ubuntu 14.04)
+
+Table of Contents
+=================
+
+* [Overview](#overview)
+* [Official ROS Documentation](#official-ros-documentation)
+* [System Requirements](#system-requirements)
+* [Hardware Requirements](#hardware-requirements)
+* [Preparing your Serial Port under Linux](#preparing-your-serial-port-under-linux)
+* [Installation of the ros_arduino_bridge Stack](#installation-of-the-ros_arduino_bridge-stack)
+* [Loading the ROSArduinoBridge Sketch](#loading-the-rosarduinobridge-sketch)
+* [Firmware Commands](#firmware-commands)
+* [Testing your Wiring Connections](#testing-your-wiring-connections)
+* [Configuring the ros_arduino_python Node](#configuring-the-ros_arduino_python-node)
+* [Launching the ros_arduino_python Node](#launching-the-ros_arduino_python-node)
+* [Viewing Sensor Data](#viewing-sensor-data)
+* [Sending Twist Commands and Viewing Odometry Data](#sending-twist-commands-and-viewing-odometry-data)
+* [ROS Services for Sensors and Servos](#ros-services-for-sensors-and-servos)
+* [ROS Joint Topics and Services](#ros-joint-topics-and-services)
+* [Using the on-board wheel encoder counters (Arduino Uno only)](#using-the-on-board-wheel-encoder-counters-arduino-uno-only)
+* [Running without a Base Controller](#running-without-a-base-controller)
+
+Overview
+--------
+This branch (kinetic-devel) is intended for ROS Kinetic and above, and uses the catkin buildsystem. It may also be compatible with ROS Indigo.
+
+This ROS metapackage 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.
+
+Features of the package include:
+
+* Direct support for Ping sonar and Sharp infrared (GP2D12) sensors
+
+* Can also read data from generic analog and digital sensors
+
+* Can control digital outputs (e.g. turn a switch or LED on and off)
+
+* Support for PWM servos
+
+* Configurable base controller for a differential drive mobile robot including support for encoders if using the required hardware (see [Hardware](#Hardware) below)
+
+* ROS diagnostics messages published for each attached sensor
+
+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
+-------------------
+**ROS Dependencies**
+
+    $ sudo apt-get install ros-kinetic-diagnostic-updater ros-kinetic-control-msgs ros-kinetic-nav-msgs
+
+**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
+
+**Arduino IDE 1.6.6 or Higher:**
+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.
+
+Hardware Requirements
+---------------------
+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 below.
+If you do not have this hardware, you can still try the package for reading sensors and controlling servos.  See [Running without a Base Controller](#unning-without-a-base-controller) at the end of this document for instructions on how to do this.
+
+The base controller requires the use of a motor controller and encoders for reading odometry data.  The current version of the package provides support for the following motor controller and encoder hardware:
+
+* Robogaia 3-axis Encoder shield (Compatible with Arduino Mega, Due, Uno)
+(https://www.robogaia.com/3-axis-encoder-conter-arduino-shield.html)
+
+* Mega Moto Controller (http://www.robotshop.com/en/arduino-compatible-mega-motor-shield-1a-5-28v.html)
+
+* Arduino R3 Motor Controller (http://arduino.cc/en/Main/ArduinoMotorShieldR3 [without the brake capability])
+
+* Instead of the Encoder shield, wheel encoders can be [connected directly](#using-the-on-board-wheel-encoder-counters-arduino-uno-only) (**NOTE:** The on-board wheel encoder counters are currently only supported by Arduino Uno.)
+
+* The library can be easily extended to include support for other motor controllers and encoder hardware or libraries.
+
+To use the base controller you must also install the appropriate libraries for your motor controller and encoders.
+
+The Robogaia Mega Encoder library can be found at:
+
+http://www.robogaia.com/uploads/6/8/0/9/6809982/__megaencodercounter-1.3.tar.gz
+
+Please see the website for the supported motor controllers above for library support.
+
+These libraries should be installed in your standard Arduino
+sketchbook/libraries directory.
+
+Finally, it is assumed you are using version 1.6.6 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:
+
+    $ 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 2018-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 Package
+----------------------------------------------
+
+    $ cd ~/catkin_workspace/src
+    $ git clone https://github.com/hbrobotics/ros_arduino_bridge.git
+    $ cd ~/catkin_workspace
+    $ catkin_make
+
+The provided Arduino library is called ROSArduinoBridge and is
+located in the ros\_arduino\_firmware package.  This sketch is
+specific to the hardware requirements above but it can also be used
+with other Arduino-type boards (e.g. Uno) by turning off the base
+controller as described in the NOTES section at the end of this
+document.
+
+To install the ROSArduinoBridge library, follow these steps:
+
+    $ cd SKETCHBOOK_PATH
+
+where SKETCHBOOK_PATH is the path to your Arduino sketchbook directory.
+
+    $ \cp -rp  `rospack find ros_arduino_firmware`/src/libraries/ROSArduinoBridge -T ROSArduinoBridge
+
+This last command copies the ROSArduinoBridge sketch files into your sketchbook folder and overwrites any existing files with the same name.  The next section describes how to configure, compile and upload this sketch.
+
+
+Loading the ROSArduinoBridge Sketch
+-----------------------------------
+
+* 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.
+
+* Launch the Arduino IDE and load the ROSArduinoBridge sketch.
+  You should be able to find it by going to:
+
+    File->Sketchbook->ROSArduinoBridge
+  
+**NOTE:** If you have the required hardware to use the base controller, uncomment the line that looks like this:
+
+<pre>
+//#define USE_BASE
+</pre>
+
+so it looks like this:
+
+<pre>
+#define USE_BASE
+</pre>
+
+You will also need to choose one of the supported motor controllers by uncommenting its #define statement and commenting out any others.  By default, the Adafruit Motor Driver v2.3 is chosen.
+
+Choose a supported encoder library by by uncommenting its #define statement and commenting out any others.  At the moment, the two options are the Robogaia Mega Encoder shield (chosen by default) and the directo connection ARDUINO_ENC_COUNTER option that works for Arduino Uno compatible boards.
+
+By default, the sketch will provide support to control PWM servos attached to your Arduino.  If you do not need servo support, you can comment out the line that looks like this:
+
+<pre>
+#define USE_SERVOS2
+</pre>
+
+so that it looks like this:
+
+<pre>
+//#define USE_SERVOS2
+</pre>
+
+
+* Compile and upload the sketch to your Arduino.
+
+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:
+
+<pre>
+#define ANALOG_READ    'a'
+#define GET_BAUDRATE   'b'
+#define PIN_MODE       'c'
+#define DIGITAL_READ   'd'
+#define READ_ENCODERS  'e'
+#define CONFIG_SERVO   'j'
+#define MOTOR_SPEEDS   'm'
+#define PING           'p'
+#define RESET_ENCODERS 'r'
+#define SERVO_WRITE    's'
+#define SERVO_READ     't'
+#define UPDATE_PID     'u'
+#define SERVO_DELAY    'v'
+#define DIGITAL_WRITE  'w'
+#define ANALOG_WRITE   'x'
+#define ATTACH_SERVO   'y'
+#define DETACH_SERVO   'z'
+#define LEFT            0
+#define RIGHT           1
+</pre>
+
+For example, to get the analog reading on pin 3, use the command:
+
+a 3
+
+To change the mode of digital pin 3 to OUTPUT, send the command:
+
+c 3 1
+
+To get the current encoder counts:
+
+e
+
+To move the robot forward at 20 encoder ticks per second:
+
+m 20 20
+
+To intialize a PWM servo on pin 3 with speed delay 100ms:
+
+j 3 100
+
+To move the servo on pin 3 to position 120 degrees:
+
+s 3 120
+
+To detach servo on pin 3:
+
+z 3
+
+
+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.
+
+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.
+
+
+Configuring the ros\_arduino\_python Node
+-----------------------------------------
+Now that your Arduino is running the required sketch, you can
+configure the ROS side of things on your PC.  You define your robot's
+dimensions, PID parameters, and sensor configuration by editing the
+YAML file in the directory ros\_arduino\_python/config.  So first move
+into that directory:
+
+    $ roscd ros_arduino_python/config
+
+Now copy the provided config file to one you can modify:
+
+    $ 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:
+
+<pre>
+port: /dev/ttyUSB0
+baud: 57600
+timeout: 0.1
+
+rate: 50
+sensorstate_rate: 10
+
+use_base_controller: False
+base_controller_rate: 10
+
+# === Robot drivetrain parameters
+#wheel_diameter: 0.146
+#wheel_track: 0.2969
+#encoder_resolution: 8384 # from Pololu for 131:1 motors
+#gear_reduction: 1.0
+#motors_reversed: True
+
+# === PID parameters
+#Kp: 20
+#Kd: 12
+#Ki: 0
+#Ko: 50
+#accel_limit: 1.0
+
+# === Sensor definitions.  Examples only - edit for your robot.
+#     Sensor type can be one of the follow (case sensitive!):
+#	  * Ping
+#	  * GP2D12
+#	  * Analog
+#	  * Digital
+#	  * PololuMotorCurrent
+#	  * PhidgetsVoltage
+#	  * PhidgetsCurrent (20 Amp, DC)
+
+sensors: {
+  #motor_current_left:   {pin: 0, type: PololuMotorCurrent, rate: 5},
+  #motor_current_right:  {pin: 1, type: PololuMotorCurrent, rate: 5},
+  #ir_front_center:      {pin: 2, type: GP2D12, rate: 10},
+  #sonar_front_center:   {pin: 5, type: Ping, rate: 10},
+  onboard_led:           {pin: 13, type: Digital, rate: 5, direction: output}
+}
+
+# Joint name and configuration is an example only
+joints: {
+    head_pan_joint: {pin: 3, init_position: 0, init_speed: 90, neutral: 90, min_angle: -90, max_angle: 90, invert: False, continous: False},
+    head_tilt_joint: {pin: 5, init_position: 0, init_speed: 90, neutral: 90, min_angle: -90, max_angle: 90, invert: False, continous: False}
+}
+
+
+</pre>
+
+**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.
+
+Let's now look at each section of this file.
+
+ _Port Settings_
+
+The port will likely be either /dev/ttyACM0 or /dev/ttyUSB0. Set accordingly.
+
+The MegaRobogaiaPololu Arudino sketch connects at 57600 baud by default.
+
+_Polling Rates_
+
+The main *rate* parameter (50 Hz by default) determines how fast the
+outside ROS loop runs.  The default should suffice in most cases.  In
+any event, it should be at least as fast as your fastest sensor rate
+(defined below).
+
+The *sensorstate\_rate* determines how often to publish an aggregated
+list of all sensor readings.  Each sensor also publishes on its own
+topic and rate.
+
+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.
+
+The *base\_controller\_rate* determines how often to publish odometry readings.
+
+_Defining Sensors_
+
+The *sensors* parameter defines a dictionary of sensor names and
+sensor parameters. (You can name each sensor whatever you like but
+remember that the name for a sensor will also become the topic name
+for that sensor.)
+
+The four most important parameters are *pin*, *type*, *rate* and *direction*.
+The *rate* defines how many times per second you want to poll that
+sensor.  For example, a voltage sensor might only be polled once a
+second (or even once every 2 seconds: rate=0.5), whereas a sonar
+sensor might be polled at 20 times per second.  The *type* must be one
+of those listed (case sensitive!).  The default *direction* is input so
+to define an output pin, set the direction explicitly to output.  In
+the example above, the Arduino LED (pin 13) will be turned on and off
+at a rate of 2 times per second.
+
+_Defining Servo Configurations_
+
+The *joints* parameter defines a dictionary of joint names and servo parameters.  (You can name each joint whatever you like but rememember that joint names will become part of the servo's ROS topic and service names.)
+
+The most important parameter is *pin* which of course must match the pin the servo attaches to on your Arduino.  Most PWM servos operate from 0 to 180 degrees with a "neutral" point of 90 degrees. ROS uses radians instead of degrees for joint positions but it is usually easier for programmers to specify the angular limits in the config file using degrees.  The ROS Arduino Bridge pacakge takes care of the conversion to radians.  An *init_position* of 0 therefore means 0 degrees relative to the neutral point of 90 degrees.  A *max_angle* of 90 degrees maps into 180 degrees at the servo. 
+
+_Setting Drivetrain and PID Parameters_
+
+To use the base controller, you will have to uncomment and set the
+robot drivetrain and PID parameters.  The sample drivetrain parameters
+are for 6" drive wheels that are 11.5" apart.  Note that ROS uses
+meters for distance so convert accordingly.  The sample encoder
+resolution (ticks per revolution) is from the specs for the Pololu
+131:1 motor.  Set the appropriate number for your motor/encoder
+combination.  Set the motors_reversed to True if you find your wheels
+are turning backward, otherwise set to False.
+
+The PID parameters are trickier to set.  You can start with the sample
+values but be sure to place your robot on blocks before sending it
+your first Twist command.
+
+Launching the ros\_arduino\_python Node
+---------------------------------------
+Take a look at the launch file arduino.launch in the
+ros\_arduino\_python/launch directory.  As you can see, it points to a
+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\_arduino\_python node with your parameters:
+
+    $ roslaunch ros_arduino_python arduino.launch
+
+You should see something like the following output:
+
+<pre>
+process[arduino-1]: started with pid [6098]
+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]
+etc
+</pre>
+
+If you have any Ping sonar sensors on your robot and you defined them
+in your config file, they should start flashing to indicate you have
+made the connection.
+
+Viewing Sensor Data
+-------------------
+To see the aggregated sensor data, echo the sensor state topic:
+
+    $ 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
+its data using:
+
+    $ 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
+
+
+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} }'
+
+The wheels should turn in a direction consistent with a
+counter-clockwise rotation (right wheel forward, left wheel backward).
+If they turn in the opposite direction, set the motors_reversed
+parameter in your config file to the opposite of its current setting,
+then kill and restart the arduino.launch file.
+
+Stop the robot with the command:
+
+    $ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{}'
+
+To view odometry data:
+
+    $ rostopic echo /odom
+
+or
+
+   $ rxplot -p 60 /odom/pose/pose/position/x:y, /odom/twist/twist/linear/x, /odom/twist/twist/angular/z
+
+ROS Services for Sensors and Servos
+-----------------------------------
+The ros\_arduino\_python package also defines a few ROS services for sensors and servos as follows:
+
+**digital\_set\_direction** - set the direction of a digital pin
+
+    $ 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
+
+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
+
+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).
+
+**servo\_read** - read the position of a servo
+
+    $ rosservice call /arduino/servo_read id
+
+where id is the index of the servo as defined in the Arduino sketch (servos.h)
+
+ROS Joint Topics and Services
+-----------------------------
+At the ROS level, a servo is called a joint and each joint has its own topics and services.  To change the position of a joint, publish the position
+in radians to the topic:
+
+**/\<joint_name\>/command**
+
+For example, a joint called head_pan_joint in the YAML config file can be controlled using the topic:
+
+**/head_pan_joint/command**
+
+which takes a Float64 argument specifying the desired position in radians.  For example, the command:
+
+    $ rostopic pub -1 /head_pan_joint/command std_msgs/Float64 -- 1.0
+
+will move the servo to angle 1.0 radians from the neutral point; i.e. about 147 degrees when using the default neutral point of 90 degrees.  Using a negative value moves the servo in the other direction:
+
+    $ rostopic pub -1 /head_pan_joint/command std_msgs/Float64 -- -1.0
+
+A number of services are also available for each joint:
+
+**/\<joint_name\>/enable** - Enable or disable a joint.  Disabling also detachs the underlying servo so that it can be moved by hand.
+
+    $ rosservice call /head_pan_joint/enable false
+
+**/\<joint_name\>/relax** - Another way to detach the underlying servo so that it can be moved by hand.
+
+    $ rosservice call /head_pan_joint/relax
+
+**/\<joint_name\>/set_speed** - Set the movement speed of servo in radians per second.
+
+    $ rosservice call /head_pan_joint/set_speed 1.0
+
+
+Using the on-board wheel encoder counters (Arduino Uno only)
+------------------------------------------------------------
+The firmware supports on-board wheel encoder counters for Arduino Uno.
+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).
+
+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.)
+
+To use the on-board wheel encoder counters, connect your wheel encoders to Arduino Uno as follows:
+
+    Left wheel encoder A output -- Arduino UNO pin 2
+    Left wheel encoder B output -- Arduino UNO pin 3
+
+    Right wheel encoder A output -- Arduino UNO pin A4
+    Right wheel encoder B output -- Arduino UNO pin A5
+
+Make the following changes in the ROSArduinoBridge sketch to disable the RoboGaia encoder shield, and enable the on-board one:
+
+    /* The RoboGaia encoder shield */
+    //#define ROBOGAIA
+    /* Encoders directly attached to Arduino board */
+    #define ARDUINO_ENC_COUNTER
+
+Compile the changes and upload to your controller.
+
+
+Running without a Base Controller
+---------------------------------
+If you do not have the hardware required to run the base controller,
+follow the instructions below so that you can still use your
+Arduino-compatible controller to read sensors and control PWM servos.
+
+First, you need to edit the ROSArduinoBridge sketch. At the top of
+the file, comment out the line that looks like this:
+
+<pre>
+#define USE_BASE
+</pre>
+
+so it looks like this:
+
+<pre>
+//#define USE_BASE
+</pre>
+
+(You may find that it is already commented out.)
+
+**NOTE:** If you are using a version of the Arduino IDE earlier than 1.6.6, then you also need to comment out the line that looks like this in the file encoder_driver.ino:
+
+    #include "MegaEncoderCounter.h"
+
+so it looks like this:
+
+    //#include "MegaEncoderCounter.h"
+
+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.

+ 4 - 0
src/ros_arduino_bridge/ros_arduino_bridge/CMakeLists.txt

@@ -0,0 +1,4 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(ros_arduino_bridge)
+find_package(catkin REQUIRED)
+catkin_metapackage()

+ 21 - 0
src/ros_arduino_bridge/ros_arduino_bridge/package.xml

@@ -0,0 +1,21 @@
+<package>
+  <name>ros_arduino_bridge</name>
+  <version>0.2.0</version>
+  <description>
+    Metapackage for ros_arduino_bridge. 
+  </description>
+  <author>Patrick Goebel</author>
+  <maintainer email="patrick@pirobot.org">Patrick Goebel</maintainer>
+  <license>BSD</license>
+  <url>http://ros.org/wiki/ros_arduino_bridge</url>
+  
+  <buildtool_depend>catkin</buildtool_depend>
+
+  <run_depend>ros_arduino_firmware</run_depend>
+  <run_depend>ros_arduino_msgs</run_depend>
+  <run_depend>ros_arduino_python</run_depend>
+
+  <export>
+   <metapackage/>
+  </export>
+</package>

+ 46 - 0
src/ros_arduino_bridge/ros_arduino_msgs/CMakeLists.txt

@@ -0,0 +1,46 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(ros_arduino_msgs)
+
+find_package(catkin REQUIRED COMPONENTS std_msgs message_generation)
+
+add_message_files(FILES
+                  AnalogFloat.msg
+                  Analog.msg
+                  ArduinoConstants.msg
+                  Digital.msg
+                  SensorState.msg
+                 )
+
+add_service_files(FILES
+                  AnalogWrite.srv
+                  AnalogSensorWrite.srv
+                  AnalogFloatSensorWrite.srv
+                  AnalogPinMode.srv           
+                  AnalogRead.srv
+                  AnalogSensorRead.srv
+                  AnalogFloatSensorRead.srv
+                  DigitalPinMode.srv
+                  DigitalRead.srv
+                  DigitalSensorRead.srv
+                  DigitalSetDirection.srv
+                  DigitalSensorPinMode.srv
+                  DigitalWrite.srv
+                  DigitalSensorWrite.srv
+                  Enable.srv
+                  Relax.srv
+                  AnalogSensorRead.srv
+                  ServoAttach.srv
+                  ServoDetach.srv
+                  ServoRead.srv
+                  ServoWrite.srv
+                  SetSpeed.srv
+                  SetServoSpeed.srv
+                  UpdatePID.srv
+                 )
+
+generate_messages(   
+	DEPENDENCIES  
+	std_msgs  
+)  
+
+catkin_package(CATKIN_DEPENDS message_runtime std_msgs)

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/msg/Analog.msg

@@ -0,0 +1,3 @@
+# Reading from a single analog IO pin.
+Header header
+uint16 value

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/msg/AnalogFloat.msg

@@ -0,0 +1,3 @@
+# Float message from a single analog IO pin.
+Header header
+float32 value

+ 5 - 0
src/ros_arduino_bridge/ros_arduino_msgs/msg/ArduinoConstants.msg

@@ -0,0 +1,5 @@
+# Arduino-style constants
+uint8 LOW=0
+uint8 HIGH=1
+uint8 INPUT=0
+uint8 OUTPUT=1

+ 4 - 0
src/ros_arduino_bridge/ros_arduino_msgs/msg/Digital.msg

@@ -0,0 +1,4 @@
+# Reading on a digital pin
+Header header
+uint8 value
+

+ 4 - 0
src/ros_arduino_bridge/ros_arduino_msgs/msg/SensorState.msg

@@ -0,0 +1,4 @@
+Header header
+
+string[] name
+float32[] value

+ 20 - 0
src/ros_arduino_bridge/ros_arduino_msgs/package.xml

@@ -0,0 +1,20 @@
+<package>
+  <name>ros_arduino_msgs</name>
+  <version>0.2.0</version>
+  <description>
+    ROS Arduino Messages.
+  </description>
+  <author>Patrick Goebel</author>
+  <maintainer email="patrick@pirobot.org">Patrick Goebel</maintainer>
+  <license>BSD</license>
+  <url>http://ros.org/wiki/ros_arduino_msgs</url>
+  
+  <buildtool_depend>catkin</buildtool_depend>
+
+  <build_depend>message_generation</build_depend>
+  <build_depend>std_msgs</build_depend>
+
+  <run_depend>message_runtime</run_depend>
+  <run_depend>std_msgs</run_depend>
+  
+</package>

+ 2 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogFloatSensorRead.srv

@@ -0,0 +1,2 @@
+---
+float32 value

+ 2 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogFloatSensorWrite.srv

@@ -0,0 +1,2 @@
+float32 value
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogPinMode.srv

@@ -0,0 +1,3 @@
+uint8 pin
+bool direction
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogRead.srv

@@ -0,0 +1,3 @@
+uint8 pin
+---
+uint16 value

+ 2 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogSensorRead.srv

@@ -0,0 +1,2 @@
+---
+uint16 value

+ 2 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogSensorWrite.srv

@@ -0,0 +1,2 @@
+uint16 value
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/AnalogWrite.srv

@@ -0,0 +1,3 @@
+uint8 pin
+uint16 value
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalPinMode.srv

@@ -0,0 +1,3 @@
+uint8 pin
+bool direction
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalRead.srv

@@ -0,0 +1,3 @@
+uint8 pin
+---
+bool value

+ 2 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalSensorPinMode.srv

@@ -0,0 +1,2 @@
+bool direction
+---

+ 2 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalSensorRead.srv

@@ -0,0 +1,2 @@
+---
+bool value

+ 2 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalSensorWrite.srv

@@ -0,0 +1,2 @@
+bool value
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalSetDirection.srv

@@ -0,0 +1,3 @@
+uint8 pin
+bool direction
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/DigitalWrite.srv

@@ -0,0 +1,3 @@
+uint8 pin
+bool value
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/Enable.srv

@@ -0,0 +1,3 @@
+bool enable
+---
+bool state

+ 2 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/Relax.srv

@@ -0,0 +1,2 @@
+
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/ServoAttach.srv

@@ -0,0 +1,3 @@
+uint8 id
+---
+

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/ServoDetach.srv

@@ -0,0 +1,3 @@
+uint8 id
+---
+

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/ServoRead.srv

@@ -0,0 +1,3 @@
+uint8 id
+---
+uint8 position

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/ServoWrite.srv

@@ -0,0 +1,3 @@
+uint8 id
+uint8 position
+---

+ 3 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/SetServoSpeed.srv

@@ -0,0 +1,3 @@
+uint8 id
+float32 speed
+---

+ 2 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/SetSpeed.srv

@@ -0,0 +1,2 @@
+float32 speed
+---

+ 5 - 0
src/ros_arduino_bridge/ros_arduino_msgs/srv/UpdatePID.srv

@@ -0,0 +1,5 @@
+float32 Kp
+float32 Kd
+float32 Ki
+float32 Ko
+---

+ 26 - 0
src/ros_arduino_bridge/ros_arduino_python/CMakeLists.txt

@@ -0,0 +1,26 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(ros_arduino_python)
+
+find_package(catkin REQUIRED dynamic_reconfigure)
+
+catkin_python_setup()
+
+generate_dynamic_reconfigure_options(cfg/ROSArduinoBridge.cfg)
+
+catkin_package(DEPENDS)
+
+catkin_package(CATKIN_DEPENDS dynamic_reconfigure)
+
+install(DIRECTORY config
+  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
+
+install(DIRECTORY launch
+  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
+
+install(DIRECTORY nodes
+  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
+
+

+ 23 - 0
src/ros_arduino_bridge/ros_arduino_python/cfg/ROSArduinoBridge.cfg

@@ -0,0 +1,23 @@
+#! /usr/bin/env python
+
+PACKAGE = "ros_arduino_python"
+
+from dynamic_reconfigure.parameter_generator_catkin import *
+
+gen = ParameterGenerator()
+
+gen.add("Kp", double_t, 0, "Kp - Proportional", 10.0, 0.0, 50.0)
+
+gen.add("Kd", double_t, 0, "Kd - Differential", 12.0, 0.0, 50.0)
+
+gen.add("Ki", double_t, 0, "Ki - Integral", 0.0, 0.0, 10.0)
+
+gen.add("Ko", double_t, 0, "Ko - Offset", 50.0, 0.0, 100.0)
+
+gen.add("accel_limit", double_t, 0, "Acceleration limit", 1.0, 0.0, 10.0)
+
+gen.add("odom_linear_scale_correction", double_t, 0, "Linear Scale Correction", 1.0, 0.0, 2.0)
+
+gen.add("odom_angular_scale_correction", double_t, 0, "Angular Scale Correction", 1.0, 0.0, 2.0)
+
+exit(gen.generate(PACKAGE, "ros_arduino_bridge", "ROSArduinoBridge"))

+ 61 - 0
src/ros_arduino_bridge/ros_arduino_python/config/my_arduino_params.yaml

@@ -0,0 +1,61 @@
+# Copyright: 2016-2020 www.corvin.cn ROS小课堂
+# Description:arduino节点运行时加载的参数,下面对参数进行解释:
+#   is_use_serial:与arduino通信是否使用串口,false的话就是IIC通信
+#   serial_port:串口通信时arduino的端口号
+#   serial_baud:串口通信时波特率
+#   i2c_smbus_num:系统管理总线号,树莓派为1
+#   isc_slave_addr:arduino的IIC设备地址
+# Author: corvin
+# History:
+#   20200706:init this file.
+
+is_use_serial: True
+
+# /dev/ttyACM# where is # is a number such as 0, 1 etc
+serial_port: /dev/ttyACM0
+serial_baud: 57600
+
+i2c_smbus_num: 1   #raspberryPi:1, huawei altals 200DK: 2
+i2c_slave_addr: 0x08  #Get arduino due i2c slave addr
+
+timeout: 0.5
+
+rate: 25
+
+cmd_topic: cmd_vel
+
+base_controller_rate: 10.0
+base_controller_timeout: 0.7
+
+# For a robot that uses base_footprint, change base_frame to base_footprint
+base_frame: base_footprint
+odom_name: odom
+
+# Robot drivetrain parameters
+wheel_diameter: 0.065
+wheel_track: 0.15     #L value
+encoder_resolution: 13 #12V DC motors
+gear_reduction: 30     #empty payload rpm 130 r/m
+linear_scale_correction: 1.028
+angular_scale_correction: 1.00
+
+# === PID parameters
+debugPID: False
+
+accel_limit: 0.05
+
+AWheel_Kp: 22
+AWheel_Kd: 30
+AWheel_Ki: 0
+AWheel_Ko: 50
+
+BWheel_Kp: 22
+BWheel_Kd: 30
+BWheel_Ki: 0
+BWheel_Ko: 50
+
+# Sensor definitions (case sensitive!):
+sensors: {
+  batPercent: {pin: 0, type: BAT_PERCENT, rate: 0.1, direction: input},
+}
+

+ 13 - 0
src/ros_arduino_bridge/ros_arduino_python/launch/arduino.launch

@@ -0,0 +1,13 @@
+<!--
+  Copyright: 2016-2020 ROS小课堂 www.corvin.cn
+  Description:
+    启动底盘arduino的上位机launch文件.
+  Author: corvin
+  History:
+    20200706: init this file.
+-->
+<launch>
+   <node name="mobilebase_arduino" pkg="ros_arduino_python" type="arduino_node.py" output="screen" required="true">
+      <rosparam file="$(find ros_arduino_python)/config/my_arduino_params.yaml" command="load" />
+   </node>
+</launch>

+ 176 - 0
src/ros_arduino_bridge/ros_arduino_python/nodes/arduino_node.py

@@ -0,0 +1,176 @@
+#!/usr/bin/env python
+#_*_ coding:utf-8 _*_
+
+"""
+  Copyright:2016-2020 www.corvin.cn ROS小课堂
+  Description: A ROS Node for the Arduino microcontroller
+  Author: corvin
+  History:
+    20200706:init this file.
+"""
+import os
+import rospy
+import thread
+from ros_arduino_msgs.srv import *
+from geometry_msgs.msg import Twist
+from serial.serialutil import SerialException
+from ros_arduino_python.arduino_sensors import *
+from ros_arduino_python.arduino_driver import Arduino
+from ros_arduino_python.base_controller import BaseController
+
+class ArduinoROS():
+    def __init__(self):
+        rospy.init_node('mobilebase_arduino_node', log_level=rospy.INFO)
+
+        # Get the actual node name in case it is set in the launch file
+        self.name = rospy.get_name()
+
+        # Cleanup when termniating the node
+        rospy.on_shutdown(self.shutdown)
+
+        self.is_use_serial = rospy.get_param("~is_use_serial", True)
+
+        self.serial_port = rospy.get_param("~serial_port", "/dev/ttyACM0")
+        self.serial_baud = int(rospy.get_param("~serial_baud", 57600))
+        self.i2c_smbus_num = rospy.get_param("~i2c_smbus_num", 1)
+        self.i2c_slave_addr = rospy.get_param("~i2c_slave_addr", 8)
+        self.timeout    = rospy.get_param("~timeout", 0.7)
+        self.base_frame = rospy.get_param("~base_frame", 'base_footprint')
+
+        # Overall loop rate: should be faster than fastest sensor rate
+        self.rate = int(rospy.get_param("~rate", 25))
+        loop_rate = rospy.Rate(self.rate)
+
+        # Initialize a Twist message
+        self.cmd_vel = Twist()
+
+        # A cmd_vel publisher so we can stop the robot when shutting down
+        self.cmd_vel_pub = rospy.Publisher('cmd_vel', Twist, queue_size=20)
+
+        # A service to turn set the direction of a digital pin (0 = input, 1 = output)
+        rospy.Service('~digital_set_direction', DigitalSetDirection, self.DigitalSetDirectionHandler)
+
+        # A service to turn a digital sensor on or off
+        rospy.Service('~digital_write', DigitalWrite, self.DigitalWriteHandler)
+
+        # A service to read the value of a digital sensor
+        rospy.Service('~digital_read', DigitalRead, self.DigitalReadHandler)
+
+        # A service to set pwm values for the pins
+        rospy.Service('~analog_write', AnalogWrite, self.AnalogWriteHandler)
+
+        # A service to read the value of an analog sensor
+        rospy.Service('~analog_read', AnalogRead, self.AnalogReadHandler)
+
+        # Initialize the controlller
+        self.controller = Arduino(self.is_use_serial, self.serial_port, self.serial_baud, self.i2c_smbus_num, self.i2c_slave_addr, self.timeout)
+
+        # Make the connection
+        self.controller.connect()
+
+        # Reserve a thread lock
+        mutex = thread.allocate_lock()
+
+        # Initialize any sensors
+        self.mySensors = list()
+        sensor_params = rospy.get_param("~sensors", dict({}))
+
+        for name, params in sensor_params.iteritems():
+            # Set the direction to input if not specified
+            try:
+                params['direction']
+            except:
+                params['direction'] = 'input'
+
+            if params['type'] == "GP2Y0A41":
+                sensor = GP2Y0A41(self.controller, name, params['pin'], params['rate'], self.base_frame)
+            elif params['type'] == "IR2Y0A02":
+                sensor = IR2Y0A02(self.controller, name, params['pin'], params['rate'], self.base_frame)
+            elif params['type'] == 'Digital':
+                sensor = DigitalSensor(self.controller, name, params['pin'], params['rate'], self.base_frame, direction=params['direction'])
+            elif params['type'] == 'Analog':
+                sensor = AnalogSensor(self.controller, name, params['pin'], params['rate'], self.base_frame, direction=params['direction'])
+            elif params['type'] == 'BAT_PERCENT':
+                sensor = BatPercent(self.controller, name, params['pin'], params['rate'], self.base_frame)
+            elif params['type'] == 'MotorTotalCurrent':
+                sensor = MotorTotalCurrent(self.controller, name, params['pin'], params['rate'], self.base_frame)
+            elif params['type'] == "US025":
+                sensor = US025(self.controller, name, params['pin'], params['rate'], self.base_frame)
+
+            try:
+                self.mySensors.append(sensor)
+                rospy.loginfo(name + " " + str(params) + " published on topic " + "/sensor/" + name)
+            except:
+                rospy.logerr("Sensor type " + str(params['type']) + " not recognized.")
+
+        # Initialize the base controller
+        self.myBaseController = BaseController(self.is_use_serial, self.controller, self.base_frame, self.name + "_base_controller")
+
+        # Start polling the sensors and base controller
+        while not rospy.is_shutdown():
+            mutex.acquire()
+            self.myBaseController.poll()
+            mutex.release()
+
+            for sensor in self.mySensors:
+                mutex.acquire()
+                sensor.poll()
+                mutex.release()
+
+            loop_rate.sleep()
+
+    def DigitalSetDirectionHandler(self, req):
+        self.controller.pin_mode(req.pin, req.direction)
+        return DigitalSetDirectionResponse()
+
+    def DigitalWriteHandler(self, req):
+        self.controller.digital_write(req.pin, req.value)
+        return DigitalWriteResponse()
+
+    def DigitalReadHandler(self, req):
+        value = self.controller.digital_read(req.pin)
+        return DigitalReadResponse(value)
+
+    def AnalogWriteHandler(self, req):
+        self.controller.analog_write(req.pin, req.value)
+        return AnalogWriteResponse()
+
+    def AnalogReadHandler(self, req):
+        value = self.controller.analog_read(req.pin)
+        return AnalogReadResponse(value)
+
+    def AlarmWriteHandler(self, req):
+        self.controller.alarm_write(req.value)
+        return AlarmWriteResponse()
+
+    def LightShowHandler(self, req):
+        self.controller.light_show(req.value)
+        return LightShowResponse()
+
+    # Stop the robot
+    def shutdown(self):
+        rospy.logwarn("Shutting down Arduino Node...")
+        try:
+            rospy.logwarn("Stopping the robot move...")
+            self.cmd_vel_pub.Publish(Twist())
+        except:
+            pass
+
+        # Close the serial port or IIC
+        try:
+            self.controller.close()
+        except:
+            pass
+        finally:
+            os._exit(0)
+
+if __name__ == '__main__':
+    try:
+        myArduino = ArduinoROS()
+    except SerialException:
+        rospy.logerr("ERROR trying to open serial port.")
+        os._exit(0)
+    else:
+        rospy.logerr("Get other unknown error !")
+        os._exit(0)
+

+ 32 - 0
src/ros_arduino_bridge/ros_arduino_python/package.xml

@@ -0,0 +1,32 @@
+<package>
+  <name>ros_arduino_python</name>
+  <version>0.2.0</version>
+  <description>
+    ROS Arduino Python.
+  </description>
+  <author>Patrick Goebel</author>
+  <maintainer email="patrick@pirobot.org">Patrick Goebel</maintainer>
+  <license>BSD</license>
+  <url>http://ros.org/wiki/ros_arduino_python</url>
+  
+  <buildtool_depend>catkin</buildtool_depend>
+  
+  <build_depend>dynamic_reconfigure</build_depend>
+  <build_depend>diagnostic_updater</build_depend>
+  <build_depend>diagnostic_aggregator</build_depend>
+  <build_depend>diagnostic_msgs</build_depend>
+
+  <run_depend>rospy</run_depend>
+  <run_depend>std_msgs</run_depend>
+  <run_depend>sensor_msgs</run_depend>
+  <run_depend>geometry_msgs</run_depend>
+  <run_depend>nav_msgs</run_depend>
+  <run_depend>diagnostic_msgs</run_depend>
+  <run_depend>diagnostic_updater</run_depend>
+  <run_depend>diagnostic_aggregator</run_depend>
+  <run_depend>tf</run_depend>
+  <run_depend>ros_arduino_msgs</run_depend>
+  <run_depend>python-serial</run_depend>
+  <run_depend>dynamic_reconfigure</run_depend>
+
+</package>

+ 11 - 0
src/ros_arduino_bridge/ros_arduino_python/setup.py

@@ -0,0 +1,11 @@
+#!/usr/bin/env python
+
+from distutils.core import setup
+from catkin_pkg.python_setup import generate_distutils_setup
+
+d = generate_distutils_setup(
+    packages=['ros_arduino_python'],
+    package_dir={'': 'src'},
+    )
+
+setup(**d)

+ 0 - 0
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/__init__.py


+ 601 - 0
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/arduino_driver.py

@@ -0,0 +1,601 @@
+#!/usr/bin/env python
+#-*- coding:utf-8 -*-
+
+"""
+  Copyright: 2016-2020 ROS小课堂 www.corvin.cn
+  Description: A Python driver for the Arduino microcontroller.
+  Author: corvin, jally
+  History:
+    20200706:创建代码.
+"""
+from serial.serialutil import SerialException
+import thread, smbus, rospy, time, os
+from serial import Serial
+import sys, traceback
+import numpy as np
+import roslib, rospy
+
+
+class Arduino:
+    ''' Configuration Arduino DUE Board Parameters
+    '''
+    N_ANALOG_PORTS  = 10
+    N_DIGITAL_PORTS = 54
+
+    def __init__(self, is_use_serial,serial_port="/dev/ttyACM0",baudrate=57600,i2c_smbus_num=1,i2c_slave_addr=8,timeout=0.5):
+        self.PID_RATE = 40   #Don't change this ! It is a fixed property of the Arduino PID controller.
+        self.PID_INTERVAL = 25
+
+        self.is_use_serial = is_use_serial #与下位机arduino的通信方式是否使用串口还是IIC
+        self.serial_port = serial_port
+        self.baudrate    = baudrate
+
+        self.i2c_smbus_num  = i2c_smbus_num
+        self.i2c_slave_addr = i2c_slave_addr
+
+        self.timeout = timeout
+
+        self.encoder_count    = 0
+        self.writeTimeout     = timeout
+        self.interCharTimeout = timeout/30.
+
+        # Keep things thread safe
+        self.mutex = thread.allocate_lock()
+
+        # An array to cache analog sensor readings
+        self.analog_sensor_cache = [None] * self.N_ANALOG_PORTS
+
+        # An array to cache digital sensor readings
+        self.digital_sensor_cache = [None] * self.N_DIGITAL_PORTS
+
+    def connect(self):
+        if self.is_use_serial:
+            self.serial_connect()
+        else:
+            self.i2c_bus = smbus.SMBus(self.i2c_smbus_num)
+            self.i2c_connect()
+
+    def serial_connect(self):
+        try:
+            rospy.loginfo("Connecting to Arduino on port: " + self.serial_port)
+            self.serial_port = Serial(port=self.serial_port, baudrate=self.baudrate, timeout=self.timeout, writeTimeout=self.writeTimeout)
+            # The next line is necessary to give the firmware time to wake up.
+            time.sleep(1)
+            test = self.get_baud()
+            if test != self.baudrate:
+                time.sleep(1)
+                test = self.get_baud()
+                if test != self.baudrate:
+                    raise SerialException
+
+            self.beep_ring(1)
+            rospy.loginfo("Arduino connected baudrate: "+str(self.baudrate))
+        except SerialException:
+            rospy.logerr("Cannot connect to Arduino !")
+            rospy.logerr(sys.exc_info())
+            rospy.logerr(traceback.print_exc(file=sys.stdout))
+            os._exit(1)
+
+    def i2c_connect(self):
+        try:
+            rospy.loginfo("Connecting to Arduino on IIC addr:"+str(self.i2c_slave_addr))
+            test = self.i2c_get_baud()
+            #test2 = self.getCurrentValue()
+            #test3 = self.getBatPercent()
+            #test4 = self.detect_distance()
+            #test5 = self.analog_read(1)
+            #test6 = self.digital_read(10)
+            #test7 = self.i2c_get_pidin()
+            #test8 = self.i2c_get_encoder_counts()
+            #print test8
+            if test != self.baudrate:
+                time.sleep(1)
+                test = self.i2c_get_baud()
+                if test != self.baudrate:
+                    raise Exception
+
+            self.beep_ring(2)
+            rospy.sleep(0.1)
+            self.beep_ring(3)
+            rospy.sleep(0.05)
+            self.beep_ring(2)
+            rospy.sleep(0.1)
+            self.beep_ring(3)
+            rospy.loginfo("Arduino is connected by IIC !")
+        except Exception:
+            rospy.logerr(sys.exc_info())
+            rospy.logerr(traceback.print_exc(file=sys.stdout))
+            rospy.logerr("Cannot connect to Arduino IIC slave addr !")
+            os._exit(1)
+
+    def open(self):
+        ''' Open the serial port.
+        '''
+        self.serial_port.open()
+
+    def close(self):
+        ''' Close the serial port or i2c bus connect.
+        '''
+        self.beep_ring(2)
+        rospy.sleep(0.5)
+        self.beep_ring(3)
+        if self.is_use_serial:
+            self.serial_port.close()
+        else:
+            self.i2c_bus.close()
+
+    def send(self, cmd):
+        ''' This command should not be used on its own: it is called by the execute commands
+            below in a thread safe manner.
+        '''
+        self.serial_port.write(cmd + '\r')
+
+    def recv(self, timeout=0.5):
+        timeout = min(timeout, self.timeout)
+        ''' This command should not be used on its own: it is called by the execute commands
+            below in a thread safe manner
+        '''
+        c = ''
+        value = ''
+        attempts = 0
+
+        while c != '\r':
+            c = self.serial_port.read(1)
+            value += c
+            attempts += 1
+            if attempts * self.interCharTimeout > timeout:
+                return None
+
+        value = value.strip('\r')
+        return value
+
+    def recv_ack(self):
+        ''' This command should not be used on its own: it is called by the execute commands
+            below in a thread safe manner.
+        '''
+        ack = self.recv(self.timeout)
+        return ack == 'OK'
+
+    def recv_int(self):
+        ''' This command should not be used on its own: it is called by the execute commands
+            below in a thread safe manner.
+        '''
+        value = self.recv(self.timeout)
+        try:
+            return int(value)
+        except:
+            return None
+
+    def recv_array(self):
+        ''' This command should not be used on its own: it is called by the execute commands
+            below in a thread safe manner.
+        '''
+        try:
+            values = self.recv(self.timeout * self.N_ANALOG_PORTS).split()
+            return map(float, values)
+        except:
+            return []
+
+    def execute(self, cmd):
+        ''' Thread safe execution of "cmd" on the Arduino returning a single integer value.
+        '''
+        self.mutex.acquire()
+
+        try:
+            self.serial_port.flushInput()
+        except:
+            pass
+
+        ntries   = 1
+        attempts = 0
+        try:
+            self.serial_port.write(cmd + '\r')
+            value = self.recv(self.timeout)
+            while attempts < ntries and (value == '' or value == 'Invalid Command' or value == None):
+                try:
+                    self.serial_port.flushInput()
+                    self.serial_port.write(cmd + '\r')
+                    value = self.recv(self.timeout)
+                except:
+                    rospy.logerr("Exception executing command: " + cmd)
+                attempts += 1
+        except:
+            self.mutex.release()
+            rospy.logerr("Exception executing command: " + cmd)
+            value = None
+
+        self.mutex.release()
+        return value
+
+    def execute_array(self, cmd):
+        ''' Thread safe execution of "cmd" on the Arduino returning an float array.
+        '''
+        self.mutex.acquire()
+        try:
+            self.serial_port.flushInput()
+        except:
+            pass
+
+        ntries   = 1
+        attempts = 0
+        try:
+            self.serial_port.write(cmd + '\r')
+            values = self.recv_array()
+            while attempts < ntries and (values == '' or values == 'Invalid Command' or values == [] or values == None):
+                try:
+                    self.serial_port.flushInput()
+                    self.serial_port.write(cmd + '\r')
+                    values = self.recv_array()
+                except:
+                    rospy.logerr("Exception executing command: " + cmd)
+                attempts += 1
+        except:
+            self.mutex.release()
+            rospy.logerr("Exception executing command: " + cmd)
+            raise SerialException
+            return []
+
+        try:
+            values = map(float, values)
+        except:
+            values = []
+
+        self.mutex.release()
+        return values
+
+    def execute_ack(self, cmd):
+        ''' Thread safe execution of "cmd" on the Arduino returning True if response is ACK.
+        '''
+        self.mutex.acquire()
+
+        try:
+            self.serial_port.flushInput()
+        except:
+            pass
+
+        ntries   = 1
+        attempts = 0
+        try:
+            self.serial_port.write(cmd + '\r')
+            ack = self.recv(self.timeout)
+            while attempts < ntries and (ack == '' or ack == 'Invalid Command' or ack == None):
+                try:
+                    self.serial_port.flushInput()
+                    self.serial_port.write(cmd + '\r')
+                    ack = self.recv(self.timeout)
+                except:
+                    rospy.logerr("Exception executing command: " + cmd)
+                attempts += 1
+        except:
+            self.mutex.release()
+            rospy.logerr("execute_ack exception when executing" + cmd)
+            rospy.logerr(sys.exc_info())
+            return 0
+
+        self.mutex.release()
+        return ack == 'OK'
+
+    def update_pid(self, AWheel_Kp, AWheel_Kd, AWheel_Ki, AWheel_Ko,
+                         BWheel_Kp, BWheel_Kd, BWheel_Ki, BWheel_Ko ):
+        ''' Set the PID parameters on the Arduino by serial
+        '''
+        rospy.loginfo("Updating Motors PID parameters ...")
+        cmd = 'u '+str(AWheel_Kp)+':'+str(AWheel_Kd)+':'+str(AWheel_Ki)+':'+str(AWheel_Ko)+':'+str(BWheel_Kp)+':'+str(BWheel_Kd)+':'+str(BWheel_Ki)+':'+str(BWheel_Ko)
+        self.execute_ack(cmd)
+        #rospy.loginfo("pid params now:"+cmd)
+
+    def i2c_update_pid(self, AWheel_Kp, AWheel_Kd, AWheel_Ki, AWheel_Ko,
+                         BWheel_Kp, BWheel_Kd, BWheel_Ki, BWheel_Ko):
+        rospy.loginfo("Updating PID parameters by IIC")
+
+    def get_baud(self):
+        ''' Get the current baud rate on the serial port.
+        '''
+        try:
+            return int(self.execute('b'));
+        except:
+            return None
+
+    def i2c_get_baud(self):
+        ''' Get the current baud rate on the arduino IIC addr.
+        '''
+        try:
+            #rospy.loginfo("i2c_slave_addr:"+str(self.i2c_slave_addr))
+            self.i2c_bus.write_byte(self.i2c_slave_addr, ord('b'))
+            #if the program ends here, maybe I/O error, please check $ sudo i2cdetect -y -a 1
+            #if 0x08 does not exist all the time or the refresh is so slow, please reset arduino DUE
+            self.i2c_bus.write_byte(self.i2c_slave_addr, ord('\r'))
+            time.sleep(0.1)
+            values = self.i2c_bus.read_i2c_block_data(self.i2c_slave_addr, 0, 5)
+            values = map(chr, values)
+            ret = ''.join(values)
+            #print "ret:"+ret
+            return int(ret)
+        except:
+            rospy.loginfo("get baud failed !")
+            return None
+
+    def get_encoder_counts(self):
+        values = self.execute_array('e')
+        if len(values) != 2:
+            rospy.logerr("Encoder count was not 2")
+            raise SerialException
+            return None
+        else:
+            return values
+
+    def i2c_get_encoder_counts(self):
+        #print "IIC Get Encoder count !"
+
+        try:
+            self.i2c_bus.write_byte(self.i2c_slave_addr, int(ord('e')))
+            self.i2c_bus.write_byte(self.i2c_slave_addr, ord('\r'))
+
+            result_array = self.i2c_bus.read_i2c_block_data(self.i2c_slave_addr, 0x08)
+            #There are result_flag valid bytes.
+            result_flag = result_array.index(120)
+            #rospy.loginfo("Valid bytes: "+str(result_flag))
+            #extract result_flag bytes as strings
+            result_string=''.join([chr(ec) for ec in result_array[0:(result_flag-1)]])
+            #extract encoder_counts by space
+            values=[int(s) for s in result_string.split(" ")]
+            if len(values) != 2:
+                rospy.logwarn("Encoder count was not 2")
+                return None
+            else:
+                #rospy.loginfo("Encoder counts now: "+ str(values))
+                return values
+        except:
+            rospy.logerr(sys.exe_info())
+            traceback.print_exc(file=sys.stdout)
+            return None
+
+
+
+    def reset_encoders(self):
+        ''' Reset the encoder counts to 0 by serial port
+        '''
+        return self.execute_ack('r')
+
+    def i2c_reset_encoders(self):
+        ''' Reset the encoder counts to 0 by IIC
+        '''
+        try:
+            self.i2c_bus.write_byte(self.i2c_slave_addr, ord('r'))
+            self.i2c_bus.write_byte(self.i2c_slave_addr, ord('\r'))
+            rospy.loginfo("Reset encoders sucessfully")
+        except:
+            return None
+
+    def drive(self, AWheel, BWheel):
+        ''' Speeds are given in encoder ticks per PID interval
+        '''
+        #rospy.loginfo("drive() A:" + str(AWheel) + ",B:" + str(BWheel))
+        return self.execute_ack('m %d %d' %(AWheel, BWheel))
+
+    def i2c_drive(self, AWheel, BWheel):
+        ''' Speeds are given in encoder ticks per PID interval
+        '''
+        #rospy.loginfo("drive() A:" + str(AWheel) + ",B:" + str(BWheel))
+        cmd = (' %d %d\r' %(AWheel, BWheel))
+        try:
+            self.i2c_bus.write_i2c_block_data(self.i2c_slave_addr, ord('m'), [ord(c) for c in cmd])
+        except:
+            return None
+
+    def stop(self):
+        ''' Stop all three motors.
+        '''
+        self.drive(0, 0)
+
+    def i2c_stop(self):
+        cmd = (' 0 0\r')
+        try:
+            self.i2c_bus.write_i2c_block_data(self.i2c_slave_addr, ord('m'), [ord(c) for c in cmd])
+        except:
+            return None
+
+    def analog_read(self, pin):
+        if self.is_use_serial:
+            return self.execute('a %d' %pin)
+        else:
+            cmd = (' %d\r' %(pin))
+            try:
+                self.i2c_bus.write_i2c_block_data(self.i2c_slave_addr, ord('a'), [ord(c) for c in cmd])
+                pin = self.i2c_bus.read_i2c_block_data(self.i2c_slave_addr, 0, 3)
+                pin = map(chr, pin)
+                ret = ''.join(pin)
+                #print "ret:"+ret
+                return int(ret)
+            except:
+                return None
+
+    def analog_write(self, pin, value):
+        if self.is_use_serial:
+            return self.execute_ack('x %d %d' %(pin, value))
+        else:
+            cmd = (' %d %d\r' %(pin, value))
+            try:
+                self.i2c_bus.write_i2c_block_data(self.i2c_slave_addr, ord('x'), [ord(c) for c in cmd])
+            except:
+                return None
+
+    def digital_read(self, pin):
+        if self.is_use_serial:
+            return self.execute('d %d' %pin)
+        else:
+            cmd = (' %d\r' %(pin))
+            try:
+                self.i2c_bus.write_i2c_block_data(self.i2c_slave_addr, ord('d'), [ord(c) for c in cmd])
+                pin = self.i2c_bus.read_i2c_block_data(self.i2c_slave_addr, 0, 2)
+                pin = map(chr, pin)
+                #print pin
+                ret = ''.join(pin)
+                #print "ret:"+ret
+                return int(ret)
+            except:
+                return None
+
+    def digital_write(self, pin, value):
+        if self.is_use_serial:
+            return self.execute_ack('w %d %d' %(pin, value))
+        else:
+            cmd = (' %d %d\r' %(pin, value))
+            try:
+                self.i2c_bus.write_i2c_block_data(self.i2c_slave_addr, ord('w'), [ord(c) for c in cmd])
+            except:
+                return None
+
+    def pin_mode(self, pin, mode):
+        if self.is_use_serial:
+            return self.execute_ack('c %d %d' %(pin, mode))
+        else:
+            cmd = (' %d %d\r' %(pin, mode))
+            try:
+                self.i2c_bus.write_i2c_block_data(self.i2c_slave_addr, ord('c'), [ord(c) for c in cmd])
+            except:
+                return None
+
+    def beep_ring(self, value):
+        if self.is_use_serial:
+            return self.execute_ack('p %d' %value)
+        else:
+            cmd = (' %d\r' %(value))
+            try:
+                self.i2c_bus.write_i2c_block_data(self.i2c_slave_addr, ord('p'), [ord(c) for c in cmd])
+            except:
+                return None
+
+    def getBatPercent(self):
+        '''get the remaining power percentage
+        '''
+        if self.is_use_serial:
+            percent = self.execute('g')
+            #rospy.loginfo("Bat percent:" + str(percent))
+            return percent
+        else:
+            try:
+                self.i2c_bus.write_byte(self.i2c_slave_addr, ord('g'))
+                self.i2c_bus.write_byte(self.i2c_slave_addr, ord('\r'))
+                percent = self.i2c_bus.read_i2c_block_data(self.i2c_slave_addr, 0, 3)
+                percent = map(chr, percent)
+                ret = ''.join(percent)
+                #print "ret:"+ret
+                return int(ret)
+            except:
+                return None
+
+    def get_pidin(self):
+        values = self.execute_array('i')
+        if len(values) != 2:
+            rospy.logerr("pidin was not 2")
+            raise SerialException
+            return None
+        else:
+            return values
+
+    def i2c_get_pidin(self):
+        rospy.loginfo("IIC Get Pidin !")
+        ch = ''
+        values = ''
+        cnt = 0
+        cmd = "\r"
+
+        try:
+            self.i2c_bus.write_byte(self.i2c_slave_addr, int(ord('i')))
+            self.i2c_bus.write_byte(self.i2c_slave_addr, ord('\r'))
+
+            result_array3 = self.i2c_bus.read_i2c_block_data(self.i2c_slave_addr, 0x08)
+            print result_array
+            #There are result_flag valid bytes.
+            result_flag3 = result_array.index(120)
+            #print result_flag3
+            #rospy.loginfo("Valid bytes: "+str(result_flag))
+            #extract result_flag bytes as strings
+            result_string3=''.join([chr(ch) for ch in result_array3[0:(result_flag3-1)]])
+            #print result_string3
+            #extract Pidin_counts by space
+            values=[int(s) for s in result_string3.split(" ")]
+            if len(values) != 2:
+                rospy.logwarn("Pidin was not 2")
+                return None
+            else:
+                #rospy.loginfo("Pidin now: "+ str(values))
+                return values
+        except:
+            rospy.logerr(sys.exe_info())
+            traceback.print_exc(file=sys.stdout)
+            return None
+
+    def get_pidout(self):
+        values = self.execute_array('o')
+        if len(values) != 2:
+            rospy.logerr("pidout was not 2")
+            raise SerialException
+            return None
+        else:
+            return values
+
+    def i2c_get_pidout(self):
+        rospy.loginfo("IIC Get Pidout !")
+        ch = ''
+        values = ''
+        cnt = 0
+        cmd = "\r"
+
+        try:
+            self.i2c_bus.write_byte(self.i2c_slave_addr, int(ord('o')))
+            self.i2c_bus.write_byte(self.i2c_slave_addr, ord('\r'))
+
+            result_array4 = self.i2c_bus.read_i2c_block_data(self.i2c_slave_addr, 0x08)
+            print result_array
+            #There are result_flag valid bytes.
+            result_flag4 = result_array.index(120)
+            #print result_flag4
+            #rospy.loginfo("Valid bytes: "+str(result_flag))
+            #extract result_flag bytes as strings
+            result_string4=''.join([chr(ch) for ch in result_array4[0:(result_flag4-1)]])
+            #print result_string4
+            #extract Pidout_counts by space
+            values=[int(s) for s in result_string4.split(" ")]
+            if len(values) != 2:
+                rospy.logwarn("Pidout was not 2")
+                return None
+            else:
+                #rospy.loginfo("Pidout now: "+ str(values))
+                return values
+        except:
+            rospy.logerr(sys.exe_info())
+            traceback.print_exc(file=sys.stdout)
+            return None
+
+""" Basic test for connectivity by serial port or IIC bus"""
+if __name__ == "__main__":
+    is_use_serial = True
+    portName = "/dev/ttyACM0"
+    baudRate = 57600
+
+    iic_smbus = 1
+    iic_num = 8
+
+    myArduino = Arduino(is_use_serial, serial_port=portName, baudrate=baudRate, i2c_smbus_num=iic_smbus, i2c_slave_addr=iic_num, timeout=0.5)
+    myArduino.connect()
+
+    rospy.loginfo("Sleeping for 1 second...")
+    time.sleep(1)
+
+    rospy.loginfo("Test Beep ring 3 times...")
+    for i in range(3):
+        myArduino.beep_ring(1)
+        time.sleep(2.0)
+
+    rospy.loginfo("Did you heard the beep ring ?")
+    rospy.loginfo("Now print infrared sensors value:")
+    values = myArduino.detect_distance()
+    distances = np.array([values[0], values[1], values[2]])
+    rospy.loginf(distances/100.0)
+
+    myArduino.stop()
+    myArduino.close()
+    rospy.logwarn("Shutting down Arduino !")
+

+ 290 - 0
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/arduino_sensors.py

@@ -0,0 +1,290 @@
+#!/usr/bin/env python
+#_*_ coding:utf-8 _*_
+
+"""
+    Sensor class for the arudino_python package
+    History:
+        20200330:增加获取电池剩余电量函数.
+        20200423:增加获取电流函数
+"""
+import roslib; roslib.load_manifest('ros_arduino_python')
+import rospy
+import numpy as np
+from decimal import Decimal
+from sensor_msgs.msg import Range
+from ros_arduino_msgs.msg import *
+
+
+LOW = 0
+HIGH = 1
+
+INPUT = 0
+OUTPUT = 1
+
+class MessageType:
+    ANALOG     = 0
+    DIGITAL    = 1
+    INFRARED   = 2
+    RANGE      = 3
+    FLOAT      = 4
+    INT        = 5
+    BOOL       = 6
+    ULTRASONIC = 7
+
+class Sensor(object):
+    def __init__(self, controller, name, pin, rate, frame_id, direction="input", **kwargs):
+        self.controller = controller
+        self.name = name
+        self.pin = pin
+        self.rate = rate
+        self.direction = direction
+
+        self.frame_id = frame_id
+        self.value = None
+
+        self.t_delta = rospy.Duration(1.0 / self.rate)
+        self.t_next = rospy.Time.now() + self.t_delta
+
+
+    def poll(self):
+        now = rospy.Time.now()
+        if now > self.t_next:
+            if self.direction == "input":
+                try:
+                    self.value = self.read_value()
+                    #rospy.loginfo("read value: "+str(self.value))
+                except:
+                    try:
+                        # try again
+                        rospy.logwarn("Failed to read sensor values, try again. ")
+                        self.ack = self.write_value()
+                    except:
+                        rospy.logerr("Sensor read value error !")
+                        return
+            else:
+                try:
+                    self.ack = self.write_value()
+                except:
+                    rospy.logerr("Sensor write value error !")
+                    return
+
+            # For range sensors, assign the value to the range message field
+            if self.message_type == MessageType.RANGE:
+                self.msg.range = self.value
+            elif self.message_type == MessageType.INFRARED:
+                self.msg.front_dist = self.value[0]
+                self.msg.left_dist  = self.value[1]
+                self.msg.right_dist = self.value[2]
+            elif self.message_type == MessageType.ULTRASONIC:
+                self.msg.front_dist = self.value[0]
+                self.msg.left_dist  = self.value[1]
+                self.msg.right_dist = self.value[2]
+            else:
+                self.msg.value = self.value
+
+            # Add a timestamp and publish the message
+            self.msg.header.stamp = rospy.Time.now()
+            self.pub.publish(self.msg)
+
+            self.t_next = now + self.t_delta
+
+class AnalogSensor(Sensor):
+    def __init__(self, *args, **kwargs):
+        super(AnalogSensor, self).__init__(*args, **kwargs)
+
+        self.message_type = MessageType.ANALOG
+        self.msg = Analog()
+        self.msg.header.frame_id = self.frame_id
+
+        self.pub = rospy.Publisher("~sensor/" + self.name, Analog, queue_size=5)
+        self.value = LOW
+
+    def read_value(self):
+        return self.controller.analog_read(self.pin)
+
+    def write_value(self, value):
+        return self.controller.analog_write(self.pin, value)
+
+class AnalogFloatSensor(Sensor):
+    def __init__(self, *args, **kwargs):
+        super(AnalogFloatSensor, self).__init__(*args, **kwargs)
+
+        self.message_type = MessageType.ANALOG
+
+        self.msg = AnalogFloat()
+        self.msg.header.frame_id = self.frame_id
+
+        self.pub = rospy.Publisher("~sensor/" + self.name, AnalogFloat, queue_size=5)
+
+        if self.direction == "output":
+            self.controller.pin_mode(self.pin, OUTPUT)
+        else:
+            self.controller.pin_mode(self.pin, INPUT)
+
+        self.value = LOW
+
+    def read_value(self):
+        return self.controller.analog_read(self.pin)
+
+    def write_value(self, value):
+        return self.controller.analog_write(self.pin, value)
+
+class DigitalSensor(Sensor):
+    def __init__(self, *args, **kwargs):
+        super(DigitalSensor, self).__init__(*args, **kwargs)
+
+        self.message_type = MessageType.DIGITAL
+        self.msg = Digital()
+        self.msg.header.frame_id = self.frame_id
+
+        self.pub = rospy.Publisher("~sensor/" + self.name, Digital, queue_size=5)
+        self.value = LOW
+
+    def read_value(self):
+        return self.controller.digital_read(self.pin)
+
+    def write_value(self):
+        # Alternate HIGH/LOW when writing at a fixed rate
+        self.value = not self.value
+        return self.controller.digital_write(self.pin, self.value)
+
+class RangeSensor(Sensor):
+    def __init__(self, *args, **kwargs):
+        super(RangeSensor, self).__init__(*args, **kwargs)
+
+        self.message_type = MessageType.RANGE
+        self.msg = Range()
+        self.msg.header.frame_id = self.frame_id
+        self.pub = rospy.Publisher("~sensor/" + self.name, Range, queue_size=5)
+
+    def read_value(self):
+        self.msg.header.stamp = rospy.Time.now()
+
+class MyRangeSensor(Sensor):
+    def __init__(self, *args, **kwargs):
+        super(MyRangeSensor, self).__init__(*args, **kwargs)
+
+        self.message_type = MessageType.INFRARED
+        self.msg = InfraredSensors()
+        self.msg.header.frame_id = self.frame_id
+
+        self.pub = rospy.Publisher("~sensor/" + self.name, InfraredSensors, queue_size=2)
+
+    def read_value(self):
+        self.msg.header.stamp = rospy.Time.now()
+
+class MyUltrasonicSensor(Sensor):
+    def __init__(self, *args, **kwargs):
+        super(MyUltrasonicSensor, self).__init__(*args, **kwargs)
+
+        self.message_type = MessageType.ULTRASONIC
+        self.msg = UltrasonicSensors()
+        self.msg.header.frame_id = self.frame_id
+
+        self.pub = rospy.Publisher("~sensor/" + self.name, UltrasonicSensors, queue_size=2)
+
+    def read_value(self):
+        self.msg.header.stamp = rospy.Time.now()
+
+class SonarSensor(RangeSensor):
+    def __init__(self, *args, **kwargs):
+        super(SonarSensor, self).__init__(*args, **kwargs)
+        self.msg.radiation_type = Range.ULTRASOUND
+
+class MySonarSensor(MyUltrasonicSensor):
+    def __init__(self, *args, **kwargs):
+        super(MySonarSensor, self).__init__(*args, **kwargs)
+        self.msg.radiation_type = Range.ULTRASOUND
+
+class IRSensor(RangeSensor):
+    def __init__(self, *args, **kwargs):
+        super(IRSensor, self).__init__(*args, **kwargs)
+        self.msg.radiation_type = Range.INFRARED
+
+class MyIRSensor(MyRangeSensor):
+    def __init__(self, *args, **kwargs):
+        super(MyIRSensor, self).__init__(*args, **kwargs)
+        self.msg.radiation_type = Range.INFRARED
+
+class GP2Y0A41(MyIRSensor):
+    def __init__(self, *args, **kwargs):
+        super(GP2Y0A41, self).__init__(*args, **kwargs)
+
+        self.msg.field_of_view = 0.01
+        self.msg.min_range = 0.04
+        self.msg.max_range = 0.30
+
+    def read_value(self):
+        values = self.controller.detect_distance()
+        distances = np.array([values[0], values[1], values[2]])
+        return distances/100.0
+
+class IR2Y0A02(IRSensor):
+    def __init__(self, *args, **kwargs):
+        super(IR2Y0A02, self).__init__(*args, **kwargs)
+
+        self.msg.field_of_view = 0.001
+        self.msg.min_range = 0.200
+        self.msg.max_range = 1.500
+
+    def read_value(self):
+        value = self.controller.analog_read(self.pin)
+
+        try:
+            volts = value*0.0048828125;
+            distance = 65*pow(volts, -1.10)
+        except:
+            return self.msg.min_range
+
+        # Convert to meters
+        distance /= 100.000
+        dist = round(float(distance), 3)
+
+        # If we get a spurious reading, set it to the max_range
+        if dist > self.msg.max_range: dist = self.msg.max_range
+        if dist < self.msg.min_range: dist = self.msg.min_range
+
+        return dist
+
+class US025(MySonarSensor):
+    def __init__(self, *args, **kwargs):
+        super(US025, self).__init__(*args, **kwargs)
+
+        self.msg.field_of_view = 0.01
+        self.msg.min_range = 0.03
+        self.msg.max_range = 6
+
+    def read_value(self):
+        values = self.controller.detect_ultrasonic_distance()
+        distances = np.array([values[0], values[1], values[2]])
+        return distances/100.0
+
+class MotorTotalCurrent(AnalogFloatSensor):
+    def __init__(self, *args, **kwargs):
+        super(MotorTotalCurrent, self).__init__(*args, **kwargs)
+
+    def read_value(self):
+        midVal = mylist[15]
+        result = (midVal/1024.0*4523.00 - 4523.00/2)/100
+        return Decimal(result).quantize(Decimal('0.00'))
+
+class BatPercent(DigitalSensor):
+    def __init__(self, *args, **kwargs):
+        super(BatPercent, self).__init__(*args, **kwargs)
+
+    def read_value(self):
+        percent = self.controller.getBatPercent()
+        return int(percent)
+
+class CurrentValue(DigitalSensor):
+    def __init__(self, *args, **kwargs):
+        super(CurrentValue, self).__init__(*args, **kwargs)
+
+    def read_value(self):
+        currentvalue = self.controller.getCurrentValue()
+        #rospy.loginfo("read currentvalue: "+currentvalue)
+        return float(currentvalue)
+
+
+if __name__ == '__main__':
+    rospy.loginf("arduino sensor main function ...")

+ 320 - 0
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/base_controller.py

@@ -0,0 +1,320 @@
+#!/usr/bin/env python
+
+"""
+    A base controller class for the Arduino microcontroller
+"""
+import os
+import rospy
+import roslib; roslib.load_manifest('ros_arduino_python')
+import dynamic_reconfigure.client
+
+from math import sin, cos, pi, sqrt
+from geometry_msgs.msg import Quaternion, Twist
+from nav_msgs.msg import Odometry
+from tf.broadcaster import TransformBroadcaster
+from std_msgs.msg import Int32
+
+""" Class to receive Twist commands and publish wheel Odometry data """
+class BaseController:
+    
+    def __init__(self, is_use_serial, arduino, base_frame, name="base_controllers_node"):
+        self.use_serial = is_use_serial
+        self.arduino    = arduino
+        self.name       = name
+        self.base_frame = base_frame
+        self.odom_name  = rospy.get_param("~odom_name", "odom")
+        self.cmd_topic  = rospy.get_param("~cmd_topic", "cmd_vel")
+        self.rate       = float(rospy.get_param("~base_controller_rate", 20))
+        self.timeout    = rospy.get_param("~base_controller_timeout", 0.7)
+
+        self.debugPID   = rospy.get_param('/dynamic_tutorials/debugPID', False)
+	
+        pid_params = dict()
+        pid_params['wheel_diameter']     = rospy.get_param("~wheel_diameter", 0.058)
+        pid_params['wheel_track']        = rospy.get_param("~wheel_track", 0.126)
+        pid_params['encoder_resolution'] = rospy.get_param("~encoder_resolution", 11)
+        pid_params['gear_reduction']     = rospy.get_param("~gear_reduction", 46)
+        pid_params['AWheel_Kp'] = rospy.get_param("~AWheel_Kp", 15)
+        pid_params['AWheel_Kd'] = rospy.get_param("~AWheel_Kd", 15)
+        pid_params['AWheel_Ki'] = rospy.get_param("~AWheel_Ki", 0)
+        pid_params['AWheel_Ko'] = rospy.get_param("~AWheel_Ko", 50)
+
+        pid_params['BWheel_Kp'] = rospy.get_param("~BWheel_Kp", 15)
+        pid_params['BWheel_Kd'] = rospy.get_param("~BWheel_Kd", 15)
+        pid_params['BWheel_Ki'] = rospy.get_param("~BWheel_Ki", 0)
+        pid_params['BWheel_Ko'] = rospy.get_param("~BWheel_Ko", 50)
+
+        self.accel_limit  = rospy.get_param('~accel_limit', 0.05)
+        self.linear_scale_correction  = rospy.get_param("~linear_scale_correction",  1.0)
+        self.angular_scale_correction = rospy.get_param("~angular_scale_correction", 1.0)
+
+        #rospy.loginfo("pid_params_dict: "+pid_params)
+
+        # Set up PID parameters and check for missing values
+        self.setup_pid(pid_params)
+
+        # How many encoder ticks are there per meter?
+        self.ticks_per_meter = self.encoder_resolution*self.gear_reduction*2/(self.wheel_diameter*pi)
+        self.ticks_per_meter = self.ticks_per_meter/self.linear_scale_correction
+
+        # What is the maximum acceleration we will tolerate when changing wheel speeds?
+        self.max_accel = self.accel_limit*self.ticks_per_meter/self.rate
+
+        # Track how often we get a bad encoder count (if any)
+        self.bad_encoder_count = 0
+
+        now = rospy.Time.now()
+        self.then    = now  # time for determining dx/dy
+        self.t_delta = rospy.Duration(1.0/self.rate)
+        self.t_next  = now + self.t_delta
+
+        # Internal data
+        self.enc_A = 0  # encoder readings
+        self.enc_B = 0
+
+        self.x  = 0  # position in xy plane
+        self.y  = 0
+        self.th = 0  # rotation in radians
+
+        self.v_A = 0
+        self.v_B = 0
+
+        self.v_des_AWheel = 0  # cmd_vel setpoint
+        self.v_des_BWheel = 0
+
+        self.last_cmd_time = now
+
+        # Subscriptions main comtrol board to send control cmd
+        rospy.Subscriber(self.cmd_topic, Twist, self.cmdVelCallback)
+
+        # Clear any old odometry info
+        if self.use_serial:
+            self.arduino.reset_encoders()
+        else:
+            self.arduino.i2c_reset_encoders()
+
+        # Set up the wheel odometry broadcaster
+        self.odomPub = rospy.Publisher(self.odom_name, Odometry, queue_size=10)
+        self.odomBroadcaster = TransformBroadcaster()
+
+        #corvin add for rqt_plot debug pid
+        if self.debugPID:
+            self.AEncoderPub = rospy.Publisher('Aencoder', Int32, queue_size=10)
+            self.BEncoderPub = rospy.Publisher('Bencoder', Int32, queue_size=10)
+            self.APidoutPub  = rospy.Publisher('Apidout',  Int32, queue_size=10)
+            self.BPidoutPub  = rospy.Publisher('Bpidout',  Int32, queue_size=10)
+            self.AVelPub     = rospy.Publisher('Avel',     Int32, queue_size=10)
+            self.BVelPub     = rospy.Publisher('Bvel',     Int32, queue_size=10)
+
+        rospy.loginfo("Started base controller for a base of " + str(self.wheel_track) + "m with " + str(self.encoder_resolution) + " ticks per rev")
+        rospy.loginfo("Publishing odometry data at: " + str(self.rate) + " Hz using " + str(self.base_frame) + " as base frame")
+
+    def setup_pid(self, pid_params):
+        # Check to see if any PID parameters are missing
+        missing_params = False
+        for param in pid_params:
+            if pid_params[param] == "":
+                print("*** PID Parameter " + param + " is missing. ***")
+                missing_params = True
+
+        if missing_params:
+            os._exit(1)
+
+        self.encoder_resolution = pid_params['encoder_resolution']
+        self.gear_reduction     = pid_params['gear_reduction']
+        self.wheel_diameter = pid_params['wheel_diameter']
+        self.wheel_track    = pid_params['wheel_track']
+        self.wheel_track    = self.wheel_track/self.angular_scale_correction
+
+        self.AWheel_Kp = pid_params['AWheel_Kp']
+        self.AWheel_Kd = pid_params['AWheel_Kd']
+        self.AWheel_Ki = pid_params['AWheel_Ki']
+        self.AWheel_Ko = pid_params['AWheel_Ko']
+
+        self.BWheel_Kp = pid_params['BWheel_Kp']
+        self.BWheel_Kd = pid_params['BWheel_Kd']
+        self.BWheel_Ki = pid_params['BWheel_Ki']
+        self.BWheel_Ko = pid_params['BWheel_Ko']
+        if self.use_serial:
+            self.arduino.update_pid(self.AWheel_Kp, self.AWheel_Kd, self.AWheel_Ki, self.AWheel_Ko,
+                                    self.BWheel_Kp, self.BWheel_Kd, self.BWheel_Ki, self.BWheel_Ko,)
+        else:
+            self.arduino.i2c_update_pid(self.AWheel_Kp, self.AWheel_Kd, self.AWheel_Ki, self.AWheel_Ko,
+                                        self.BWheel_Kp, self.BWheel_Kd, self.BWheel_Ki, self.BWheel_Ko,)
+
+    # main loop, always run
+    def poll(self):
+        self.send_debug_pid()
+
+        time_now = rospy.Time.now()
+        if time_now > self.t_next:
+            # Read the encoders
+            try:
+                if self.use_serial:
+                    aWheel_enc, bWheel_enc = self.arduino.get_encoder_counts()
+                else:
+                    aWheel_enc, bWheel_enc = self.arduino.i2c_get_encoder_counts()
+                    #rospy.loginfo("get encoder counts: "+str(self.arduino.i2c_get_encoder_counts()))
+            except:
+                try:
+                    # try again
+                    #rospy.logwarn("Failed to get encoder counts, try again. ")
+                    aWheel_enc, bWheel_enc = self.arduino.i2c_get_encoder_counts()
+                except:
+                    self.bad_encoder_count += 1
+                    rospy.logerr("Encoder exception count: " + str(self.bad_encoder_count))
+                    return
+
+            # Calculate odometry
+            dist_A = (aWheel_enc - self.enc_A)/self.ticks_per_meter
+            dist_B = (bWheel_enc - self.enc_B)/self.ticks_per_meter
+
+            # save current encoder value for next calculate
+            self.enc_A = aWheel_enc
+            self.enc_B = bWheel_enc
+
+            dt = time_now - self.then
+            self.then = time_now
+            dt = dt.to_sec()
+
+            va = dist_A/dt
+            vb = dist_B/dt
+
+            #forward kinemation
+            vx  = (va + vb)/2.0
+            vy  = 0
+            vth = (vb - va)/(self.wheel_track)
+
+            delta_x  = (vx*cos(self.th) - vy*sin(self.th))*dt
+            delta_y  = (vx*sin(self.th) + vy*cos(self.th))*dt
+            delta_th = vth*dt
+
+            self.x  += delta_x
+            self.y  += delta_y
+            self.th += delta_th
+
+            quaternion   = Quaternion()
+            quaternion.x = 0.0
+            quaternion.y = 0.0
+            quaternion.z = sin(self.th/2.0)
+            quaternion.w = cos(self.th/2.0)
+
+            odom = Odometry()
+            odom.header.frame_id = self.odom_name
+            odom.child_frame_id  = self.base_frame
+            odom.header.stamp    = time_now
+            odom.pose.pose.position.x  = self.x
+            odom.pose.pose.position.y  = self.y
+            odom.pose.pose.position.z  = 0
+            odom.pose.pose.orientation = quaternion
+            odom.pose.covariance = [1e-9, 0, 0, 0, 0, 0,
+                                    0, 1e-3, 1e-9, 0, 0, 0,
+                                    0, 0, 1e6, 0, 0, 0,
+                                    0, 0, 0, 1e6, 0, 0,
+                                    0, 0, 0, 0, 1e6, 0,
+                                    0, 0, 0, 0, 0, 1e-9]
+            odom.twist.twist.linear.x  = vx
+            odom.twist.twist.linear.y  = vy
+            odom.twist.twist.angular.z = vth
+            odom.twist.covariance = [1e-9, 0, 0, 0, 0, 0,
+                                    0, 1e-3, 1e-9, 0, 0, 0,
+                                    0, 0, 1e6, 0, 0, 0,
+                                    0, 0, 0, 1e6, 0, 0,
+                                    0, 0, 0, 0, 1e6, 0,
+                                    0, 0, 0, 0, 0, 1e-9]
+            self.odomPub.publish(odom)
+
+            # send motor cmd
+            if time_now > (self.last_cmd_time + rospy.Duration(self.timeout)):
+                self.stop()
+            else:
+                self.send_motor_speed()
+
+            # set next compare time
+            self.t_next = time_now + self.t_delta
+
+
+    # debug motor pid parameter
+    def send_debug_pid(self):
+        if self.debugPID:
+            try:
+                if self.use_serial:
+                    A_pidin, B_pidin = self.arduino.get_pidin()
+                else:
+                    A_pidin, B_pidin = self.arduino.i2c_get_pidin()
+                self.AEncoderPub.publish(A_pidin)
+                self.BEncoderPub.publish(B_pidin)
+            except:
+                rospy.logerr("getpidin exception count:")
+                return
+
+            try:
+                if self.use_serial:
+                    A_pidout, B_pidout = self.arduino.get_pidout()
+                else:
+                    A_pidout, B_pidout = self.arduino.i2c_get_pidout()
+                self.APidoutPub.publish(A_pidout)
+                self.BPidoutPub.publish(B_pidout)
+            except:
+                rospy.logerr("getpidout exception count")
+                return
+
+    # normalize motor dest encode value and send
+    def send_motor_speed(self):
+        if self.v_A < self.v_des_AWheel:
+          self.v_A += self.max_accel
+          if self.v_A > self.v_des_AWheel:
+              self.v_A = self.v_des_AWheel
+        else:
+          self.v_A -= self.max_accel
+          if self.v_A < self.v_des_AWheel:
+              self.v_A = self.v_des_AWheel
+
+        if self.v_B < self.v_des_BWheel:
+          self.v_B += self.max_accel
+          if self.v_B > self.v_des_BWheel:
+              self.v_B = self.v_des_BWheel
+        else:
+          self.v_B -= self.max_accel
+          if self.v_B < self.v_des_BWheel:
+              self.v_B = self.v_des_BWheel
+
+        # send to arduino to drive motor
+        if self.use_serial:
+            self.arduino.drive(self.v_A, self.v_B)
+        else:
+            self.arduino.i2c_drive(self.v_A, self.v_B)
+
+        if self.debugPID:
+            self.AVelPub.publish(self.v_A)
+            self.BVelPub.publish(self.v_B)
+
+
+    # stop move mobile base
+    def stop(self):
+        self.v_A = 0
+        self.v_B = 0
+        self.v_des_AWheel = 0
+        self.v_des_BWheel = 0
+        if self.use_serial:
+            self.arduino.drive(0, 0)
+        else:
+            self.arduino.i2c_drive(0, 0)
+        #rospy.logwarn("stop mobilebase move!!!!")
+
+    def cmdVelCallback(self, req):
+        # Handle velocity-based movement requests
+        self.last_cmd_time = rospy.Time.now()
+
+        x  = req.linear.x  # m/s
+        y  = 0  # m/s
+        th = req.angular.z # rad/s
+
+        #Inverse Kinematic
+        vA = (-x + 0.5*self.wheel_track*th)
+        vB = (x + 0.5*self.wheel_track*th)
+
+        self.v_des_AWheel = int(vA * self.ticks_per_meter / self.arduino.PID_RATE)
+        self.v_des_BWheel = int(vB * self.ticks_per_meter / self.arduino.PID_RATE)
+        #rospy.loginfo("cmdCallback(): A v_des:"+str(self.v_des_AWheel)+",B v_des:"+str(self.v_des_BWheel))
+