sample_sai_robot.urdf
<?xml version="1.0"?>
<robot name="sai_robot">
<link name="base_link" />
<link name="robot_body_layer">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<cylinder radius="0.25" length="0.01"/>
</geometry>
<material name="yellow">
<color rgba="1 0.4 0.0 1.0"/>
</material>
</visual>
</link>
<joint name="dummy_joint" type="fixed">
<origin xyz="0.0 0.0 0.095" rpy="0.0 0.0 0.0"/>
<parent link="base_link"/>
<child link="robot_body_layer"/>
</joint>
<link name="left_motor_link">
<visual>
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry>
<cylinder radius="0.02" length="0.08"/>
</geometry>
<material name="gray">
<color rgba="0.75 0.75 0.75 1.0"/>
</material>
</visual>
</link>
<link name="right_motor_link">
<visual>
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry>
<cylinder radius="0.02" length="0.08"/>
</geometry>
<material name="gray" />
</visual>
</link>
<joint name="left_motor_join" type="fixed">
<origin xyz="0.125 0.22 -0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="left_motor_link"/>
</joint>
<joint name="right_motor_join" type="fixed">
<origin xyz="0.125 -0.22 -0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="right_motor_link"/>
</joint>
<link name="left_wheel_link">
<visual>
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry>
<cylinder radius="0.07" length="0.04"/>
</geometry>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
</visual>
</link>
<link name="right_wheel_link">
<visual>
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry>
<cylinder radius="0.07" length="0.04"/>
</geometry>
<material name="black" />
</visual>
</link>
<joint name="left_wheel_joint" type="continuous">
<origin xyz="0.0 0.06 0.0" rpy="0.0 0.0 0.0"/>
<parent link="left_motor_link"/>
<child link="left_wheel_link"/>
<axis xyz="0.0 1.0 0.0"/>
</joint>
<joint name="right_wheel_joint" type="continuous">
<origin xyz="0.0 -0.06 0.0" rpy="0.0 0.0 0.0"/>
<parent link="right_motor_link"/>
<child link="right_wheel_link"/>
<axis xyz="0.0 1.0 0.0"/>
</joint>
<link name="caster_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<sphere radius="0.045"/>
</geometry>
<material name="black" />
</visual>
</link>
<joint name="caster_joint" type="fixed">
<origin xyz=" -0.125 0.0 -0.05" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="caster_link"/>
</joint>
<link name="imu_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.1 0.1 0.01"/>
</geometry>
<material name="green">
<color rgba="0.42 0.54 0.45 1.0"/>
</material>
</visual>
</link>
<joint name="imu_joint" type="fixed">
<origin xyz=" -0.125 0.0 0.01" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="imu_link"/>
</joint>
<link name="laser_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<cylinder radius="0.05" length="0.05"/>
</geometry>
<material name="blue">
<color rgba="0.0 0.0 1.0 1.0"/>
</material>
</visual>
</link>
<joint name="laser_joint" type="fixed">
<origin xyz="0.0 0.0 0.03" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="laser_link"/>
</joint>
<link name="camera_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.03 0.15 0.02"/>
</geometry>
<material name="gold">
<color rgba="0.9 0.9 0.1 1.0"/>
</material>
</visual>
</link>
<joint name="camera_joint" type="fixed">
<origin xyz="0.18 0.0 0.015" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="camera_link"/>
</joint>
<link name="us_back_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.01 0.02 0.04"/>
</geometry>
<material name="red">
<color rgba="0.71 0.54 0.75 1.0"/>
</material>
</visual>
</link>
<link name="us_front_left_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.01 0.02 0.04"/>
</geometry>
<material name="red" />
</visual>
</link>
<link name="us_front_right_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.01 0.02 0.04"/>
</geometry>
<material name="red" />
</visual>
</link>
<joint name="us_back_joint" type="fixed">
<origin xyz=" -0.2 0.0 0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="us_back_link"/>
</joint>
<joint name="us_front_left_joint" type="fixed">
<origin xyz="0.18 0.12 0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="us_front_left_link"/>
</joint>
<joint name="us_front_right_joint" type="fixed">
<origin xyz="0.18 -0.12 0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="us_front_right_link"/>
</joint>
</robot >
simple_model_display.launch
<launch>
<arg name="model"
default="$(find begin1)/urdf/simple_sai_robot.urdf"/>
<arg name="rvizconfig"
default="$(find begin1)/rviz/simple_model.rviz" />
<arg name="gui" default="true" />
<param name="robot_description"
command="$(find xacro)/xacro $(arg model)" />
<node if="$(arg gui)" name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node unless="$(arg gui)" name="joint_state_publisher"
pkg="joint_state_publisher"
type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher"
type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)"
required="true" />
</launch>
注意:第3行和第5行填自己的功能包名称
还有
# package.xml文 件
...
<build_depend>urdf </build_depend>
<build_depend>xacro </build_depend>
...
<build_export_depend>urdf </build_export_depend>
<build_export_depend>xacro </build_export_depend>
...
<exec_depend>urdf </exec_depend>
<exec_depend>xacro </exec_depend>
# CMakeLists .txt文 件
find_package (catkin REQUIRED COMPONENTS
...
urdf
xacro
)
catkin_package (
...
... urdf xacro
...
)
启动launch文件
roslaunch begin1 simple_model_display.launch