Modified 2020-10-28 by PhiDeltaEE
Learn how to work with the wheel encoders from the Duckiebot
Being able to work with the wheel encoder data from the Duckiebots
Modified 2020-10-28 by PhiDeltaEE
Encoders are sensors that are able to convert analog angular position or motion of a shaft into a digital signal. In Duckietown we use Hall Effect Encoders, which are able to extract the incremental change in angular position of the wheels. This is very useful, since it can be used to accurately map the position of the Duckiebot while it moves in the Duckietown.
our encoders produce 135 ticks per revolution.
Modified 2020-10-29 by Aleksandar Petrov
The first task is to get familiar with how encoders work within the Duckietown pipeline. For this you will need a good understanding on how to build your own ROS-compliant Duckietown code. You will be required to create your own subscriber/publisher nodes, get the encoder information, and use it for the following tasks.
Similarly as with the Braitenberg Vehicles, we will be developing new Duckietown functionality. For this we will need the following:
The data from each wheel encoders can be used to determined the distance travelled by each wheel:
Below you can see the WheelEncoderStamped.msg
from the Duckietown messages package:
# Enum: encoder type
uint8 ENCODER_TYPE_ABSOLUTE = 0
uint8 ENCODER_TYPE_INCREMENTAL = 1
Header header
uint32 data
uint16 resolution
uint8 type
Now you are ready to get started with the Duckietown encoders! Here’s a useful (but definitely incomplete!) template that will help you get going. Note, this is not the only solution. Any solution which implements the required functionality will be considered correct.
Template:
#!/usr/bin/env python3
import numpy as np
import os
import rospy
from duckietown.dtros import DTROS, NodeType, TopicType, DTParam, ParamType
from duckietown_msgs.msg import Twist2DStamped, WheelEncoderStamped, WheelsCmdStamped
from std_msgs.msg import Header, Float32
class OdometryNode(DTROS):
def __init__(self, node_name):
"""Wheel Encoder Node
This implements basic functionality with the wheel encoders.
"""
# Initialize the DTROS parent class
super(EncoderNode, self).__init__(node_name=node_name, node_type=NodeType.PERCEPTION)
self.veh_name = rospy.get_namespace().strip("/")
# Get static parameters
self._radius = rospy.get_param(f'/{self.veh_name}/kinematics_node/radius', 100)
# Subscribing to the wheel encoders
self.sub_encoder_ticks_left = rospy.Subscriber(...)
self.sub_encoder_ticks_right = rospy.Subscriber(...)
self.sub_executed_commands = rospy.Subscriber(...)
# Publishers
self.pub_integrated_distance_left = rospy.Publisher(...)
self.pub_integrated_distance_right = rospy.Publisher(...)
self.log("Initialized")
def cb_encoder_data(self, wheel, msg):
""" Update encoder distance information from ticks.
"""
def cb_executed_commands(self, msg):
""" Use the executed commands to determine the direction of travel of each wheel.
"""
if __name__ == '__main__':
node = OdometryNode(node_name='my_odometry_node')
# Keep it spinning to keep the node alive
rospy.spin()
rospy.loginfo("wheel_encoder_node is up and running...")
Do the following:
Create a copy of the Duckietown ROS template.
Create a subscriber node that is able to obtain the encoder information from both encoders.
Run your node and the Keyboard Control node.
Manually drive your Duckiebot around for ~10 seconds, and record a rosbag with the following parameters: encoder ticks (left and right), wheel commands.
You could record the data from the topics directly with a rosbag (if Keyboard Control is running), but creating the subscriber node is necessary for the next step.
Do the following:
Modify your previous code to also output the distance travelled by each wheel of the Duckiebot. Tip: this can be done by integrating the distance traveled by each wheel, but you need to take care of the direction of rotation of the wheels.
Publish the distance travelled per wheel to a new topic.
Manually drive your Duckiebot for ~10 seconds, and record a rosbag with the following values: wheel commands (left, right), encoder ticks (left, right), distance traveled per wheel (left, right).
Modified 2020-10-29 by Aleksandar Petrov
Now that we know how to work with the information from the wheel encoders, it is time to make something useful out of them. The task for now will be to implement some calibration functions with the encoders.
In Duckietown, Duckiebots are modeled using a differential drive model, which depends on several parameters such as the baseline (or distance between the two wheels of the robot), and the wheel radius. To simplify our lives, we assume these are constant values, the same across all Duckiebots. Nevertheless, in the real world this is often not the case, as you have already seen. To overcome this modeling limitation we usually perform wheel calibration, where we manually update some parameters from our configuration files (such as the trim value). While this helps to solve individual motor differences, it can still be improved by using the wheel encoders.
We can use the wheel encoders to obtain an accurate model, which extracts the parameters for your own Duckiebot! We will be updating the baseline
and radius
parameters used by the kinematics_node.py. Note that all these parameters can be modified using the rosparam set
commands. However, to make the change permanent by writing it to the corresponding configuration file, you would need to use the save_calibration
ros service call.
Do the following:
Create a copy of the Duckietown ROS template or use your template from the previous exercise.
Run Keyboard control and manually control your Duckiebot.
Run your Duckiebot on a straight line for a fixed length (e.g. 1m, or 1 tile) and extract the value of the wheel radius. You might get slightly different values for each wheel, so take the average.
Use rosparam set
commands to update the radius parameter in your kinematics configuration file.
After updating the parameters, make the change permanent by calling the save_calibration
service to save the file: rosservice call /DUCKIEBOT_NAME/kinematics_node/save_calibration
.
the wheel radius can be found directly from the following formula.
Deliverable: new radius value obtained. Can also be found in /data/config/calibrations/kinematics/HOSTNAME.yaml
, after you called the save_calibration
service.