前言
闲来无事,手上又没有可玩的机器人,就简单打个仿真玩一下
安装软件
我这里使用的docker镜像,基于ubuntu18.04 + ros-melodic的
https://hub.docker.com/repository/docker/vell001/ubt18.04_ros_xrdp
# 安装ROS Melodic
sudo apt install ros-melodic-desktop-full
# 安装Gazebo插件和键盘控制包
sudo apt install ros-melodic-gazebo-ros-pkgs ros-melodic-teleop-twist-keyboard
创建工作空间
mkdir -p ~/vellbot_ws/src && cd ~/vellbot_ws
catkin_make
source devel/setup.bash
创建机器人模型
我这里非常简单,使用两轮差速控制,有两个差速轮,和一个万向支撑轮
对应xacro文件如下:
<?xml version="1.0"?>
<robot name="vellbot" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Defining the colors used in this robot -->
<material name="Black">
<color rgba="0 0 0 1"/>
</material>
<material name="Blue">
<color rgba="0 0 1 1"/>
</material>
<link name="base_link">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<box size="0.4 0.6 0.1"/>
</geometry>
<material name="Blue"/>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<box size="0.4 0.6 0.1"/>
</geometry>
</collision>
<inertial>
<mass value="5.0"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.2"/>
</inertial>
</link>
<xacro:macro name="wheel" params="name radius:=0.05 width:=0.02">
<link name="${name}">
<visual>
<origin xyz="0 0 0" rpy="0 1.5708 0"/>
<geometry>
<cylinder radius="${radius}" length="${width}"/>
</geometry>
<material name="Black"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 1.5708 0"/>
<geometry>
<cylinder radius="${radius}" length="${width}"/>
</geometry>
</collision>
<inertial>
<mass value="0.3"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0002"/>
</inertial>
</link>
</xacro:macro>
<xacro:macro name="omni_wheel" params="name radius:=0.05">
<link name="${name}">
<visual>
<geometry><sphere radius="${radius}"/></geometry>
<material name="Black"/>
</visual>
<collision>
<geometry><sphere radius="${radius}"/></geometry>
</collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.00001" ixy="0" ixz="0" iyy="0.00001" iyz="0" izz="0.00001"/>
</inertial>
</link>
</xacro:macro>
<xacro:wheel name="left_wheel"/>
<xacro:wheel name="right_wheel"/>
<xacro:omni_wheel name="caster_wheel"/>
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0.15 0.2 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="-0.15 0.2 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="caster_wheel_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_wheel"/>
<origin xyz="0 -0.2 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>
<gazebo reference="base_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="left_wheel">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="right_wheel">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="caster_wheel">
<material>Gazebo/Black</material>
<mu1>0.1</mu1>
<mu2>0.05</mu2>
<kp>1e4</kp>
<kd>1e3</kd>
</gazebo>
<gazebo>
<plugin name="diff_drive" filename="libgazebo_ros_diff_drive.so">
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<leftJoint>left_wheel_joint</leftJoint>
<rightJoint>right_wheel_joint</rightJoint>
<wheelSeparation>0.3</wheelSeparation>
<wheelDiameter>0.1</wheelDiameter>
</plugin>
</gazebo>
</robot>
创建 launch 文件,启动 gazebo 和键盘控制
<launch>
<!-- 加载机器人模型 -->
<param name="robot_description" command="$(find xacro)/xacro $(find vellbot)/urdf/vellbot.xacro" />
<!-- 启动Gazebo -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="worlds/empty.world"/>
</include>
<!-- 将机器人模型加载到Gazebo -->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"
args="-param robot_description -urdf -model vellbot" />
<!-- 启动键盘控制节点 -->
<node name="teleop" pkg="teleop_twist_keyboard" type="teleop_twist_keyboard.py" output="screen">
<param name="speed" value="0.5" /> <!-- 线速度(m/s) -->
<param name="turn" value="1.0" /> <!-- 角速度(rad/s) -->
</node>
</launch>
按键控制
roslaunch vellbot vellbot_gazebo.launch
正常启动的话,会打印如下键盘控制说明,按如下说明操作即可控制小车运动