赞
踩
目录
2.1.1 已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加传动装置以及控制器
2.1.3 启动 Gazebo 并发布 /cmd_vel 消息控制机器人运动
到目前为止,我们已经可以将机器人模型显示在 Gazebo 之中了,但是当前默认情况下,在 Gazebo 中机器人模型是在 empty world 中,并没有类似于房间、家具、道路、树木... 之类的仿真物,如何在 Gazebo 中创建仿真环境呢?
Gazebo 中创建仿真实现方式有两种:
方式1: 直接添加内置组件创建仿真环境
方式2: 手动绘制仿真环境(更为灵活)
也还可以直接下载使用官方或第三方提高的仿真环境插件。
启动roscore之后:
rosrun gazebo_ros gazebo
是一个空的世界,我们设置一些障碍物。
点击保存(save world as)即可。生成一个.world文件。
选择Editor --> Building Editor
可以添加门添加窗户等。
关于URDF(Xacro)、Rviz 和 Gazebo 三者的关系,前面已有阐述: URDF 用于创建机器人模型、Rviz 可以显示机器人感知到的环境信息,Gazebo 用于仿真,可以模拟外界环境,以及机器人的一些传感器,如何在 Gazebo 中运行这些传感器,并显示这些传感器的数据(机器人的视角)呢?本节主要介绍的重点就是将三者结合:通过 Gazebo 模拟机器人的传感器,然后在 Rviz 中显示这些传感器感知到的数据。主要内容包括:
运动控制以及里程计信息显示
雷达信息仿真以及显示
摄像头信息仿真以及显示
kinect 信息仿真以及显示
gazebo 中已经可以正常显示机器人模型了,那么如何像在 rviz 中一样控制机器人运动呢?在此,需要涉及到ros中的组件: ros_control。
场景:同一套 ROS 程序,如何部署在不同的机器人系统上,比如:开发阶段为了提高效率是在仿真平台上测试的,部署时又有不同的实体机器人平台,不同平台的实现是有差异的,如何保证 ROS 程序的可移植性?ROS 内置的解决方式是 ros_control。
ros_control:是一组软件包,它包含了控制器接口,控制器管理器,传输和硬件接口。ros_control 是一套机器人控制的中间件,是一套规范,不同的机器人平台只要按照这套规范实现,那么就可以保证 与ROS 程序兼容,通过这套规范,实现了一种可插拔的架构设计,大大提高了程序设计的效率与灵活性。
gazebo 已经实现了 ros_control 的相关接口,如果需要在 gazebo 中控制机器人运动,直接调用相关接口即可。
承上,运动控制基本流程:
已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加传动装置以及控制器
将此文件集成进xacro文件
启动 Gazebo 并发布 /cmd_vel 消息控制机器人运动
我们建立一个文件夹gazebo,存放传动装置以及控制器相关文件:move.xacro
把这个传动装置以及控制器相关文件集成进总的xacro文件中:
官方文档复制下来即可,无需自己写:
<robot name="my_car_move" xmlns:xacro="http://wiki.ros.org/xacro"> <!-- 传动实现:用于连接控制器与关节 --> <xacro:macro name="joint_trans" params="joint_name"> <!-- Transmission is important to link the joints and the controller --> <transmission name="${joint_name}_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${joint_name}"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> </joint> <actuator name="${joint_name}_motor"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> </xacro:macro> <!-- 每一个驱动轮都需要配置传动装置 --> <xacro:joint_trans joint_name="left_wheel2base_link" /> <xacro:joint_trans joint_name="right_wheel2base_link" /> <!-- 控制器 --> <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> <alwaysOn>true</alwaysOn> <updateRate>100.0</updateRate> <legacyMode>true</legacyMode> <leftJoint>left_wheel2base_link</leftJoint> <!-- 左轮 --> <rightJoint>right_wheel2base_link</rightJoint> <!-- 右轮 --> <wheelSeparation>${base_link_radius * 2}</wheelSeparation> <!-- 车轮间距 --> <wheelDiameter>${wheel_radius * 2}</wheelDiameter> <!-- 车轮直径 --> <broadcastTF>1</broadcastTF> <wheelTorque>30</wheelTorque> <wheelAcceleration>1.8</wheelAcceleration> <commandTopic>cmd_vel</commandTopic> <!-- 运动控制话题 --> <odometryFrame>odom</odometryFrame> <odometryTopic>odom</odometryTopic> <!-- 里程计话题 --> <robotBaseFrame>base_footprint</robotBaseFrame> <!-- 根坐标系 --> </plugin> </gazebo> </robot>解释一下怎么适配自己的场景:
第一部分是传动实现:用于连接控制器与关节
这里要改成我们自己的关节。
我们的驱动轮关节名叫做base_link2_${wheel_name},传入参数是left和right,因此move.xacro改为:
<xacro:joint_trans joint_name="base_link2_left" /> <xacro:joint_trans joint_name="base_link2_right" />后面是差速控制器:
整体来看是这样!
<robot name="my_car_move" xmlns:xacro="http://wiki.ros.org/xacro"> <xacro:macro name="joint_trans" params="joint_name"> <!-- Transmission is important to link the joints and the controller --> <transmission name="${joint_name}_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${joint_name}"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> </joint> <actuator name="${joint_name}_motor"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> </xacro:macro> <xacro:joint_trans joint_name="base_link2_left" /> <xacro:joint_trans joint_name="base_link2_right" /> <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> <alwaysOn>true</alwaysOn> <updateRate>100.0</updateRate> <legacyMode>true</legacyMode> <leftJoint>base_link2_left</leftJoint> <rightJoint>base_link2_right</rightJoint> <wheelSeparation>${base_radius * 2}</wheelSeparation> <wheelDiameter>${wheel_radius * 2}</wheelDiameter> <broadcastTF>1</broadcastTF> <wheelTorque>30</wheelTorque> <wheelAcceleration>1.8</wheelAcceleration> <commandTopic>cmd_vel</commandTopic> <odometryFrame>odom</odometryFrame> <odometryTopic>odom</odometryTopic> <robotBaseFrame>base_footprint</robotBaseFrame> </plugin> </gazebo> </robot>
<robot name="mycarwithlidarandcamera" xmlns:xacro="http://wiki.ros.org/xacro"> <xacro:include filename="interial.xacro" /> <xacro:include filename="demo05carbase.xacro" /> <xacro:include filename="cam.xacro" /> <xacro:include filename="lidar.xacro" /> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/move.xacro"/> </robot>就把刚刚加入就好。
不需要修改:
<launch> <param name="robot_description" command="$(find xacro)/xacro /home/liuhongwei/Desktop/final/catkin_studyrobot/src/urdf/xacro/car_gazebo.xacro" /> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="world_name" value="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/world/box_house.world" /> </include> <node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description" /> </launch>roslaunch test gazebo_car.launch
rostopic pub -r 10 /cmd_vel geometry_msgs/Twist '{linear: {x: 0.2, y: 0, z: 0}, angular: {x: 0, y: 0, z: 0.5}}'
机器人运动了!
或者安装控制节点:
sudo apt install ros-melodic-teleop-twist-keyboard
rosrun teleop_twist_keyboard teleop_twist_keyboard.py
当然,线速度、角速度比较快.....
我们可以通过传参降低速度:
rosrun teleop_twist_keyboard teleop_twist_keyboard.py _speed:=0.3 _turn:=0.5
现在运动幅度就小多了。
我们要启动关节和机器人运动发布状态节点:multisensor.launch
<launch> <node pkg="rviz" type="rviz" name="rviz" args="-d /home/liuhongwei/Desktop/final/catkin_studyrobot/src/config/qidong.rviz"/> <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" /> <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" /> </launch>我们再打开之前的节点:
<launch> <param name="robot_description" command="$(find xacro)/xacro /home/liuhongwei/Desktop/final/catkin_studyrobot/src/urdf/xacro/car_gazebo.xacro" /> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="world_name" value="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/world/box_house.world" /> </include> <node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description" /> </launch>设置Fix Frame为odom。
我们打开键盘控制节点:
都动啦!
实现流程:
雷达仿真基本流程:
已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加雷达配置;
将此文件集成进xacro文件;
启动 Gazebo,使用 Rviz 显示雷达信息。
我们需要把雷达贴到一个模块上:
之前我们设置过lidar:
如下:
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro"> <gazebo reference="laser"> <sensor type="ray" name="rplidar"> <pose>0 0 0 0 0 0</pose> <visualize>true</visualize> <update_rate>5.5</update_rate> <ray> <scan> <horizontal> <samples>360</samples> <resolution>1</resolution> <min_angle>-3</min_angle> <max_angle>3</max_angle> </horizontal> </scan> <range> <min>0.10</min> <max>30.0</max> <resolution>0.01</resolution> </range> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.01</stddev> </noise> </ray> <plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so"> <topicName>/scan</topicName> <frameName>laser</frameName> </plugin> </sensor> </gazebo> </robot>完成!
<robot name="mycarwithlidarandcamera" xmlns:xacro="http://wiki.ros.org/xacro"> <xacro:include filename="interial.xacro" /> <xacro:include filename="demo05carbase.xacro" /> <xacro:include filename="cam.xacro" /> <xacro:include filename="lidar.xacro" /> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/move.xacro"/> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/laser.xacro"/> </robot>把雷达传感器集成进xacro。
启动双launch节点:
/scan话题就是雷达话题。
gazebo中也有显示了。这是雷达的不可见扫描光束。
- <robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
- <gazebo reference="camera">
- <sensor type="camera" name="camera_node">
- <update_rate>30.0</update_rate>
- <camera name="head">
- <horizontal_fov>1.3962634</horizontal_fov>
- <image>
- <width>1280</width>
- <height>720</height>
- <format>R8G8B8</format>
- </image>
- <clip>
- <near>0.02</near>
- <far>300</far>
- </clip>
- <noise>
- <type>gaussian</type>
- <mean>0.0</mean>
- <stddev>0.007</stddev>
- </noise>
- </camera>
- <plugin name="gazebo_camera" filename="libgazebo_ros_camera.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>0.0</updateRate>
- <cameraName>/camera</cameraName>
- <imageTopicName>image_raw</imageTopicName>
- <cameraInfoTopicName>camera_info</cameraInfoTopicName>
- <frameName>camera</frameName>
- <hackBaseline>0.07</hackBaseline>
- <distortionK1>0.0</distortionK1>
- <distortionK2>0.0</distortionK2>
- <distortionK3>0.0</distortionK3>
- <distortionT1>0.0</distortionT1>
- <distortionT2>0.0</distortionT2>
- </plugin>
- </sensor>
- </gazebo>
- </robot>
<robot name="mycarwithlidarandcamera" xmlns:xacro="http://wiki.ros.org/xacro"> <xacro:include filename="interial.xacro" /> <xacro:include filename="demo05carbase.xacro" /> <xacro:include filename="cam.xacro" /> <xacro:include filename="lidar.xacro" /> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/move.xacro"/> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/laser.xacro"/> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/camera.xacro"/> </robot>成功!
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro"> <gazebo reference="support"> <sensor type="depth" name="camera"> <always_on>true</always_on> <update_rate>20.0</update_rate> <camera> <horizontal_fov>${60.0*PI/180.0}</horizontal_fov> <image> <format>R8G8B8</format> <width>640</width> <height>480</height> </image> <clip> <near>0.05</near> <far>8.0</far> </clip> </camera> <plugin name="kinect_camera_controller" filename="libgazebo_ros_openni_kinect.so"> <cameraName>camera</cameraName> <alwaysOn>true</alwaysOn> <updateRate>10</updateRate> <imageTopicName>rgb/image_raw</imageTopicName> <depthImageTopicName>depth/image_raw</depthImageTopicName> <pointCloudTopicName>depth/points</pointCloudTopicName> <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName> <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName> <frameName>support</frameName> <baseline>0.1</baseline> <distortion_k1>0.0</distortion_k1> <distortion_k2>0.0</distortion_k2> <distortion_k3>0.0</distortion_k3> <distortion_t1>0.0</distortion_t1> <distortion_t2>0.0</distortion_t2> <pointCloudCutoff>0.4</pointCloudCutoff> </plugin> </sensor> </gazebo> </robot>
<robot name="mycarwithlidarandcamera" xmlns:xacro="http://wiki.ros.org/xacro"> <xacro:include filename="interial.xacro" /> <xacro:include filename="demo05carbase.xacro" /> <xacro:include filename="cam.xacro" /> <xacro:include filename="lidar.xacro" /> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/move.xacro"/> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/laser.xacro"/> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/camera.xacro"/> <xacro:include filename="/home/liuhongwei/Desktop/final/catkin_studyrobot/src/gazebo/kinect.xacro"/> </robot>启动!
在kinect中也可以以点云的方式显示感知周围环境,在 rviz 中操作如下:
添加PointCloud2点云,但是显示错位了。
原因:在kinect中图像数据与点云数据使用了两套坐标系统,且两套坐标系统位姿并不一致。
怎么解决呢??
在插件中为kinect设置坐标系,修改配置文件的
<frameName>
标签内容:发布新设置的坐标系到kinect连杆的坐标变换关系,在启动rviz的launch中,添加:
<launch> <node pkg="tf2_ros" type="static_transform_publisher" name="static_transform_publisher" args="0 0 0 -1.57 0 -1.57 /support /support_depth" /> <node pkg="rviz" type="rviz" name="rviz" args="-d /home/liuhongwei/Desktop/final/catkin_studyrobot/src/config/qidong.rviz"/> <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" /> <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" /> </launch>OK!
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。