ROS Driver Instructions

Overview

The ROS chassis driver xqserial_server package is responsible for the differential solution of the subscribed /cmd_vel topic, and then converts it into a serial port command for the motor driver. At the same time, the serial port package information uploaded by the driver is processed, and then organized and published into the topic of odometer and sensor data.

Hardware connection

The motor driver and the host are connected through a USB to rs232 module (corresponding to "motor serial port"). The serial port should be bound to the USB port through udev rules and mapped to ttyUSB001. Serial port parameters are baud rate 115200, 8 data bits, 1 stop bit, no parity.

Please operate the wiring of the driver according to the driver manual. Before debugging the xqserial_server package, you need to ensure that the mtools software can normally control the forward and reverse rotation of the motor in a closed loop, otherwise the driver may be burned.

Ubuntu Host serial port permission setting and device number mapping

We are using a usb to rs232 module, and ubuntu will recognize it as a ttyUSB0 device by default. This can be queried with the ls /dev command. The identified device number is random, in order to map the serial port number to ttyUSB001, and set the device user read and write permissions at the same time. We can do this with udev rules.

For details, refer to Step 3 of the following post. The use and realization principle of automatic charging function package

package compilation

It involves the basic knowledge of ros workspace, ros package, catkin_make, ros workspace source command, and git. If you are not sure about these, please learn them from Google.

First git clone to download the xqserial_server package and put it in the src folder of the ros workspace, switch to the lungu branch, and finally compile it with catkin_make.

Assuming your ros workspace is in ~/catkin_ws, the following are all instructions for downloading and compiling.

cd ~/catkin_ws/src/
git clone https://github.com/BluewhaleRobot/xqserial_server.git
cd xqserial_server
git checkout lungu
cd ~/catkin_ws/
catkin_make

executable nodes

After catkin_make is compiled, an executable node xqserial_server will be generated, and a launch file xqserial.launch that can be used directly has been provided in the launch folder. visualization.py in the script folder is a python script file that can be used to visualize the IMU data published by xqserial_server.

xqserial_server Node

The xqserial_server node is the master node of the package, which involves the processing and publishing of data such as differential speed calculation, odometer, sensor, and tf. In hardware, this node accesses the serial device of the driver. The ROS configuration information for this node will be described in detail below.

Subscribed topic data

Topic Message type description
/cmd_vel geometry_msgs/Twist The topic of speed is resolved into motor control commands after subscription.
/imu_cal std_msgs/Bool IMU auto-calibration command, set to true to trigger auto-calibration. At this time, the robot needs to wait for 2 minutes, and cannot be triggered repeatedly within 2 minutes.
/globalMoveFlag std_msgs/Bool When set to true, the /cmd_vel command takes effect; when set to false, /cmd_vel is disabled.
/barDetectFlag std_msgs/Bool Set to true to enable ultrasonic obstacle avoidance, false to disable ultrasonic and infrared obstacle avoidance.

Published topic data, 50hz frequency

Topic Message type description
/xqserial_server/Odom nav_msgs/Odometry Chassis odometer, angle part has been integrated with IMU.
/xqserial_server/StatusFlag std_msgs/Int32 A value of 0 indicates that the driver is still initializing, and a value of 1 indicates that processing state is normal. A value of 2 means IR is triggered.
/xqserial_server/Twist geometry_msgs/Twist The speed of the chassis feedback, the linear speed is the encoder feedback value, and the angular speed is the IMU return value.
/xqserial_server/Power std_msgs/Float64 Battery voltage in V.
/xqserial_server/Pose2D geometry_msgs/Pose2D Two-dimensional pose data, you can easily view the coordinates and angles of the odometer.
/xqserial_server/IMU sensor_msgs/Imu IMU topic data, the tf relationship of IMU needs to be adjusted in launch according to the following settings.
/xqserial_server/Sonar1 sensor_msgs/Range Ultrasonic module S1 topic data, tf relationship needs to be adjusted in launch according to the following settings.
/xqserial_server/Sonar2 sensor_msgs/Range Ultrasonic module S2 topic data, tf relationship needs to be adjusted in launch according to the following settings.

Node parameters

Parameter Type Defaults Description
~port String /dev/ttyUSB001 Motor driver serial port name
~wheel_separation double 0.36 The distance between the centers of the power wheels or tracks on both sides, in meters
~wheel_radius double 0.0825 The radius of the power wheel or track, in meters
~max_speed double 5.0 The maximum speed of the wheel or the maximum speed of the crawler power wheel, in revolutions per second

Published tf transform

odom→base_footprint 50hz Publishing frequency,base_footprint in the center of the car.

Calibration IMU

Place the trolley horizontally and still, and publish the ros topic to start the IMU self-calibration. During the calibration process of about 2 minutes, the trolley cannot be moved or collided.

rostopic pub /imu_cal std_msgs/Bool '{data: true}' -1

During the calibration process, the /xqserial_server/IMU topic data is always zero, and returns to the normal value after the calibration is completed. Through this topic data, the calibration progress and calibration result can be judged.

Calibrate Robot Parameters

Before performing the following operations, you need to complete the IMU calibration in step 6, because the IMU will affect the odometer feedback accuracy.

Calibrate wheel_radius

Calibration principle:

The tape measure can measure the actual distance of the car (set to L), and the topic /xqserial_server/Pose2D can check the feedback distance of the car odometer (set to l), so we can get the ratio of L/l (the value after calibration should be 1) , this ratio is the scaling factor of the wheel radius parameter wheel_radius in the launch file. Multiply this ratio by the current value to get the calibrated value.

After calibration wheel_radius = Before calibration wheel_radius * L / l

Calibration steps:

Remote control the car to the starting line, the angle of the car should be aligned, and then restart the xqserial_server package launch file to reset the odometer to zero. Then remote control car moves about 2 meters in a straight line, record the forward distance L of the car measured with a tape measure, and the topic feedback value l, and calculate the L/l ratio. Obtain the calibrated wheel_radius value according to the calibration principle, modify the wheel radius parameter in the launch file to this new value, and then restart the launch file, the radius calibration is completed.

Calibrate wheel_separation

Note: The calibration of the wheel radius needs to be completed before calibration.

Calibration principle:

The angular velocity feedback value in the /xqserial_server/Twist topic is calculated by the IMU, so it can be used as a reference value W, and the angular velocity value in the /cmd_vel topic is the set value w. The calculated W/w ratio is the scaling factor for the wheel spacing parameter. This value does not need to be very precise, because it will only affect the accuracy of the angular velocity control, not Affects the accuracy of the angle part of the odometer. If you want to get accurate values, it is recommended to write a python node to subscribe to these two topics, and get a more accurate ratio by calculating the average value.

After calibration wheel_separation = Before calibration wheel_separation * W /w

Calibration steps:

remote control car rotates in place, and the calibrated wheel_separation value is obtained according to the calibration principle. Modify the wheel spacing parameter in the launch file to this new value, then restart the launch file, and the wheel spacing parameter calibration is complete.

results matching ""

    No results matching ""