创建机器人描述
catkin_create_pkg robot_description urdf xacro gazebo_ros gazebo_ros_control gazebo_plugins
URDF
robot_base.xacro
<robot name="robot_base" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="PI" value="3.1415926"/>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
<xacro:property name="base_footprint_radius" value="0.001" />
<xacro:property name="base_link_radius" value="0.1" />
<xacro:property name="base_link_length" value="0.08" />
<xacro:property name="earth_space" value="0.015" />
<xacro:property name="base_link_m" value="0.5" />
<link name="base_footprint">
<visual>
<geometry>
<sphere radius="${base_footprint_radius}" />
</geometry>
</visual>
</link>
<link name="base_link">
<visual>
<geometry>
<cylinder radius="${base_link_radius}" length="${base_link_length}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="yellow">
<color rgba="0.5 0.3 0.0 0.5" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="${base_link_radius}" length="${base_link_length}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
</collision>
<xacro:cylinder_inertial_matrix m="${base_link_m}" r="${base_link_radius}" h="${base_link_length}" />
</link>
<joint name="base_link2base_footprint" type="fixed">
<parent link="base_footprint" />
<child link="base_link" />
<origin xyz="0 0 ${earth_space + base_link_length / 2 }" />
</joint>
<gazebo reference="base_link">
<material>Gazebo/Yellow</material>
</gazebo>
<xacro:property name="wheel_radius" value="0.0325" />
<xacro:property name="wheel_length" value="0.015" />
<xacro:property name="wheel_m" value="0.05" />
<xacro:macro name="add_wheels" params="name flag">
<link name="${name}_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
<material name="black" />
</visual>
<collision>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
</collision>
<xacro:cylinder_inertial_matrix m="${wheel_m}" r="${wheel_radius}" h="${wheel_length}" />
</link>
<joint name="${name}_wheel2base_link" type="continuous">
<parent link="base_link" />
<child link="${name}_wheel" />
<origin xyz="0 ${flag * base_link_radius} ${-(earth_space + base_link_length / 2 - wheel_radius) }" />
<axis xyz="0 1 0" />
</joint>
<gazebo reference="${name}_wheel">
<material>Gazebo/Red</material>
</gazebo>
</xacro:macro>
<xacro:add_wheels name="left" flag="1" />
<xacro:add_wheels name="right" flag="-1" />
<xacro:property name="support_wheel_radius" value="0.0075" />
<xacro:property name="support_wheel_m" value="0.03" />
<xacro:macro name="add_support_wheel" params="name flag" >
<link name="${name}_wheel">
<visual>
<geometry>
<sphere radius="${support_wheel_radius}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="black" />
</visual>
<collision>
<geometry>
<sphere radius="${support_wheel_radius}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
</collision>
<xacro:sphere_inertial_matrix m="${support_wheel_m}" r="${support_wheel_radius}" />
</link>
<joint name="${name}_wheel2base_link" type="continuous">
<parent link="base_link" />
<child link="${name}_wheel" />
<origin xyz="${flag * (base_link_radius - support_wheel_radius)} 0 ${-(base_link_length / 2 + earth_space / 2)}" />
<axis xyz="1 1 1" />
</joint>
<gazebo reference="${name}_wheel">
<material>Gazebo/Red</material>
</gazebo>
</xacro:macro>
<xacro:add_support_wheel name="front" flag="1" />
<xacro:add_support_wheel name="back" flag="-1" />
</robot>
camera.xacro
<robot name="camera" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:property name="camera_length" value="0.01" />
<xacro:property name="camera_width" value="0.025" />
<xacro:property name="camera_height" value="0.025" />
<xacro:property name="camera_x" value="0.08" />
<xacro:property name="camera_y" value="0.0" />
<xacro:property name="camera_z" value="${base_link_length / 2 + camera_height / 2}" />
<xacro:property name="camera_m" value="0.01" />
<link name="camera">
<visual>
<geometry>
<box size="${camera_length} ${camera_width} ${camera_height}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="black" />
</visual>
<collision>
<geometry>
<box size="${camera_length} ${camera_width} ${camera_height}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<xacro:Box_inertial_matrix m="${camera_m}" l="${camera_length}" w="${camera_width}" h="${camera_height}" />
</link>
<joint name="camera2base_link" type="fixed">
<parent link="base_link" />
<child link="camera" />
<origin xyz="${camera_x} ${camera_y} ${camera_z}" />
</joint>
<gazebo reference="camera">
<material>Gazebo/Blue</material>
</gazebo>
</robot>
laser.xacro
<robot name="laser" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:property name="support_length" value="0.15" />
<xacro:property name="support_radius" value="0.01" />
<xacro:property name="support_x" value="0.0" />
<xacro:property name="support_y" value="0.0" />
<xacro:property name="support_z" value="${base_link_length / 2 + support_length / 2}" />
<xacro:property name="support_m" value="0.02" />
<link name="support">
<visual>
<geometry>
<cylinder radius="${support_radius}" length="${support_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="red">
<color rgba="0.8 0.2 0.0 0.8" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="${support_radius}" length="${support_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<xacro:cylinder_inertial_matrix m="${support_m}" r="${support_radius}" h="${support_length}" />
</link>
<joint name="support2base_link" type="fixed">
<parent link="base_link" />
<child link="support" />
<origin xyz="${support_x} ${support_y} ${support_z}" />
</joint>
<gazebo reference="support">
<material>Gazebo/White</material>
</gazebo>
<xacro:property name="laser_length" value="0.05" />
<xacro:property name="laser_radius" value="0.03" />
<xacro:property name="laser_x" value="0.0" />
<xacro:property name="laser_y" value="0.0" />
<xacro:property name="laser_z" value="${support_length / 2 + laser_length / 2}" />
<xacro:property name="laser_m" value="0.1" />
<link name="laser">
<visual>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="black" />
</visual>
<collision>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<xacro:cylinder_inertial_matrix m="${laser_m}" r="${laser_radius}" h="${laser_length}" />
</link>
<joint name="laser2support" type="fixed">
<parent link="support" />
<child link="laser" />
<origin xyz="${laser_x} ${laser_y} ${laser_z}" />
</joint>
<gazebo reference="laser">
<material>Gazebo/Black</material>
</gazebo>
</robot>
inertia.xacro 惯性矩阵
<robot name="inertia" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- Macro for inertia matrix -->
<xacro:macro name="sphere_inertial_matrix" params="m r">
<inertial>
<mass value="${m}" />
<inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0"
iyy="${2*m*r*r/5}" iyz="0"
izz="${2*m*r*r/5}" />
</inertial>
</xacro:macro>
<xacro:macro name="cylinder_inertial_matrix" params="m r h">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
izz="${m*r*r/2}" />
</inertial>
</xacro:macro>
<xacro:macro name="Box_inertial_matrix" params="m l w h">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(h*h + l*l)/12}" ixy = "0" ixz = "0"
iyy="${m*(w*w + l*l)/12}" iyz= "0"
izz="${m*(w*w + h*h)/12}" />
</inertial>
</xacro:macro>
</robot>
launch
<launch>
<!-- 将 Urdf 文件的内容加载到参数服务器 -->
<param name="robot_description" command="$(find xacro)/xacro $(find robot_description)/urdf/robot_car.xacro" />
<!-- 启动 gazebo -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find robot_description)/worlds/box_house.world" />
</include>
<!-- 在 gazebo 中显示机器人模型 -->
<node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description" />
</launch>
box_house.world 接: https://pan.baidu.com/s/1T17RWZF1DMeb6FhLc8a2tQ 密码: ka98
下面配置ros_control
<robot name="move" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="joint_trans" params="joint_name">
<transmission name="${joint_name}_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${joint_name}_motor">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<xacro:joint_trans joint_name="left_wheel2base_link" />
<xacro:joint_trans joint_name="right_wheel2base_link" />
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>Debug</rosDebugLevel>
<publishWheelTF>true</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>1</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<legacyMode>true</legacyMode>
<leftJoint>left_wheel2base_link</leftJoint>
<rightJoint>right_wheel2base_link</rightJoint>
<wheelSeparation>${base_link_radius * 2}</wheelSeparation>
<wheelDiameter>${wheel_radius * 2}</wheelDiameter>
<broadcastTF>1</broadcastTF>
<wheelTorque>30</wheelTorque>
<wheelAcceleration>1.8</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>
</robot>
robt_car.xacro 整合ros_control
<robot name="robot_car" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="inertia.xacro" />
<xacro:include filename="robot_base.xacro" />
<xacro:include filename="camera.xacro" />
<xacro:include filename="laser.xacro" />
<xacro:include filename="gazebo/move.xacro" />
</robot>
要点
两轮差速配置文件中需要注意的是 这几个参数
<xacro:joint_trans joint_name="left_wheel2base_link" />
<xacro:joint_trans joint_name="right_wheel2base_link" />
<leftJoint>left_wheel2base_link</leftJoint>
<rightJoint>right_wheel2base_link</rightJoint>
<wheelSeparation>${base_link_radius * 2}</wheelSeparation>
<wheelDiameter>${wheel_radius * 2}</wheelDiameter>
一定要对应好urdf中的配置 如果配置错误有些情况下没有错误提示
rostopic list
/clock
/cmd_vel
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/set_link_state
/gazebo/set_model_state
/joint_states
/odom
/rosout
/rosout_agg
/tf
存在/cmd_vel 和 /odom 等话题 说明配置成功
让它原地打转
rostopic pub -r 10 /cmd_vel geometry_msgs/Twist '{linear: {x: 0.2, y: 0, z: 0}, angular: {x: 0, y: 0, z: 0.5}}'