Note: The ROS_DOMAIN_ID of the Raspberry Pi and the microROS control board need to be consistent. You can check [MicroROS Control Board Parameter Configuration] to set the microROS control board ROS_DOMAIN_ID. Check the tutorial [Connect MicroROS Agent] to determine whether the IDs are consistent.
The car connects to the agent, runs the program, and adjusts the parameters here through the dynamic parameter regulator to calibrate the linear speed of the car. The intuitive reflection of the calibrated linear speed is to give the car an instruction to go straight forward for 1 meter to see how far it actually ran and whether it is within the error range.
After successfully starting the Raspberry Pi, enter the following command in the terminal to start the agent,
sh ~/start_agent_rpi5.sh
Then, turn on the car switch and wait for the car to connect to the agent. The connection is successful, as shown in the figure below.
Open another terminal and enter the following command to enter docker.
xxxxxxxxxx
sh ros2_humble.sh
When the following interface appears, you have successfully entered docker. Now you can control the car through commands.
First, start the car's underlying data processing program. This program will release the TF transformation of odom->base_footprint. With this TF change, you can calculate "how far the car has gone" and input it at the terminal.
xxxxxxxxxx
ros2 launch yahboomcar_bringup yahboomcar_bringup_launch.py
Then start the car linear speed calibration program and enter the following command on the terminal.
xxxxxxxxxx
ros2 run yahboomcar_bringup calibrate_linear
Finally, enter the following command in the terminal to open the dynamic parameter adjuster.
xxxxxxxxxx
ros2 run rqt_reconfigure rqt_reconfigure
Note: There may not be the above nodes when you first open it. You can see all the nodes after clicking Refresh. The displayed calibrate_linear node is the node for calibrating linear speed.
In the rqt_reconfigure interface, select the calibrate_linear node. There is start_test below and click the box to the right to start calibration. Other parameters in the rqt interface are explained as follows:
test_distance:Calibrate the test distance, here the test goes forward 1 meter;
speed:Linear speed;
tolerance:Allowable error tolerance;
odom_linear_scale_correction:Linear speed proportional coefficient. If the test result is not ideal, just modify this value.;
start_test:test switch;
direction:It can be ignored. This value is used for the wheat wheel structure car. After modification, the linear speed of left and right movement can be calibrated.;
base_frame:The name of the base coordinate system;
odom_frame:The name of the odometer coordinate system.
Click start_test to start calibration. The car will monitor the TF transformation of base_footprint and odom, calculate the theoretical distance traveled by the car, wait until the error is less than the tolerance, and issue a parking instruction.
If the actual distance the car runs is not 1m, then modify the odom_linear_scale_correction parameter in rqt. After modification, click on the blank space. Click start_test again, reset start_test, and then click start_test again to calibrate. The same goes for modifying other parameters. You need to click on the blank space to write the modified parameters.
Source code reference path.
xxxxxxxxxx
/root/yahboomcar_ws/src/yahboomcar_bringup/yahboomcar_bringup
calibrate_linear.py,The core code is as follows,
x
#Monitor the TF transformation of base_footprint and odom
def get_position(self):
try:
now = rclpy.time.Time()
trans = self.tf_buffer.lookup_transform(self.odom_frame,self.base_frame,now)
#print("trans: ",trans)
return trans
except (LookupException, ConnectivityException, ExtrapolationException):
self.get_logger().info('transform not ready')
raise
return
#Get the current coordinates
self.position.x = self.get_position().transform.translation.x
self.position.y = self.get_position().transform.translation.y
#Calculate how far distance and error are
distance = sqrt(pow((self.position.x - self.x_start), 2) +pow((self.position.y - self.y_start), 2))
distance *= self.odom_linear_scale_correction
print("distance: ",distance)
error = distance - self.test_distance