17 min read

In this article by Lentin Joseph, author of the book Learning Robotics Using Python, we will see how to assemble this robot using these parts and also the final interfacing of sensors and other electronics components of this robot to Tiva C LaunchPad. We will also try to interface the necessary robotic components and sensors of ChefBot and program it in such a way that it will receive the values from all sensors and control the information from the PC. Launchpad will send all sensor values via a serial port to the PC and also receive control information (such as reset command, speed, and so on) from the PC.

After receiving sensor values from the PC, a ROS Python node will receive the serial values and convert it to ROS Topics. There are Python nodes present in the PC that subscribe to the sensor’s data and produces odometry. The data from the wheel encoders and IMU values are combined to calculate the odometry of the robot and detect obstacles by subscribing to the ultrasonic sensor and laser scan also, controlling the speed of the wheel motors by using the PID node. This node converts the linear velocity command to differential wheel velocity. After running these nodes, we can run SLAM to map the area and after running SLAM, we can run the AMCL nodes for localization and autonomous navigation.

In the first section of this article, Building ChefBot hardware, we will see how to assemble the ChefBot hardware using its body parts and electronics components.

(For more resources related to this topic, see here.)

Building ChefBot hardware

The first section of the robot that needs to be configured is the base plate. The base plate consists of two motors and its wheels, caster wheels, and base plate supports. The following image shows the top and bottom view of the base plate:

Learning Robotics Using Python

Base plate with motors, wheels, and caster wheels

The base plate has a radius of 15cm and motors with wheels are mounted on the opposite sides of the plate by cutting a section from the base plate. A rubber caster wheel is mounted on the opposite side of the base plate to give the robot good balance and support for the robot. We can either choose ball caster wheels or rubber caster wheels. The wires of the two motors are taken to the top of the base plate through a hole in the center of the base plate. To extend the layers of the robot, we will put base plate supports to connect the next layers. Now, we can see the next layer with the middle plate and connecting tubes. There are hollow tubes, which connect the base plate and the middle plate. A support is provided on the base plate for hollow tubes. The following figure shows the middle plate and connecting tubes:

 Learning Robotics Using Python

Middle plate with connecting tubes

The connecting tubes will connect the base plate and the middle plate. There are four hollow tubes that connect the base plate to the middle plate. One end of these tubes is hollow, which can fit in the base plate support, and the other end is inserted with a hard plastic with an option to put a screw in the hole. The middle plate has no support except four holes:

 Learning Robotics Using Python

Fully assembled robot body

The middle plate male connector helps to connect the middle plate and the top of the base plate tubes. At the top of the middle plate tubes, we can fit the top plate, which has four supports on the back. We can insert the top plate female connector into the top plate support and this is how we will get the fully assembled body of the robot.

The bottom layer of the robot can be used to put the Printed Circuit Board (PCB) and battery. In the middle layer, we can put Kinect and Intel NUC. We can put a speaker and a mic if needed. We can use the top plate to carry food. The following figure shows the PCB prototype of robot; it consists of Tiva C LaunchPad, a motor driver, level shifters, and provisions to connect two motors, ultrasonic, and IMU:

 Learning Robotics Using Python

ChefBot PCB prototype

The board is powered with a 12 V battery placed on the base plate. The two motors can be directly connected to the M1 and M2 male connectors. The NUC PC and Kinect are placed on the middle plate. The Launchpad board and Kinect should be connected to the NUC PC via USB. The PC and Kinect are powered using the same 12 V battery itself. We can use a lead-acid or lithium-polymer battery. Here, we are using a lead-acid cell for testing purposes. We will migrate to lithium-polymer for better performance and better backup. The following figure shows the complete assembled diagram of ChefBot:

 Learning Robotics Using Python

Fully assembled robot body

After assembling all the parts of the robot, we will start working with the robot software. ChefBot’s embedded code and ROS packages are available in GitHub. We can clone the code and start working with the software.

Configuring ChefBot PC and setting ChefBot ROS packages

In ChefBot, we are using Intel’s NUC PC to handle the robot sensor data and its processing. After procuring the NUC PC, we have to install Ubuntu 14.04.2 or the latest updates of 14.04 LTS. After the installation of Ubuntu, install complete ROS and its packages. We can configure this PC separately, and after the completion of all the settings, we can put this in to the robot. The following are the procedures to install ChefBot packages on the NUC PC.

Clone ChefBot’s software packages from GitHub using the following command:

$ git clone https://github.com/qboticslabs/Chefbot_ROS_pkg.git

We can clone the code in our laptop and copy the chefbot folder to Intel’s NUC PC. The chefbot folder consists of the ROS packages of ChefBot. In the NUC PC, create a ROS catkin workspace, copy the chefbot folder and move it inside the src directory of the catkin workspace.

