ROS Tutorial: Four motion modes(Differential, Track, Ackermann, Mecanum mode)
Differential mode
The four-wheel differential robot is a robot model with unique advantages. The main advantages are as follows:
- High flexibility: The four-wheel differential robot uses four independent drive wheels, which can achieve more flexible maneuverability. By controlling the speed and direction of each wheel, the robot can move, turn and rotate in any direction on the plane.
- Good stability: The wheels of the four-wheel differential robot are evenly distributed, and support independent control of different wheels, which can maintain stability under different road conditions. At the same time, due to the use of differential drive, the robot has better anti-rolling ability and performs more stably when encountering scenes such as slopes.
- Strong load capacity: The four-wheel differential robot has a strong load capacity and can carry larger items or equipment. Because of its good stability, it can perform heavy-load work in different terrains and environments.
- High safety: The four-wheel differential robot can be controlled by remote control or autonomous navigation, which can not only prevent people from directly contacting dangerous situation, but also has a high anti-collision ability.
The four-wheel differential robot has a wide range of applications in various scenarios, such as logistics, security, environmental monitoring, and other fields. It has particular advantages when the robot needs to have good stability.
A four-wheel differential motion robot can be simplified as a model shown in the figure below. Four wheels are driven by four separate motors. The robot can be controlled to move forward, backward, and steer only by controlling the velocity of the four wheels.
We give the robot a reference coordinate system. The red arrow is the positive direction of the X axis, the blue arrow is the positive direction of the Y axis, the Z axis is perpendicular to the screen outward along the origin, the coordinate origin is the center of mass of the robot, and the coordinate system satisfies the Ampere’s right-hand rule. When the velocity (size + direction) of the four wheels is the same, the robot can move forward and backward. When the velocities of the four wheels are not the same, the robot will turn.
Once the robot turns, it means that there is a turning center, which is the point ICR in the figure below. Taking the left front wheel as an example, the relative velocity direction of the contact point A of the wheel and the ground is shown in the figure. The resultant velocity direction and the line segment A-ICR are perpendicular to each other, and the tire can only rotate along the longitudinal component velocity direction. The velocity resolution shows that there is also a lateral component velocity along the wheel axis (motor axis).
Control the robot with the keyboard in differential mode
We can try to control limo in four-wheel differential mode. First, adjust limo to four-wheel differential mode, pull up the two latches, and turn 30 degrees clockwise to make the shorter line on the two latches points to the front of the vehicle body.
At this point, it is in insertion state. Fine-tune the tire angle to align the hole so that the latch is inserted. When the vehicle light turns yellow, the switch is successful.
Then, run the following commands:
Note: Before running the command, please make sure that the programs in other terminals have been terminated. The termination command is: Ctrl+c.
roslaunch limo_base limo_base.launch
Launch keyboard control node
roslaunch limo_bringup limo_teletop_keyboard.launch
Test
Assuming that the body parameters of a four-wheel differential chassis are known, including wheelbase, track width, wheel radius, etc., please write a C++ program to calculate the rotation speed of the four wheels of the chassis at any given linear velocity and angular velocity. Tip: You can use the kinematic model for calculation.
Track mode
Compared with other types of robots, tracked robots have the following advantages:
- Strong adaptability: tracked robots can adapt to complex terrain and harsh environments, such as deserts, snow, mud, etc., and can move more stably in these environments.
- Strong carrying capacity: Since tracked robots use chains and tracks to drive, they have a larger ground contact area and ground adhesion performance, and can better carry larger loads.
- Strong passing ability: tracked robots can cross some uneven obstacles, such as rivers, gullies, obstacles, etc., and have better obstacle crossing performance.
- Strong stability: Since tracked robots have a larger ground contact area and ground adhesion performance, they can maintain a more stable state, especially in uneven terrain.
- Strong friction: Since tracked robots have a larger ground contact area and more contact points, their friction is stronger and they can move more easily in scenes such as slopes.
Therefore, tracked robots are widely used in some special environments, such as field exploration, fire rescue, polar expeditions and other fields, especially in scenes where robots need to have stronger adaptability and obstacle crossing capabilities, they have more advantages.
In the track differential mode, a single-sided track can be equivalently regarded as an “infinite number of small wheels”, and the “speed” of the single-sided “infinite number of small wheels” is the same. Therefore, the steering mode of the track differential mode is the same as that of the four-wheel differential mode, which is also slide steering.
Specifically, the track differential motion and the four-wheel differential motion are achieved by controlling the relative velocity of the tracks (or wheels) on both sides, but there are also differences between them: the shear and pressure distribution generated by the track on the ground are different from those of the wheels. This difference has little effect when it comes to wheel speed control. When the wheel speeds are inconsistent, we can refer to the following simplified model.
Control the robot with the keyboard in track mode
Put the track directly on in the four-wheel differential mode. It is recommended to put it on the rear wheel first. In the track mode, please lift the doors on both sides to prevent scratches.
Run the commands:
Note: Before running the command, please make sure that the programs in other terminals have been terminated. The termination command is: Ctrl+c.
roslaunch limo_base limo_base.launch
Launch keyboard control node
roslaunch limo_bringup limo_teletop_keyboard.launch
Test
Title description: Please calculate the steering angle and travel distance required for the tracked vehicle from the starting position to the end position based on the kinematic model of the tracked chassis.
Known conditions:
● The starting position is (x_1, y_1), and the end position is (x_2, y_2);
● The tracked chassis wheelbase is L;
● The linear velocities of the tracks on both sides of the tracked chassis are v_L and v_R respectively.
Requirements:
● Calculate the steering angle and travel distance required for the tracked vehicle from the starting position to the end position.
Tips:
● According to the kinematic model of the tracked vehicle, calculate the angular velocity of the left and right tracks to solve the steering angle;
● According to the kinematic model of the tracked vehicle, calculate the distance traveled by the tracked vehicle.
Ackermann mode
Ackerman chassis is a car chassis that uses front-wheel steering. Its advantages are:
- High stability: The Ackerman chassis uses front-wheel steering, which can keep the car stable while driving, helping to avoid problems such as skidding or tipping when turning.
- Small turning radius: Due to the front-wheel steering, the Ackerman chassis can achieve a smaller turning radius when turning, which is suitable for scenes that need to operate in a small space.
- High control accuracy: The Ackerman chassis can control the movement of the car by controlling the steering angle of the front wheel and the speed of the rear wheel. The control accuracy is high and it is suitable for scenes that require high-precision control.
- Strong adaptability: The Ackerman chassis is flexible in design and can adapt to various working environments and task requirements. For example, it can be used in robot off-road, indoor inspection, autonomous navigation and other fields.
Therefore, the Ackerman chassis is widely used in various mobile robots, autonomous navigation robots and other fields, especially in scenes where robots need to have stability, small turning radius and high-precision control capabilities.
Begin with the simplified model of Ackermann motion mode. Similar to differential motion, when all four wheels are given the same velocity (magnitude + direction), the robot is capable of moving forward and backward. However, the differentiating factor lies in turning. To achieve this, the Ackermann steering geometry is employed to calculate the turning radius based on the angle of deflection of the two front wheels.
The geometric center of the robot is denoted by the point CENTER, whereas the midpoint of the rear rod is referred to as the point BASE. In this configuration, the robot executes a circular motion around the ICR, which corresponds to the minimum turning radius. From the diagram, the deflection angles of the two front wheels are not equal, with the difference between these angles (θA-θB) being known as the Ackermann angle. If the robot employs four-wheel drive in the Ackermann motion mode, the inner wheel’s velocity will be lower than that of the outer wheel during turning.
Control the robot with the keyboard in Ackermann mode
First pull up the pins on both sides and turn them 30 degrees clockwise so that the longer lines on the two pins point to the front of the vehicle.
Then the pins will lock. When the lights turn green and stay on, the switch is successful.
Run the command:
Note: Before running the command, please make sure that the programs in other terminals have been terminated. The termination command is: Ctrl+c.
roslaunch limo_base limo_base.launch
Launch keyboard control node:
roslaunch limo_bringup limo_teletop_keyboard.launch
Note: When the vehicle cannot go straight in Ackermann mode, the steering gear calibration is required.
Test
● In the Ackerman chassis, how to calculate the turning radius and speed of the chassis when the current wheel speed and turning angle are given? Please write a C++ program to input the current wheel speed and turning angle through the keyboard and output the calculated turning radius and speed.
Mecanum mode
Compared with other types of robots, the Mecanum wheel car has the following advantages:
- High maneuverability: The four wheels of the Mecanum wheel car are arranged in a diamond shape, which allows the robot to rotate and translate in place, and has high maneuverability.
- High precision: The Mecanum wheel car has high manipulation accuracy and can achieve extremely high positioning accuracy, which is suitable for scenes requiring high-precision positioning.
- Simple control: The control algorithm of the Mecanum wheel car is relatively simple, and the movement of the robot can be achieved through a simple kinematic control algorithm.
- Flexible movement: The movement mode of the Mecanum wheel car is very flexible, and a variety of movements can be achieved by controlling the speed and direction of each wheel, such as oblique movement, side sliding, rotation, etc.
- High load capacity: The structure of the Mecanum wheel car is relatively compact and can carry a large load, which is suitable for scenes that need to carry heavy objects.
Therefore, the Mecanum wheel car is widely used in some special scenes, such as autonomous navigation robots, indoor inspection robots, robot handling and other fields, especially in scenes where robots need to have high maneuverability and precision control capabilities, it has more advantages.
The Mecanum wheel is a special kind of wheel, which is composed of a hub and rollers: the hub is the main support of the entire wheel, and the rollers are passively moving drums (small wheels) mounted on the hub. The two form a complete big wheel. The angle between the hub axis and the roller shaft on the market can be roughly divided into 30 degrees, 45 degrees, and 60 degrees. In order to meet the geometric relationship of omnidirectional motion, the edge of the hub adopts a bending process to provide mounting holes for the shaft of the roller.
Assuming that the wheel rotates counterclockwise, the force analysis of the Mecanum wheel is carried out. In the coordinate system in the above figure, red represents the x axis, green represents the y axis, blue represents the z axis, the roller coordinate system is represented by a dotted line, and the hub coordinate system is represented by a solid line; the yellow arrow indicates the force analysis of the Mecanum wheel and roller; the blue arrow indicates the speed direction.
The rollers on the periphery of the Mecanum wheel are in contact with the ground. When the Mecanum wheel rotates around the hub axle, the rollers will generate frictional force Ff with the ground, and the force direction is the positive direction of the Y axis of the hub coordinate system. The orthogonal decomposition of Ff along the roller coordinate system shows that F1 is along the negative direction of the Y axis of the roller, and the size is √2/2Ff, and FII is along the positive direction of the X axis of the roller, and the size is √2/2Ff. F1 is the rolling friction of the roller, which causes wear to the roller and cannot change the direction of movement of the tire. FⅡ will force the roller to move in the positive direction of the X axis, so FⅡ is static friction, which promotes the roller to move relative to the ground.
Different wheel arrangements also require different control methods. The omnidirectional movement of the Mecanum wheel is simplified to the model shown in the figure above. The blue arrow indicates the direction of wheel movement, and the orange arrow represents the force analysis of the Mecanum wheel. Combining the forces, we will find that the mobile robot has only one forward force, so the robot will move forward at this time.
Combine the friction of each tire based on the previous four-wheel differential motion mode, the robot can move in any direction. Below are some examples of tire conditions when moving in different directions.
Control the robot with the keyboard in Mecanum mode
First, remove the hub cover and tire, leaving only the hub motor, then make sure the small roller of each Mecanum wheel faces the center of the vehicle body, install the Mecanum wheel with the M3*5 screws in the package, and finally use the remote control/APP to adjust to the Mecanum wheel mode.
Note: Before running the command, please make sure that the programs in other terminals have been terminated. The termination command is: Ctrl+c.
roslaunch limo_base limo_base.launch
Launch keyboard control node:
roslaunch limo_bringup limo_teletop_keyboard.launch
Test
● The robot chassis uses a Mecanum chassis, the distance from the front wheel to the rear wheel is L1, and the distance from the left and right wheels to the center of the robot is L2. Without considering the influence of motors and tires, please calculate the relationship between the robot’s speed and angular velocity on the x-axis and y-axis and the linear velocity and angular velocity of the wheels.
● There is a Mecanum chassis robot, the distance from the front wheel to the rear wheel is 50cm, and the distance from the left and right wheels to the center of the robot is 40cm. The robot is expected to drive to the left front at a speed of 3m/s, so what is the linear velocity of the left and right wheels of the robot? If the robot needs to rotate counterclockwise around the center at an angular velocity of 30 degrees/second, what are the angular velocities of the left and right wheels?
About Limo
Limo is a smart educational robot published by AgileX Robotics. More details please visit: https://global.agilex.ai/
If you are interested ROS and Limo, and want to discuss freely, you can join the discord community : AgileX Robotics !