4 使用smartcar进行仿真
博客转自古-月:http://blog.csdn.net/hcx25909
之前的博客中,我们使用rviz进行了TurtleBot的仿真,而且使用urdf文件建立了自己的机器人smartcar,本篇博客是将两者进行结合,使用smartcar机器人在rviz中进行仿真。
一、模型完善
之前我们使用的都是urdf文件格式的模型,在很多情况下,ROS对urdf文件的支持并不是很好,使用宏定义的.xacro文件兼容性更好,扩展性也更好。所以我们把之前的urdf文件重新整理编写成.xacro文件。.xacro文件主要分为三部分:
1、机器人主体
<?xml version="1.0"?> <robot name="smartcar" xmlns:xacro="http://ros.org/wiki/xacro"> <property name="M_PI" value="3.14159"/> <!-- Macro for SmartCar body. Including Gazebo extensions, but does not include Kinect --> <include filename="$(find smartcar_description)/urdf/gazebo.urdf.xacro"/> <property name="base_x" value="0.33" /> <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="100" velocity="100"/> <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="100" velocity="100"/> <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="100" velocity="100"/> <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="100" velocity="100"/> <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属性部分
<?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、主文件
<?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"> <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文件
在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="driver.py" 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.vcg" /> </launch>
古月的源代码可在此处找到:http://download.csdn.net/detail/hcx25909/5487985,不过他的代码是针对Fuerte版本,所以配置文件要做一些修改,包括如下内容
- urdf.vcg修改为urdf.rviz
-
<node name="arbotix" pkg="arbotix_python" type="driver.py" output="screen"> #改为 <node name="arbotix" pkg="arbotix_python" type="arbotix_driver" output="screen"
- lauch和urdf文件夹内的配置文件名字由urdf.vcg改为urdf.rviz
三、仿真测试
首先运行lanuch,既可以看到rviz中的机器人:
roslaunch smartcar_description smartcar_display.rviz.launch
发布一条动作的消息。
rostopic pub -r 10 /cmd_vel geometry_msgs/Twist '{linear: {x: 0.5, y: 0, z: 0}, angular: {x: 0, y: 0, z: 0.5}}'
四、节点关系
rosrun rqt_graph rqt_graph
Nodes/Topics