It is recommended to study the code in P3DX, which is very useful for reference.
The very important role of xacro is to use macro-like methods to quickly build models using parameterization.
A ROS/Gazebo Pioneer 3DX model created by Rafael Berkvens modified by Mario Serna Hernández. 地址:https://github.com/mario-serna/pioneer_p3dx_model
File 1: pxdx.xacro
Two other documents were cited at the beginning, which will be discussed later.
There are three main parts in the link: delete the original mesh file after simplification, and the mesh can reference the 3D model to beautify the effect.
Three parts: inertial, visual, collision
Represents the inertial element, the visual element and the collision element respectively
Joint represents the connection relationship between links, which can be revolute or fixed
<?xml version="1.0"?>
<!--
This is the xacro description of a Pioneer 3DX, to be used in rviz and gazebo.
Copyright (C) 2013 Rafael Berkvens [email protected]
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
This project is based on work by Tracy Davies, where it was in turn based on
work original in ucs-ros-pkg.-->
<robot name="pxdx" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- import all gazebo-customization elements, including gazebo colors -->
<xacro:include filename="pxdx.gazebo" />
<!-- import the pioneer 3dx's wheels -->
<xacro:include filename="pxdx_wheel.xacro" />
<!-- chassis -->
<link name="base_link">
<inertial>
<mass value="3.5" />
<!--<origin xyz="-0.025 0 -0.223"/> -->
<origin xyz="-0.05 0 0" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />
</inertial>
<visual name="base_visual">
<origin xyz="-0.045 0 0.145" rpy="0 0 0" />
<geometry name="pioneer_geom">
<box size="0.35 0.25 0.14" />
</geometry>
<material name="ChassisRed">
<color rgba="0.851 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<origin xyz="-0.045 0 0.145" rpy="0 0 0" />
<geometry>
<box size="0.35 0.25 0.14" />
</geometry>
</collision>
</link>
<!-- top_plate -->
<link name="top_plate">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="top_geom">
<box size="0.45 0.38 0.01" />
</geometry>
<material name="TopBlack">
<color rgba="0.038 0.038 0.038 1.0" />
</material>
</visual>
<collision>
<origin xyz="0.0 0 0" rpy="0 0 0" />
<geometry name="pioneer_geom">
<box size="0.45 0.38 0.01" />
</geometry>
</collision>
</link>
<joint name="base_top_joint" type="fixed">
<origin xyz="-0.045 0 0.234" rpy="0 0 0" />
<parent link="base_link" />
<child link="top_plate" />
</joint>
<!-- swivel -->
<link name="swivel">
<inertial>
<mass value="0.1" />
<origin xyz="0 0 0" />
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="pioneer_geom">
<box size="0.01 0.01 0.01" />
</geometry>
<material name="swivel">
<color rgba="0.5 0.5 0.5 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.01 0.01 0.01" />
</geometry>
</collision>
</link>
<joint name="base_swivel_joint" type="continuous">
<origin xyz="-0.185 0 0.055" rpy="0 0 0" />
<axis xyz="0 0 1" />
<anchor xyz="0 0 0" />
<limit effort="100" velocity="100" k_velocity="0" />
<joint_properties damping="0.0" friction="0.0" />
<parent link="base_link" />
<child link="swivel" />
</joint>
<!-- center_hubcap -->
<link name="center_hubcap">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943" />
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="pioneer_geom">
<box size="0.01 0.01 0.01" />
</geometry>
<material name="swivel">
<color rgba="0.5 0.5 0.5 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.01 0.01 0.01" />
</geometry>
</collision>
</link>
<joint name="swivel_hubcap_joint" type="continuous">
<origin xyz="-0.026 0 -0.016" rpy="0 0 0" />
<axis xyz="0 1 0" />
<anchor xyz="0 0 0" />
<limit effort="100" velocity="100" k_velocity="0" />
<joint_properties damping="0.0" friction="0.0" />
<parent link="swivel" />
<child link="center_wheel" />
</joint>
<!-- center_wheel -->
<link name="center_wheel">
<inertial>
<mass value="0.1" />
<origin xyz="0 0 0" />
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943" />
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="${-3.1415927/2.0} 0 0" />
<geometry name="pioneer_geom">
<cylinder radius="0.0375" length="0.01" />
</geometry>
<material name="WheelBlack">
<color rgba="0.117 0.117 0.117 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${-3.1415927/2.0} 0 0" />
<geometry>
<cylinder radius="0.0375" length="0.01" />
</geometry>
</collision>
</link>
<joint name="center_wheel_joint" type="fixed">
<origin xyz="-0.0035 0 -0.001" rpy="0 0 0"/>
<parent link="center_wheel"/>
<child link="center_hubcap"/>
</joint>
<xacro:p3dx_wheel suffix="left" parent="base_link" reflect="1"/>
<xacro:p3dx_wheel suffix="right" parent="base_link" reflect="-1"/>
<!-- lms100 laser -->
<link name="lms100">
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.1 0.1 0.1" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.1 0.1 0.1" />
</geometry>
</collision>
</link>
<joint name="lms100_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0.3 0 0.15" rpy="0 0 0" />
<parent link="base_link" />
<child link="lms100" />
</joint>
</robot>
The second file: pxdx.gazebo is
mainly used to define gazebo-related elements including plug-ins
<?xml version="1.0"?>
<!--
This is the gazebo urdf description of a Pioneer 3DX.
Copyright (C) 2013 Rafael Berkvens [email protected]
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
-->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- properties (constants) -->
<xacro:property name="ns" value="pxdx" />
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/${ns}</robotNamespace>
</plugin>
</gazebo>
<!-- base_link -->
<gazebo reference="base_link">
<material>Gazebo/Red</material>
</gazebo>
<!-- top_plate -->
<gazebo reference="top_plate">
<material>Gazebo/Black</material>
</gazebo>
<!-- swivel -->
<gazebo reference="swivel">
<material>Gazebo/Grey</material>
</gazebo>
<!-- center_hubcap -->
<gazebo reference="center_hubcap">
<material>Gazebo/Grey</material>
</gazebo>
<!-- center_wheel -->
<gazebo reference="center_wheel">
<material>Gazebo/Black</material>
<mu1>10.0</mu1>
<mu2>10.0</mu2>
<kp>1000000.0</kp>
<kd>1.0</kd>
</gazebo>
<!-- differential drive -->
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<alwaysOn>true</alwaysOn>
<legacyMode>0</legacyMode>
<robotNamespace>/${ns}</robotNamespace>
<updateRate>100</updateRate>
<leftJoint>base_right_wheel_joint</leftJoint>
<rightJoint>base_left_wheel_joint</rightJoint>
<wheelSeparation>0.39</wheelSeparation>
<wheelDiameter>0.15</wheelDiameter>
<wheelAcceleration>1.0</wheelAcceleration>
<wheelTorque>5</wheelTorque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>base_footprint</odometryFrame>
<robotBaseFrame>base_link</robotBaseFrame>
<publishWheelTF>0</publishWheelTF>
<publishOdom>1</publishOdom>
<publishWheelJointState>0</publishWheelJointState>
</plugin>
</gazebo>
<!-- ground truth -->
<gazebo>
<plugin name="p3d_base_controller" filename="libgazebo_ros_p3d.so">
<alwaysOn>true</alwaysOn>
<updateRate>50.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>base_pose_ground_truth</topicName>
<robotNamespace>/${ns}</robotNamespace>
<gaussianNoise>0.01</gaussianNoise>
<frameName>map</frameName>
<!-- initialize odometry for fake localization -->
<xyzOffsets>0 0 0</xyzOffsets>
<rpyOffsets>0 0 0</rpyOffsets>
</plugin>
</gazebo>
<!-- lms100 -->
<gazebo reference="lms100">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-1.57</min_angle>
<max_angle>1.57</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<!-- Noise parameters based on published spec for Hokuyo laser achieving
"+-30mm" accuracy at range < 10m. A mean of 0.0m and stddev of 0.01m will
put 99.7% of samples within 0.03m of the true reading. -->
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>laser_scan</topicName>
<robotNamespace>/${ns}</robotNamespace>
<frameName>lms100</frameName>
</plugin>
</sensor>
</gazebo>
<gazebo>
<plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
<jointName>base_right_wheel_joint,base_left_wheel_joint,swivel_hubcap_joint,base_swivel_joint</jointName>
<robotNamespace>/${ns}</robotNamespace>
</plugin>
</gazebo>
</robot>
Important plugins:
joint_state_publisher publishes joint state
ros_laser generates point cloud
ros_diff controls movement
ros_p3d publishes the real trajectory
ros_control connects to the controller
The third file: pxdx_wheel.xacro
<?xml version="1.0"?>
<!--
This is the xacro description of a wheel of the Pioneer 3DX.
Copyright (C) 2013 Rafael Berkvens [email protected]
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
This project is based on work by Tracy Davies, where it was in turn based on
work original in ucs-ros-pkg.
-->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- properties (constants) -->
<xacro:property name="M_PI" value="3.14159" />
<!-- right/left hubcap + wheel -->
<xacro:macro name="p3dx_wheel" params="suffix parent reflect">
<!-- wheel -->
<link name="p3dx_${suffix}_wheel">
<inertial>
<mass value="0.5" />
<origin xyz="0 0 0" />
<inertia ixx="0.012411765597" ixy="0" ixz="0" iyy="0.015218160428"
iyz="0" izz="0.011763977943" />
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="${-3.1415927/2} 0 0" />
<geometry name="pioneer_geom">
<cylinder radius="0.09" length="0.01" />
</geometry>
<material name="WheelBlack">
<color rgba="0.117 0.117 0.117 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${-3.1415927/2} 0 0" />
<geometry>
<!--<mesh filename="package://p3dx_description/meshes/${suffix}_wheel.stl"/> -->
<cylinder radius="0.09" length="0.01" />
</geometry>
</collision>
</link>
<joint name="base_${suffix}_hubcap_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="p3dx_${suffix}_wheel" />
<child link="p3dx_${suffix}_hubcap" />
</joint>
<!-- hubcap -->
<link name="p3dx_${suffix}_hubcap">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.012411765597" ixy="0" ixz="0" iyy="0.015218160428"
iyz="0" izz="0.011763977943" />
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="pioneer_geom">
<box size="0.01 0.01 0.01" />
</geometry>
<material name="HubcapYellow">
<color rgba="1.0 0.811 0.151 1.0" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.01 0.01 0.01" />
</geometry>
</collision>
</link>
<joint name="base_${suffix}_wheel_joint" type="continuous">
<axis xyz="0 1 0" />
<anchor xyz="0 0 0" />
<limit effort="100" velocity="100" />
<joint_properties damping="0.0" friction="0.0" />
<origin xyz="0 ${reflect*0.158} 0.091" rpy="0 0 0" />
<parent link="base_link" />
<child link="p3dx_${suffix}_wheel" />
</joint>
<!-- gazebo elements -->
<transmission name="${parent}_${suffix}_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_${suffix}_wheel_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="base_${suffix}_wheel_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>${reflect * 624/35 * 80/19}</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="p3dx_${suffix}_hubcap">
<material>Gazebo/Yellow</material>
</gazebo>
<gazebo reference="p3dx_${suffix}_wheel">
<material>Gazebo/Black</material>
<mu1>0.5</mu1>
<mu2>50.0</mu2>
<kp>100000000.0</kp>
<kd>1.0</kd>
</gazebo>
</xacro:macro>
</robot>
Note that the virtual interface is mainly defined in transmission for connection control
Then you can use the launch file to start
<launch>
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="pxdx.yaml" command="load"/>
<param name="robot_description" command="$(find xacro)/xacro 'pxdx.xacro'"/>
<!-- load the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
ns="pxdx/" output="screen" args="--stopped
joint1_position_controller
joint2_position_controller
joint_state_controller"/>
<!-- push robot_description to factory and spawn robot in gazebo -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"
args="-z 1.0 -unpause -urdf -model pxdx -param robot_description" respawn="false" output="screen" >
</node>
<!-- convert joint states to TF transforms for rviz, etc -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/pxdx/joint_states" />
<param name="tf_prefix" value="pxdx"/>
</node>
</launch>
After rviz starts
Set fixed frame = pxdx/base_footprint
Add robot model and odom and laser_scan
After saving the config file, you can pass
rosrun rviz rviz -d pxdx.rviz
roslaunch pxdx.launch
#通过twist键盘控制运动
rosrun teleop_twist_keyboard teleop_twist_keyboard.py /cmd_vel:=/pxdx/cmd_vel
Just look at the imperfect places.