Build and install the source code of ChefBot by simply using the following command This should be executed inside the catkin workspace we created:

$ catkin_make

If all dependencies are properly installed in NUC, then the ChefBot packages will build and install in this system. After setting the ChefBot packages on the NUC PC, we can switch to the embedded code for ChefBot. Now, we can connect all the sensors in Launchpad. After uploading the code in Launchpad, we can again discuss ROS packages and how to run it.

Interfacing ChefBot sensors with Tiva C LaunchPad

We have discussed interfacing of individual sensors that we are going to use in ChefBot. In this section, we will discuss how to integrate sensors into the Launchpad board. The Energia code to program Tiva C LaunchPad is available on the cloned files at GitHub. The connection diagram of Tiva C LaunchPad with sensors is as follows. From this figure, we get to know how the sensors are interconnected with Launchpad:

 Learning Robotics Using Python

Sensor interfacing diagram of ChefBot

M1 and M2 are two differential drive motors that we are using in this robot. The motors we are going to use here is DC Geared motor with an encoder from Pololu. The motor terminals are connected to the VNH2SP30 motor driver from Pololu. One of the motors is connected in reverse polarity because in differential steering, one motor rotates opposite to the other. If we send the same control signal to both the motors, each motor will rotate in the opposite direction. To avoid this condition, we will connect it in opposite polarities. The motor driver is connected to Tiva C LaunchPad through a 3.3 V-5 V bidirectional level shifter. One of the level shifter we will use here is available at: https://www.sparkfun.com/products/12009.

The two channels of each encoder are connected to Launchpad via a level shifter. Currently, we are using one ultrasonic distance sensor for obstacle detection. In future, we could expand this number, if required. To get a good odometry estimate, we will put IMU sensor MPU 6050 through an I2C interface. The pins are directly connected to Launchpad because MPU6050 is 3.3 V compatible. To reset Launchpad from ROS nodes, we are allocating one pin as the output and connected to reset pin of Launchpad. When a specific character is sent to Launchpad, it will set the output pin to high and reset the device. In some situations, the error from the calculation may accumulate and it can affect the navigation of the robot. We are resetting Launchpad to clear this error. To monitor the battery level, we are allocating another pin to read the battery value. This feature is not currently implemented in the Energia code.

The code you downloaded from GitHub consists of embedded code. We can see the main section of the code here and there is no need to explain all the sections because we already discussed it.

Writing a ROS Python driver for ChefBot

After uploading the embedded code to Launchpad, the next step is to handle the serial data from Launchpad and convert it to ROS Topics for further processing. The launchpad_node.py ROS Python driver node interfaces Tiva C LaunchPad to ROS. The launchpad_node.py file is on the script folder, which is inside the chefbot_bringup package. The following is the explanation of launchpad_node.py in important code sections:

#ROS Python client
import rospy
import sys
import time
import math
 
#This python module helps to receive values from serial port which execute in a thread
from SerialDataGateway import SerialDataGateway
#Importing required ROS data types for the code
from std_msgs.msg import Int16,Int32, Int64, Float32, String, Header, UInt64
#Importing ROS data type for IMU
from sensor_msgs.msg import Imu

The launchpad_node.py file imports the preceding modules. The main modules we can see is SerialDataGateway. This is a custom module written to receive serial data from the Launchpad board in a thread. We also need some data types of ROS to handle the sensor data. The main function of the node is given in the following code snippet:

if __name__ =='__main__':
rospy.init_node('launchpad_ros',anonymous=True)
launchpad = Launchpad_Class()
try:
 
   launchpad.Start()
   rospy.spin()
except rospy.ROSInterruptException:
   rospy.logwarn("Error in main function")
 
launchpad.Reset_Launchpad()
launchpad.Stop()

The main class of this node is called Launchpad_Class(). This class contains all the methods to start, stop, and convert serial data to ROS Topics. In the main function, we will create an object of Launchpad_Class(). After creating the object, we will call the Start() method, which will start the serial communication between Tiva C LaunchPad and PC. If we interrupt the driver node by pressing Ctrl + C, it will reset the Launchpad and stop the serial communication between the PC and Launchpad.

The following code snippet is from the constructor function of Launchpad_Class(). In the following snippet, we will retrieve the port and baud rate of the Launchpad board from ROS parameters and initialize the SerialDateGateway object using these parameters. The SerialDataGateway object calls the _HandleReceivedLine() function inside this class when any incoming serial data arrives on the serial port.

This function will process each line of serial data and extract, convert, and insert it to the appropriate headers of each ROS Topic data type:

