转自:https://www.ncnynl.com/archives/201609/843.html
总结:
一、机器人描述文件三个:
机器人主体body文件:
gazebo属性文件:
主文件 smartcar.urdf:
二、启动文件smartcar_display.rviz.launch:启动节点和模拟器。
三、新增smartcar_description/config/smartcar_arbotix.yaml文件:
四、urdf.rviz文件:
cp /opt/ros/indigo/share/urdf_tutorial/rviz/urdf.rviz
1.indigo版本机器人主体文件:smartcar_description/urdf/smartcar_body.urdf.xacro
- 修改
property
,为xacro:property
- 修改
include
, 为xacro:include
<?xml version="1.0"?>
<robot name="smartcar" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.14159"/>
<!-- Macro for SmartCar body. Including Gazebo extensions, but does not include Kinect -->
<xacro:include filename="$(find smartcar_description)/urdf/gazebo.urdf.xacro"/>
<xacro:property name="base_x" value="0.33" />
<xacro:property name="base_y" value="0.33" />
<xacro:macro name="smartcar_body">
<link name="base_link">
<inertial>
<origin xyz="0 0 0.055"/>
<mass value="1.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
<visual>
<geometry>
<box size="0.25 .16 .05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.055"/>
<material name="blue">
<color rgba="0 0 .8 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.055"/>
<geometry>
<box size="0.25 .16 .05" />
</geometry>
</collision>
</link> <link name="left_front_wheel">
<inertial>
<origin xyz="0.08 0.08 0.025"/>
<mass value="0.1" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial> <visual>
<geometry>
<cylinder length=".02" radius="0.025"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>
<geometry>
<cylinder length=".02" radius="0.025"/>
</geometry>
</collision>
</link> <joint name="left_front_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="left_front_wheel"/>
<origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>
<limit effort="" velocity=""/>
<joint_properties damping="0.0" friction="0.0"/>
</joint> <link name="right_front_wheel"> <inertial> <origin xyz="0.08 -0.08 0.025"/> <mass value="0.1" /> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> <visual> <geometry> <cylinder length=".02" radius="0.025"/> </geometry> <material name="black"> <color rgba="0 0 0 1"/> </material> </visual> <collision> <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/> <geometry> <cylinder length=".02" radius="0.025"/> </geometry> </collision> </link> <joint name="right_front_wheel_joint" type="continuous"> <axis xyz="0 0 1"/> <parent link="base_link"/> <child link="right_front_wheel"/> <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/> <limit effort="" velocity=""/> <joint_properties damping="0.0" friction="0.0"/> </joint> <link name="left_back_wheel"> <inertial> <origin xyz="-0.08 0.08 0.025"/> <mass value="0.1" /> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> <visual> <geometry> <cylinder length=".02" radius="0.025"/> </geometry> <material name="black"> <color rgba="0 0 0 1"/> </material> </visual> <collision> <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/> <geometry> <cylinder length=".02" radius="0.025"/> </geometry> </collision> </link> <joint name="left_back_wheel_joint" type="continuous"> <axis xyz="0 0 1"/> <parent link="base_link"/> <child link="left_back_wheel"/> <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/> <limit effort="" velocity=""/> <joint_properties damping="0.0" friction="0.0"/> </joint> <link name="right_back_wheel"> <inertial> <origin xyz="-0.08 -0.08 0.025"/> <mass value="0.1" /> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> <visual> <geometry> <cylinder length=".02" radius="0.025"/> </geometry> <material name="black"> <color rgba="0 0 0 1"/> </material> </visual> <collision> <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/> <geometry> <cylinder length=".02" radius="0.025"/> </geometry> </collision> </link> <joint name="right_back_wheel_joint" type="continuous"> <axis xyz="0 0 1"/> <parent link="base_link"/> <child link="right_back_wheel"/> <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/> <limit effort="" velocity=""/> <joint_properties damping="0.0" friction="0.0"/> </joint> <link name="head"> <inertial> <origin xyz="0.08 0 0.08"/> <mass value="0.1" /> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> <visual> <geometry> <box size=".02 .03 .03"/> </geometry> <material name="white"> <color rgba="1 1 1 1"/> </material> </visual> <collision> <origin xyz="0.08 0 0.08"/> <geometry> <cylinder length=".02" radius="0.025"/> </geometry> </collision> </link> <joint name="tobox" type="fixed"> <parent link="base_link"/> <child link="head"/> <origin xyz="0.08 0 0.08"/> </joint> </xacro:macro> </robot>
2.gazebo属性部分 smartcar_description/urdf/gazebo.urdf.xacro
<?xml version="1.0"?>
<robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://ros.org/wiki/xacro" name="smartcar_gazebo"> <!-- ASUS Xtion PRO camera for simulation --> <!-- gazebo_ros_wge100 plugin is in kt2_gazebo_plugins package --> <xacro:macro name="smartcar_sim"> <gazebo reference="base_link"> <material>Gazebo/Blue</material> </gazebo> <gazebo reference="right_front_wheel"> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="right_back_wheel"> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="left_front_wheel"> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="left_back_wheel"> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="head"> <material>Gazebo/White</material> </gazebo> </xacro:macro> </robot>
3.主文件:smartcar_description/urdf/smartcar.urdf.xacro
<?xml version="1.0"?>
<robot name="smartcar" xmlns:xi="http://www.w3.org/2001/XInclude" xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz" xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body" xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom" xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering" xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable" xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" xmlns:xacro="http://ros.org/wiki/xacro"> <xacro:include filename="$(find smartcar_description)/urdf/smartcar_body.urdf.xacro" /> <!-- Body of SmartCar, with plates, standoffs and Create (including sim sensors) --> <smartcar_body/> <smartcar_sim/>
</robot>
二、lanuch文件,smartcar_description/launch/smartcar_display.rviz.launch
<launch> <param name="/use_sim_time" value="false" /> <!-- Load the URDF/Xacro model of our robot --> <arg name="urdf_file" default="$(find xacro)/xacro.py '$(find smartcar_description)/urdf/smartcar.urdf.xacro'" /> <arg name="gui" default="false" />
<param name="robot_description" command="$(arg urdf_file)" />
<param name="use_gui" value="$(arg gui)"/>
<node name="arbotix" pkg="arbotix_python" type="arbotix_driver" output="screen">
<rosparam file="$(find smartcar_description)/config/smartcar_arbotix.yaml" command="load" />
<param name="sim" value="true"/>
</node> <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" > </node> <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher"> <param name="publish_frequency" type="double" value="20.0" /> </node> <!-- We need a static transforms for the wheels --> <node pkg="tf" type="static_transform_publisher" name="odom_left_wheel_broadcaster" args="0 0 0 0 0 0 /base_link /left_front_link 100" /> <node pkg="tf" type="static_transform_publisher" name="odom_right_wheel_broadcaster" args="0 0 0 0 0 0 /base_link /right_front_link 100" /> <node name="rviz" pkg="rviz" type="rviz" args="-d $(find smartcar_description)/urdf.rviz" /> </launch>
4.在indigo版本里,新增smartcar_description/config/smartcar_arbotix.yaml文件,内容为:
port: /dev/ttyUSB0
baud:
rate:
sync_write: True
sync_read: True
read_rate:
write_rate: controllers: {
# Pololu motors: cpr = 0.3888105m travel = ticks per meter (empirical: )
base_controller: {type: diff_controller, base_frame_id: base_link, base_width: 0.26, ticks_meter: , Kp: , Kd: , Ki: , Ko: , accel_limit: 1.0 }
}
5.urdf.rviz文件:(或者自己按照目录找到了copy过来,如果没有就先安装这个包:
urdf_tutorial
$ cp /opt/ros/indigo/share/urdf_tutorial/rviz/urdf.rviz
三、仿真测试
首先运行lanuch,既可以看到rviz中的机器人:
roslaunch smartcar_description smartcar_display.rviz.launch
然后在新建终端中运行:
rostopic pub -r /cmd_vel geometry_msgs/Twist '{linear: {x: 0.5, y: 0, z: 0}, angular: {x: 0, y: 0, z: 0.5}}'
运行结果:
如果小车跑不起来,把Global中的fixed frame改成odom,就好了