Gazebo构建小车模型并通过ROS控制
- 介绍
- 编写车子的URDF文件
- 编写控制小车移动的插件(与ROS交互)
- 结尾
介绍
突然想试试Gazebo这款仿真软件,因为它可以让你在任何时候都有机器人玩。但Gazebo的机制也比较复杂,所以还是先学习一下如何搭一个简单的小车,并通过ROS平台完成对小车的控制。
编写车子的URDF文件
这里是跟着《ROS机器人开发》书中的介绍一步步来的,对详细过程有兴趣的朋友去看一下。为了方便,直接把代码和注释都写在一起,但运行时要注意的是:URDF文件里不要有中文注释:
<?xml version='1.0'?>
<robot name="dd_robot">
<link name="base_link">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.5 0.5 0.25" />
</geometry>
<material name="blue">
<color rgba="0.0 0.5 1.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.5 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>
<visual name="caster">
<origin xyz="0.2 0.0 -0.125" rpy="0.0 0.0 0.0"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
</visual>
<collision>
<origin xyz="0.2 0.0 -0.125" rpy="0.0 0.0 0.0"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
</collision>
</link>
<link name="right_wheel">
<visual>
<origin xyz="0.0 -0.0 0.0" rpy="1.570795 0.0 0.0"/>
<geometry>
<cylinder length="0.1" radius="0.2"/>
</geometry>
<material name="black">
<color rgba="0.05 0.05 0.05 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="1.570795 0.0 0.0"/>
<geometry>
<cylinder length="0.1" radius="0.2"/>
</geometry>
</collision>
</link>
<joint name="join_right_wheel" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0.0 -0.30 0.0" rpy="0.0 0.0 0.0"/>
<axis xyz="0.0 1.0 0.0"/>
</joint>
<link name="left_wheel">
<visual>
<origin xyz="0.0 0.0 0.0" rpy="1.570795 0.0 0.0"/>
<geometry>
<cylinder length="0.1" radius="0.2"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="1.570795 0.0 0.0"/>
<geometry>
<cylinder length="0.1" radius="0.2"/>
</geometry>
</collision>
</link>
<joint name="join_left_wheel" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0.0 -0.3 0.0" rpy="0.0 0.0 0.0"/>
<axis xyz="0.0 1.0 0.0"/>
</joint>
<gazebo reference="base_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="right_wheel">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="left_wheel">
<material>Gazebo/Black</material>
</gazebo>
</robot>
这串代码是使用 VSCode 写的,因为 VSCode 里面有个专门的 URDF 插件,可以帮你补全代码啥的,挺实用的。根据这个代码我们就构建了一个拥有三个轮子的小车。然后用下面的 launch 文件( launch 文件中可以写中文注释)打开rviz,将小车模型在rviz中显示。
<launch
<!--在通过命令行启动launch文件时要提供那些参数,也可以设置这些参数的默认值-->
<arg name="model" />
<arg name="gui" default="False" />
<!--这个launch将在ROS中的参数管理平台中发布这些可以查看、使用的参数-->
<!--robot_description是最重要的!!他应该是能够告诉 Rviz 应该读取显示哪个URDF文件-->
<param name="robot_description" textfile="$(find ros_robotics)/urdf/$(arg model)" />
<param name="use_gui" value="$(arg gui)"/><!--use_gui表示是否打开一个可以控制整个模型中所有joint的gui界面-->
<!--这个launch要启动3个node节点: joint_state_publisher, robot_state_publisher and rviz-->
<!--下面启动node的方法其实是系统自动在命令窗口中分别用rosrun命令启动各个node,以最后的node代码块为例,它对应的启动命令是:
rosrun pkg(rviz) node(rviz) args(各个参数) required(意义不太清楚) 代码块中的name有着其他含义-->
<!--这段node代码块的含义:
从pkg对应的功能包中,启动名称为type对应值的节点,并将启动的阶段在ROS平台中的名称设为name的对应值-->
<!--joint_state_publisher将urdf中的关节信息发布出去,从而帮助rviz等软件根据关节来显示各个link和机器人模型-->
<node name="joint_state_publisher"
pkg="joint_state_publisher"
type="joint_state_publisher" />
<!--robot_state_publisher会将机器人行动后的信息发布出去,帮助tf功能包确定机器人当前的状态,从何在模拟软件中显示-->
<node name="robot_state_publisher"
pkg="robot_state_publisher"
type="robot_state_publisher" />
<!--这段node块复杂一点:
一开始的代码和之前的意义一样,即启动rviz。之后设置rviz启动时的所有参数args,和required(意义不明)
urdf.rviz是rviz软件的可读文件,它保存了上一次rviz退出时的状态,之后启动rviz时,通过读取这个urdf.rviz可以恢复先前的状态,并配置好rviz的参数-->
<node name="rviz" pkg="rviz" type="rviz"
args="-d $(find ros_robotics)/urdf.rviz"
required="true" />
</launch>
直接用 roslaunch 命令执行该launch文件,显示效果:
第一次执行可能要调一下Rviz,先点左边窗口的Add按钮,找到RobotModel和TF,然后将Fixed Frame设定为base_link即可。
其实也可以用Gazebo显示,只要稍微修改一下就行,这就看个人的习惯了。这个小车模型可以直接在 Gazebo 中用Model Edit 搭建。相比于写代码,图形化的搭建方式可能会更方便些。具体搭建方法大家可以参考这篇文章。
编写控制小车移动的插件(与ROS交互)
这个小车和常见的 turtlebot 不能说是一模一样,但也可以说是毫无关系。不过好在Gazebo中有很多现成的插件和模型,我们可以自行选择添加,编写小车代码只是为了帮助加深对 Gazebo 的理解。因为只是初步学习Gazebo仿真,所以我只做了控制小车移动的代码。为了方便直接把代码和注释写在一起:
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/transport/transport.hh>
#include <gazebo/msgs/msgs.hh>
#include <thread>
#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <ros/subscribe_options.h>
#include <std_msgs/Float32.h>
namespace gazebo
{
class PositionPlugin : public ModelPlugin
{
public: PositionPlugin()
{
std::cout<<"Motion Plugin"<<std::endl;
}
public: void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
{
std::cout<<"Starting Load"<<std::endl;
this->model = _model;
std::cerr << "\n The model's name is [" <<
_model->GetScopedName() << "]\n";
std::string car_name_ori="Hello";
if (!ros::isInitialized())
{
int argc = 0;
char **argv = NULL;
ros::init(argc, argv, car_name_ori + "_" + "node",
ros::init_options::NoSigintHandler);
}
this->rosNode.reset(new ros::NodeHandle(car_name_ori + "_" + "Handle"));
ros::SubscribeOptions so =
ros::SubscribeOptions::create<std_msgs::Float32>(
"/" + this->model->GetName() + "/" + car_name_ori + "/pos_cmd",
1,
boost::bind(&PositionPlugin::OnRosMsg, this, _1),
ros::VoidPtr(), &this->rosQueue);
this->rosSub = this->rosNode->subscribe(so);
this->rosQueueThread =
std::thread(std::bind(&PositionPlugin::QueueThread, this));
this->updateConnection = event::Events::ConnectWorldUpdateBegin(
std::bind(&PositionPlugin::OnUpdate, this));
}
public: void OnRosMsg(const std_msgs::Float32ConstPtr &_msg)
{
this->vel=_msg->data;
sleep(1);
this->vel=0;
}
public:void OnUpdate()
{
this->model->SetLinearVel(ignition::math::Vector3d(this->vel, 0, 0));
}
private: void QueueThread()
{
static const double timeout = 0.01;
while (this->rosNode->ok())
{
this->rosQueue.callAvailable(ros::WallDuration(timeout));
}
}
private: physics::ModelPtr model;
private: std::unique_ptr<ros::NodeHandle> rosNode;
private: ros::Subscriber rosSub;
private: ros::CallbackQueue rosQueue;
private: std::thread rosQueueThread;
private: double vel;
private: event::ConnectionPtr updateConnection;
};
GZ_REGISTER_MODEL_PLUGIN(PositionPlugin)
}
为了让 Gazebo 直接同时加载小车模型和编写的插件,这里推荐写一个 world 文件:
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="motion_world">
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://ground_plane</uri>
</include>
<model name='dd_robot'>
<include>
<uri>model://dd_robot</uri>
</include>
<plugin name="motion_controller" filename="libmotion_controller.so">
</plugin>
</model>
</world>
</sdf>
然后用gazebo world文件
命令运行这个文件。提一嘴,在执行命令前,我们要先把之前的小车 URDF 文件变成Gazebo 可用的SDF文件。方法很简单,直接执行这个命令即可gz sdf -p urdf文件 > sdf文件
。我们还需要为这个 SDF 文件配套写一个 config 文件(介绍文件),内容如下:
<?xml version="1.0" encoding="UTF-8"?>
<model>
<name>dd_robot</name>
<version>1.0</version>
<sdf version="1.4">dd_robot.sdf</sdf>
<description>My Car.</description>
</model>
然后我们把转换好的 SDF 文件和 config 文件打包到一个叫 dd_robot 文件夹中,并将文件夹放进 ~/.gazebo/models/ 目录下。只有这样,在执行world文件时,Gazebo 才能找到你的模型文件,因为 Gazebo 是有默认模型搜索路径的(也可以修改GAZEBO_MODEL_PATH环境变量,不过我没试过)。然后先在一个命令窗口执行roscore
,并在另一个窗口运行 world 文件。最后再在新的窗口向对应的topic发布命令:rostopic pub topicname 信息类型 信息
,即左边窗口的操作:
图一、小车的原始位置。
图二、控制小车以0.2m/s的速度移动1s钟(这在代码中有写)
结尾
在调试的过程中发现Gazebo还是很好玩的,不过它的机制很复杂,还常常报些搞不懂的错(毕竟新手)。虽然Gazebo的模型库中就有很多已经构建好的模型,但尝试自己动手搭建未尝不是件很刺激的事(也是件烦躁的事)。好了,对Gazebo的初步学习到此结束,之后还有很长的路要走,比如给模型加入纹理啥的。
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)