Start the car, run the program in the terminal, and the URDF model will be displayed in rviz.
Open the terminal and enter the following command to enter the docker,
./docker_ros2.sh
The following interface appears, which means that you have successfully entered Docker. Now you can control the car through commands.

Load URDF and generate a simulation controller and start rviz, input in the terminal,
xxxxxxxxxxros2 launch yahboomcar_description display_launch.py
Then, use the mouse to adjust the viewing angle and slide the simulated controller just created, and you can see the tires/camera of the car changing.

l1_Joint: Control the left front wheel
l2_Joint: Control the left rear wheel
r1_Joint: Control the right front wheel
r2_Joint: Control the right rear wheel
arm1_Joint: Control gimbal 1
arm2_Joint: Control gimbal 2
Randomize: Randomly publish values to each joint
Center: All joints return to the center
Code location,
xxxxxxxxxx/root/yahboomcar_ws/src/yahboomcar_description/launch
display_launch.py
xfrom ament_index_python.packages import get_package_share_path
from launch import LaunchDescriptionfrom launch.actions import DeclareLaunchArgumentfrom launch.substitutions import Command, LaunchConfiguration
from launch_ros.actions import Nodefrom launch_ros.parameter_descriptions import ParameterValue
def generate_launch_description(): urdf_tutorial_path = get_package_share_path('yahboomcar_description') default_model_path = urdf_tutorial_path / 'urdf/Raspbot-V2.urdf' default_rviz_config_path = urdf_tutorial_path / 'rviz/raspbotv2.rviz'
model_arg = DeclareLaunchArgument(name='model', default_value=str(default_model_path), description='Absolute path to robot urdf file') robot_description = ParameterValue(Command(['xacro ', LaunchConfiguration('model')]), value_type=str) rviz_arg = DeclareLaunchArgument(name='rvizconfig', default_value=str(default_rviz_config_path), description='Absolute path to rviz config file') robot_state_publisher_node = Node( package='robot_state_publisher', executable='robot_state_publisher', parameters=[{'robot_description': robot_description}] )
joint_state_publisher_gui_node = Node( package='joint_state_publisher_gui', executable='joint_state_publisher_gui' )
tf_base_footprint_to_base_link = Node( package='tf2_ros', executable='static_transform_publisher', arguments=['0', '0', '0.05', '0.0', '0.0', '0.0', 'base_footprint', 'base_link'], ) rviz_node = Node( package='rviz2', executable='rviz2', name='rviz2', output='screen', arguments=['-d', LaunchConfiguration('rvizconfig')], ) return LaunchDescription([ model_arg, joint_state_publisher_gui_node, robot_state_publisher_node, tf_base_footprint_to_base_link, rviz_arg, rviz_node ])
/root/yahboomcar_ws/src/yahboomcar_description/urdf/Raspbot-V2.urdfURDF, the full name is Unified Robot Description Format, translated into Chinese as Unified Robot Description Format, is a robot model file described in XML format, similar to D-H parameters.
xxxxxxxxxx<?xml version="1.0" encoding="utf-8"?>
The first line is a required field for XML and describes the version information of XML.
xxxxxxxxxx<robot name="RaspbotV2"></robot>The second line describes the current robot name; all information about the current robot is included in the [robot] tag.
Relationship between link and joint: two links are connected by joints, imagine that the arm has a forearm (link) and an upper arm (link) connected by an elbow joint (joint).
1), Introduction
In the URDF descriptive language, link is used to describe physical properties,
Links can also describe the size of the connecting rod (size)\color (color)\shape (shape)\inertial matrix (inertial matrix)\collision parameters (collision properties), etc. Each Link will become a coordinate system.
2), Sample code
xxxxxxxxxx<link name="base_link"> <inertial> <origin xyz="0.013209067968915 0.000305835286849597 0.034565647785585" rpy="0 0 0" /> <mass value="0.315736522899678" /> <inertia ixx="0.000126930677782624" ixy="-1.93570093947537E-07" ixz="-3.2159760519397E-08" iyy="0.000217028578454845" iyz="3.16386759318505E-07" izz="0.000309637617387382" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://yahboomcar_description/meshes/base_link.STL" /> </geometry> <material name=""> <color rgba="0.203921568627451 0.203921568627451 0.203921568627451 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://yahboomcar_description/meshes/base_link.STL" /> </geometry> </collision> </link>Describes the relationship between two joints, motion position and speed limits, kinematic and dynamic properties. There are several types of joints:
2), sample code
xxxxxxxxxx <joint name="arm1_Joint" type="revolute"> <limit effort="100" velocity="1" lower="-1.57" upper="1.57"/> <origin xyz="0.058 0 0.0575" rpy="0 0 0" /> <parent link="base_link" /> <child link="arm1_Link" /> <axis xyz="0 0 1" /> <limit lower="0" upper="0" effort="0" velocity="0" /> </joint>In the [joint] tag, the name attribute is a required item, describing the name of the joint, and it is unique. In the [joint] tag, the type attribute is filled in with the six major joint types.
3), Tag introduction