第一次在gazebo里面跑自己的小车,很兴奋,在这里记录下。
urdf文件为dd_robot.urdf
<?xml version="1.0"?>
<robot name ="dd_robot">
<!--Base link-->
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0 "/>
<geometry>
<box size="0.4 0.5 0.25" />
</geometry>
<material name="yellow">
<color rgba="1 0.4 0 1"/>
</material>
</visual>
<!--base link collsion-->
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.4 0.5 0.25" />
</geometry>
</collision>
<inertial>
<mass value="5"/>
<inertia ixx="0.13" ixy="0.0" ixz="0.0"
iyy="0.21" iyz="0.0" izz="0.13"/>
</inertial>
</link>
<gazebo reference="base_link">
<material>Gazebo/Yellow</material>
</gazebo>
<!--joint_right_wheel-->
<joint name="joint_right_wheel" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="-0.1 -0.30 0.0" rpy="1.570795 0 0"/>
<axis xyz="0.0 0 1"/>
</joint>
<!--right link-->
<link name="right_wheel">
<visual>
<origin xyz="0 0 0" rpy="0 0 0 "/>
<geometry>
<cylinder radius="0.2" length="0.1"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<cylinder radius="0.2" length="0.1"/>
</geometry>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0"
iyy="0.005" iyz="0.0" izz="0.005"/>
</inertial>
</link>
<gazebo reference="right_wheel">
<material>Gazebo/Red</material>
</gazebo>
<!--joint_left_wheel-->
<joint name="joint_left_wheel" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz=" -0.10 0.3 0.0" rpy=" 1.570795 0 0"/>
<axis xyz="0.0 0 1.0"/>
</joint>
<!--left link-->
<link name="left_wheel">
<visual>
<origin xyz="0 0 0" rpy="0 0 0 "/>
<geometry>
<cylinder radius="0.2" length="0.1"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<cylinder radius="0.2" length="0.1"/>
</geometry>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0"
iyy="0.005" iyz="0.0" izz="0.005"/>
</inertial>
</link>
<gazebo reference="left_wheel">
<material>Gazebo/Red</material>
</gazebo>
<!--front_castor_joint-->
<joint name="front_castor_joint" type="fixed">
<parent link="base_link"/>
<child link="front_castor_link"/>
<origin xyz=" 0.1625 0 -0.1625" rpy="0.0 0.0 0.0"/>
<axis xyz="0.0 1 0.0"/>
</joint>
<!--front castor link-->
<link name="front_castor_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0 "/>
<geometry>
<sphere radius="0.0375"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<sphere radius="0.0375"/>
</geometry>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>
</link>
<gazebo reference="front_castor_link">
<material>Gazebo/Red</material>
</gazebo>
<link name="base_footprint">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
</link>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 0.2" rpy="0 0 0" />
<parent link="base_footprint"/>
<child link="base_link" />
</joint>
<!-- Transmission is important to link the joints and the controller -->
<transmission name="joint_left_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_left_wheel" />
<actuator name="joint_left_motor">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Transmission is important to link the joints and the controller -->
<transmission name="joint_right_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_right_wheel" />
<actuator name="joint_right_motor">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- controller -->
<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>
<publishOdomTF>true</publishOdomTF>
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<legacyMode>true</legacyMode>
<leftJoint>joint_left_wheel</leftJoint>
<rightJoint>joint_right_wheel</rightJoint>
<wheelSeparation>${0.5*2}</wheelSeparation>
<wheelDiameter>${2*0.2}</wheelDiameter>
<broadcastTF>1</broadcastTF>
<wheelTorque>30</wheelTorque>
<wheelAcceleration>1.8</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<odometrySource>odom</odometrySource>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>
</robot>
launch文件为dd_robot_gazebo.launch:
<launch>
<!-- 设置launch文件的参数 -->
<arg name="world_name" value="$(find ros_robotic)/worlds/playground.world"/>
<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"/>
<arg name="model" default="$(find ros_robotic)/urdf/dd_robot.urdf"/>
<!-- 运行gazebo仿真环境 -->
<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>
<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" >
<param name="publish_frequency" type="double" value="50.0" />
</node>
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" args=" -urdf -model dd_robot -param robot_description" respawn="false" output="screen" />
</launch>
运行roslaunch ros_robotic dd_robot_gazebo.launch
整个catkin_ws/src目录如下:
src
├── arbotix_ros
│ ├── arbotix
│ │ ├── CHANGELOG.rst
│ │ ├── CMakeLists.txt
│ │ └── package.xml
│ ├── arbotix_controllers
│ │ ├── bin
│ │ ├── CHANGELOG.rst
│ │ ├── CMakeLists.txt
│ │ └── package.xml
│ ├── arbotix_firmware
│ │ ├── CHANGELOG.rst
│ │ ├── CMakeLists.txt
│ │ ├── package.xml
│ │ └── src
│ ├── arbotix_msgs
│ │ ├── CHANGELOG.rst
│ │ ├── CMakeLists.txt
│ │ ├── msg
│ │ ├── package.xml
│ │ └── srv
│ ├── arbotix_python
│ │ ├── bin
│ │ ├── CHANGELOG.rst
│ │ ├── CMakeLists.txt
│ │ ├── demos
│ │ ├── mainpage.dox
│ │ ├── package.xml
│ │ ├── setup.py
│ │ └── src
│ ├── arbotix_sensors
│ │ ├── bin
│ │ ├── CHANGELOG.rst
│ │ ├── CMakeLists.txt
│ │ ├── package.xml
│ │ ├── setup.py
│ │ └── src
│ └── README.md
├── CMakeLists.txt -> /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake
├── ros_robotic
│ ├── CMakeLists.txt
│ ├── config
│ │ └── fake_robot_arbotix.yaml
│ ├── launch
│ │ ├── dd_gazebo.launch
│ │ ├── dd_robot_with_arbotix.launch
│ │ └── dd_rviz.launch
│ ├── package.xml
│ ├── urdf
│ │ ├── dd_robot.gazebo
│ │ ├── dd_robot.gv
│ │ ├── dd_robot.pdf
│ │ ├── dd_robot.urdf
│ │ └── urdfbackup.urdf
│ ├── urdf.rviz
│ └── worlds
├── teleop_twist_joy
│ ├── CHANGELOG.rst
│ ├── CMakeLists.txt
│ ├── config
│ │ ├── atk3.config.yaml
│ │ ├── beitong.config.yaml
│ │ ├── ps3.config.yaml
│ │ ├── ps3-holonomic.config.yaml
│ │ ├── xbox.config.yaml
│ │ └── xd3.config.yaml
│ ├── include
│ │ └── teleop_twist_joy
│ ├── launch
│ │ └── teleop.launch
│ ├── LICENSE.txt
│ ├── package.xml
│ ├── README.md
│ ├── src
│ │ ├── teleop_node.cpp
│ │ └── teleop_twist_joy.cpp
│ └── test
│ ├── differential_joy.test
│ ├── holonomic_joy.test
│ ├── no_enable_joy.test
│ ├── only_turbo_joy.test
│ ├── six_dof_joy.test
│ ├── test_joy_twist.py
│ ├── turbo_angular_enable_joy.test
│ ├── turbo_angular_enable_joy_with_rosparam_map.test
│ └── turbo_enable_joy.test
└── teleop_twist_keyboard
├── CHANGELOG.rst
├── CMakeLists.txt
├── package.xml
├── README.md
└── teleop_twist_keyboard.py
同样,可以游戏手柄控制,APP控制(只要在同一个wifi下)。
下一步来学习下xacro来简化下urdf。