ROS packages for ROS Noetic related to odometry running on a Raspberry Pi 4 B for an autonomous 2WD Robot.

ROS Packages

LM393 Speed Sensor - Odometry

Note that this sensor is deprecated in the current version of DiffBot because it isn’t a quadrature encoder. Instead, the DG01D-E motor includes a quadrature encoder that can measure ticks (can be converted to speed) and the direction the motor is turning (clock-wise or anti-clock-wise). The LM393 speed sensor could be used in combination with an additional information about the current driving direction, for example coming from the software. Howerver, this won’t be as accurate as using a quadrature encoder that provides this information.

To measure how far the robot has driven, we use the LM393 speed sensor from Joy-IT as odometry sensor. First, we will create a ROS package with catkin create pkg PKG_NAME [--catkin-deps [DEP [DEP ...]]]:

fjp@ubuntu:~/git/2wd-robot/ros/src$ catkin create pkg lm393_speed_sensor --catkin-deps rospy roscpp nav_msgs
Creating package "lm393_speed_sensor" in "/home/fjp/git/2wd-robot/ros/src"...
Created file lm393_speed_sensor/CMakeLists.txt
Created file lm393_speed_sensor/package.xml
Created folder lm393_speed_sensor/include/lm393_speed_sensor
Created folder lm393_speed_sensor/src
Successfully created package files in /home/fjp/git/2wd-robot/ros/src/lm393_speed_sensor.

The package depends on the two ROS client libraries rospy and roscpp. The current implementation uses python and the RPi.GPIO library for interrupts. To achieve more percise results, C++ should be used instead. To signalise the current pose of the robot in the odometry frame, the nav_msgs/Range message is used.

Connection

To get the speed sensors working, we connect the signal pins to (physical) GPIO 15 and (physical) GPIO 16 of the Raspberry Pi 4 B and power them with 3.3V. The ground pins are connected to ground of the Pi.

LM393 Speed Sensor Library

To use the LM393 speed sensor as a ROS node the sensor functionality is wraped in a class. This provides an easy to extend interface for the speed sensor (API) The code consists of a class LM393SpeedSensor which has two interrupt service routines (ISR) methods. Using the RPi.GPIO interrupt capabilities, these ISR methods are used as callback functions when the sensor measures a falling edge. This is the case when the rotary disk spins and the optocoupler measures a high to low signal due to the spinning disk.

The sensor API is implemented in the lm393_speed_sensor.py python module. Executing the module will result in the following output when the motors are spinning freely with full speed and using some force to slow them down. We see that the rotational speed $\omega$, measured in RPM (revolutions per minute) changes.

fjp@ubuntu:~/git/2wd-robot/ros/src/lm393_speed_sensor/src$ sudo python lm393_speed_sensor.py
TODO

The rotational speed $\omega$ values will be converted to tangential velocity values using the radius $r$ of the wheels.

\[v = \omega \cdot r = 2 \pi n \cdot r\]

ROS Node for LM393 Speed Sensor

ROS provides the Odometry Message in the nav_msgs header. This message type can be used to write a wrapper that will act as a ROS node for the LM393 speed sensor.

To design this node we will send out measurements periodically over a topic of type nav_msgs/Odometry. The code for this node is in speed_sensor.py.

After writing the node we need to build the packages in the workspace with catkin build.

fjp@ubuntu:~/git/2wd-robot/ros$ catkin build
TODO

As the final note of the build output suggests, we have to source the setup.bash files in the devel space.

fjp@ubuntu:~/git/2wd-robot/ros$ source devel/setup.bash

To make the speed_sensor node executable we have to modify the speed_sensor.py file:

fjp@ubuntu:~/git/2wd-robot/ros/src/grove_ultrasonic_ranger/src$ sudo chmod a+x speed_sensor.py

Then we can test the node using rosrun:

fjp@ubuntu:~/git/2wd-robot/ros$ sudo su
[sudo] password for fjp:
root@ubuntu:/home/fjp/git/2wd-robot/ros# source devel/setup.bash 
root@ubuntu:/home/fjp/git/2wd-robot/ros# rosrun lm393_speed_sensor speed_sensor.py 

This lets the node publish range messages which we can capture in another terminal window using rostopic. First we use rostopic list to find the name of the topic we are interested in:

fjp@ubuntu:~/git/2wd-robot/ros$ rostopic list
TODO

We named our topic /odom which we can use with the rostopic echo command to see the published messages:

Comments