#Get serial port and baud rate of Tiva C Launchpad
port = rospy.get_param("~port", "/dev/ttyACM0")
baudRate = int(rospy.get_param("~baudRate", 115200))
 
#################################################################
rospy.loginfo("Starting with serial port: " + port + ", baud rate: " + str(baudRate))
 
#Initializing SerialDataGateway object with serial port, baud rate and callback function to handle incoming serial data
self._SerialDataGateway = SerialDataGateway(port, baudRate, self._HandleReceivedLine)
rospy.loginfo("Started serial communication")
 
 
###################################################################Subscribers and Publishers
 
#Publisher for left and right wheel encoder values
self._Left_Encoder = rospy.Publisher('lwheel',Int64,queue_size = 10)
self._Right_Encoder = rospy.Publisher('rwheel',Int64,queue_size = 10)
 
#Publisher for Battery level(for upgrade purpose)
self._Battery_Level = rospy.Publisher('battery_level',Float32,queue_size = 10)
#Publisher for Ultrasonic distance sensor
self._Ultrasonic_Value = rospy.Publisher('ultrasonic_distance',Float32,queue_size = 10)
 
#Publisher for IMU rotation quaternion values
self._qx_ = rospy.Publisher('qx',Float32,queue_size = 10)
self._qy_ = rospy.Publisher('qy',Float32,queue_size = 10)
self._qz_ = rospy.Publisher('qz',Float32,queue_size = 10)
self._qw_ = rospy.Publisher('qw',Float32,queue_size = 10)
 
#Publisher for entire serial data
self._SerialPublisher = rospy.Publisher('serial', String,queue_size=10)

We will create the ROS publisher object for sensors such as the encoder, IMU, and ultrasonic sensor as well as for the entire serial data for debugging purpose. We will also subscribe the speed commands for the left-hand side and the right-hand side wheel of the robot. When a speed command arrives on Topic, it calls the respective callbacks to send speed commands to the robot’s Launchpad:

self._left_motor_speed = rospy.Subscriber('left_wheel_speed',Float32,self._Update_Left_Speed)
self._right_motor_speed = rospy.Subscriber('right_wheel_speed',Float32,self._Update_Right_Speed)

After setting the ChefBot driver node, we need to interface the robot to a ROS navigation stack in order to perform autonomous navigation. The basic requirement for doing autonomous navigation is that the robot driver nodes, receive velocity command from ROS navigational stack. The robot can be controlled using teleoperation. In addition to these features, the robot must be able to compute its positional or odometry data and generate the tf data for sending into navigational stack. There must be a PID controller to control the robot motor velocity. The following ROS package helps to perform these functions. The differential_drive package contains nodes to perform the preceding operation. We are reusing these nodes in our package to implement these functionalities. The following is the link for the differential_drive package in ROS:

http://wiki.ros.org/differential_drive

The following figure shows how these nodes communicate with each other. We can also discuss the use of other nodes too:

 Learning Robotics Using Python

The purpose of each node in the chefbot_bringup package is as follows:

  • twist_to_motors.py: This node will convert the ROS Twist command or linear and angular velocity to individual motor velocity target. The target velocities are published at a rate of the ~rate Hertz and the publish timeout_ticks times velocity after the Twist message stops. The following are the Topics and parameters that will be published and subscribed by this node:
    • Publishing Topics:
      • lwheel_vtarget (std_msgs/Float32): This is the the target velocity of the left wheel(m/s).
      • rwheel_vtarget (std_msgs/Float32): This is the target velocity of the right wheel(m/s).
    • Subscribing Topics:
      • Twist (geometry_msgs/Twist): This is the target Twist command for the robot. The linear velocity in the x direction and angular velocity theta of the Twist messages are used in this robot.
    • Important ROS parameters:
      • ~base_width (float, default: 0.1): This is the distance between the robot’s two wheels in meters.
      • ~rate (int, default: 50): This is the rate at which velocity target is published(Hertz).
      • ~timeout_ticks (int, default:2): This is the number of the velocity target message published after stopping the Twist messages.
  • pid_velocity.py: This is a simple PID controller to control the speed of each motors by taking feedback from wheel encoders. In a differential drive system, we need one PID controller for each wheel. It will read the encoder data from each wheels and control the speed of each wheels.
    • Publishing Topics:
      • motor_cmd (Float32): This is the final output of the PID controller that goes to the motor. We can change the range of the PID output using the out_min and out_max ROS parameter.
      • wheel_vel (Float32): This is the current velocity of the robot wheel in m/s.
    • Subscribing Topics:
      • wheel (Int16): This Topic is the output of a rotary encoder. There are individual Topics for each encoder of the robot.
      • wheel_vtarget (Float32): This is the target velocity in m/s.
    • Important parameters:
      • ~Kp (float ,default: 10): This parameter is the proportional gain of the PID controller.
      • ~Ki (float, default: 10): This parameter is the integral gain of the PID controller.
      • ~Kd (float, default: 0.001): This parameter is the derivative gain of the PID controller.
      • ~out_min (float, default: 255): This is the minimum limit of the velocity value to motor. This parameter limits the velocity value to motor called wheel_vel Topic.
      • ~out_max (float, default: 255): This is the maximum limit of wheel_vel Topic(Hertz).
      • ~rate (float, default: 20): This is the rate of publishing wheel_vel Topic.
      • ticks_meter (float, default: 20): This is the number of wheel encoder ticks per meter. This is a global parameter because it’s used in other nodes too.
      • vel_threshold (float, default: 0.001): If the robot velocity drops below this parameter, we consider the wheel as stopped. If the velocity of the wheel is less than vel_threshold, we consider it as zero.
      • encoder_min (int, default: 32768): This is the minimum value of encoder reading.
      • encoder_max (int, default: 32768): This is the maximum value of encoder reading.
      • wheel_low_wrap (int, default: 0.3 * (encoder_max – encoder_min) + encoder_min): These values decide whether the odometry is in negative or positive direction.
      • wheel_high_wrap (int, default: 0.7 * (encoder_max – encoder_min) + encoder_min): These values decide whether the odometry is in the negative or positive direction.
  • diff_tf.py: This node computes the transformation of odometry and broadcast between the odometry frame and the robot base frame.
    • Publishing Topics:
      • odom (nav_msgs/odometry): This publishes the odometry (current pose and twist of the robot.
      • tf: This provides transformation between the odometry frame and the robot base link.
    • Subscribing Topics:
      • lwheel (std_msgs/Int16), rwheel (std_msgs/Int16): These are the output values from the left and right encoder of the robot.
  • chefbot_keyboard_teleop.py: This node sends the Twist command using controls from the keyboard.
    • Publishing Topics:
      • cmd_vel_mux/input/teleop (geometry_msgs/Twist): This publishes the twist messages using keyboard commands.

After discussing nodes in the chefbot_bringup package, we will look at the functions of launch files.

Understanding ChefBot ROS launch files

We will discuss the functions of each launch files of the chefbot_bringup package.

  • robot_standalone.launch: The main function of this launch file is to start nodes such as launchpad_node, pid_velocity, diff_tf, and twist_to_motor to get sensor values from the robot and to send command velocity to the robot.
  • keyboard_teleop.launch: This launch file will start the teleoperation by using the keyboard. This launch starts the chefbot_keyboard_teleop.py node to perform the keyboard teleoperation.
  • 3dsensor.launch : This file will launch Kinect OpenNI drivers and start publishing RGB and depth stream. It will also start the depth stream to laser scanner node, which will convert point cloud to laser scan data.
  • gmapping_demo.launch: This launch file will start SLAM gmapping nodes to map the area surrounding the robot.
  • amcl_demo.launch: Using AMCL, the robot can localize and predict where it stands on the map. After localizing on the map, we can command the robot to move to a position on the map, then the robot can move autonomously from its current position to the goal position.
  • view_robot.launch: This launch file displays the robot URDF model in RViz.
  • view_navigation.launch: This launch file displays all the sensors necessary for the navigation of the robot.

Summary

This article was about assembling the hardware of ChefBot and integrating the embedded and ROS code into the robot to perform autonomous navigation. We assembled individual sections of the robot and connected the prototype PCB that we designed for the robot. This consists of the Launchpad board, motor driver, left shifter, ultrasonic, and IMU. The Launchpad board was flashed with the new embedded code, which can interface all sensors in the robot and can send or receive data from the PC. After discussing the embedded code, we wrote the ROS Python driver node to interface the serial data from the Launchpad board. After interfacing the Launchpad board, we computed the odometry data and differential drive controlling using nodes from the differential_drive package that existed in the ROS repository. We interfaced the robot to ROS navigation stack. This enables to perform SLAM and AMCL for autonomous navigation. We also discussed SLAM, AMCL, created map, and executed autonomous navigation on the robot.

Resources for Article:


Further resources on this subject:

1 COMMENT

  1. HI,
    i have tiva 4C 129 board , i want to replace tiva c 123 with tiva c 129. cloned the energia code from github, i am able to get the data from the ultrasonic sensor, but i am not getting data from MPU, becuase i am not getting where to change the I2C pins which i am using. as shown above you are using some I2C pins on tiva c 123 but i want to change the pins since i am using Tiva c 129 . please let me know how can i change the I2C pins in code , in which file i need make this changes , i want use I2C[0] module on tiva c 129 board.

LEAVE A REPLY

Please enter your comment!
Please enter your name here