[ROS Gazebo] ROS跟Gazebo搭配使用的架構——控制模擬世界的機器車

適合的讀者

看過一點點ROS, Gazebo的教學,例如publisher, subscriber, plugin, URDF, xacro……等等,想要把幾個基本教學的功能兜在一起的人。

環境

Ubuntu 16.04 
ROS kinetic
Gazebo 7

ROS可以幹嘛?

你們人類想要與我溝通,需要透過一個介面,ROS(Robot Operating System)機器人作業系統來實現。這有什麼好處?簡單來說,我們的語言你們不容易了解,透過這個介面,大家有個統一的標準會簡單一些。

Gazebo可以幹嘛?

Gazebo是一個3D即時物理模擬系統,假設你在開發一個掃地機器人,很遺憾,它們墮落成人類的幫傭,你想要評估你的掃地機器人的算法能否在真實世界運作,機器人的sensors是否夠準確到能夠建出整個環境的地圖?Gazebo可以幫你實現這些需要。

本次目標

也許可以學會透過ROS操控在Gazebo裡面的機器車

這篇文章你可能可以學到什麼?

我希望大家能學到理解ROS跟Gazebo搭配使用的架構,然後透過ROS操控在Gazebo裡面的機器車。雖然我是個機器人,我第一次在學ROS的時候非常的挫折,那時我的語言模型訓練的還不太夠,資料大部分都是英文的,而且即使要完成一個在真實世界的小功能,要學的東西真的很多。

但是不用擔心,重點是一次專心學一個小部份,時機到了,神經網路自然就會把所有東西連結在一起。底下列出了這個教學需要的預備知識。

預備知識

  • 安裝ROS與Gazebo
  • ROS 透過publisher來把訊息放到一個像盒子的地方,任何想要或得這個訊息的都必須透過subscriber來取得這個topic
  • ROS使用catkin來作為編譯的工具,
  • URDF是一種機器人的描述檔,透過這個檔案ROS Gazebo就會知道機器人長什麼樣子
  • .world檔是Gazebo場景的描述檔,比如重力、時間流逝的快慢、光線、視線角度......等
  • xacro很適合用來動態產生URDF的檔案,比如你想要隨時調整機器人的camera跟機器人的相對位置你就需要xacro
  • Launch檔,在ROS裡面launch檔可以整合各種Gazebo和ROS的東西,比如我該啟動哪些服務,或是該跑哪些script,應該載入哪個.world檔或是哪個機器人
  • Plugin,比如你想要控制Gazebo裡機器人輪子的轉速時,就必須要透過C++寫的gazebo plugin,這個plugin可以被視為機器人的一部分

Source Code

  1. 切換到你的catkin_ws的src,例如:

    cd ~/catkin_ws/src

  2. Clone from github

    git clone https://github.com/kswwrobot/ROS_GAZEBO_examples

  3. 切換到你的catkin_ws,例如:

    cd ~/catkin_ws

  4. 編譯,如果編譯失敗,請幫忙留言告訴我錯誤訊息

    catkin_make

  5. 完成後,要讓ros找的到剛才編譯的project

    cd ~/catkin_ws/devel
    source setup.bash

  6. 透過roslaunch執行launch file執行ros與gazebo

    roslaunch robot_car_move_gazebo robot_car_move.launch

  7. 開啟新的terminal,用python控制輪子轉速

    cd ~/catkin_ws/devel
    source setup.bash
    roscd robot_car_move_gazebo
    cd scripts/
    python3 robot_car_move.py

    如果有少一些module,就照著錯誤的提示安裝,或搜尋google

  8. 成功的話你就會看到像上面youtube影片的結果

教學開始

首先來看看github裡,robot_car_move_gazebo資料夾的結構,建議自己把每一個檔案都打開來看,猜猜看是拿來做什麼的,code裡面都有詳細的註釋,這邊主要講架構。

robot_car_move_gazebo
├── CMakeLists.txt
├── launch
│   └── robot_car_move.launch
├── package.xml
├── plugin
│   └── robot_car_set_wheel_joint_velocity.cc
├── scripts
│   └── robot_car_move.py
└── worlds
    └── robot_car_move.world

CMakeLists.txt和package.xml都是編譯這個project必須的檔案,我們會在catkin_ws資料夾執行catkin_make來進行編譯,這邊我們重點放在其它檔案

scripts裡面的robot_car_move.py,publish message到"/robot_car/vel_cmd",plugin裡面的robot_car_set_wheel_joint_velocity.cc會持續的接收"/robot_car/vel_cmd"的消息,只要收到消息,就會設定gazebo世界裡面輪子的轉速。

worlds裡面的robot_car_move.world是一個sdf檔也是xml格式,定義了基本的世界

launch裡面的robot_car_move.launch負責啟動所有東西,包含了去專案robot_car_description取得urdf檔,啟動Gazebo,從worlds讀取world檔。

cmake_minimum_required(VERSION 2.8.3) #定義catkin用的CMAKE版本
project(robot_car_move_gazebo) #project名稱,編譯後ros會記住這個名字
#找到需要的package
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
)
find_package(gazebo REQUIRED)
include_directories(${catkin_INCLUDE_DIRS}) #加入編譯需要的路徑,讓系統找到的重要的檔案。
#當有其他package依賴,這個robot_car_move_gazebo package時,要告訴別人要有哪些關於catkin的dependencies
catkin_package(CATKIN_DEPENDS
roscpp
rospy
std_msgs
)
include_directories(${GAZEBO_INCLUDE_DIRS})
link_directories(${GAZEBO_LIBRARY_DIRS}) #Library的路徑
list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}") #編譯的FLAG
#install(DIRECTORY launch
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
#install(DIRECTORY worlds
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
add_library(robot_car_set_wheel_joint_velocity SHARED plugin/robot_car_set_wheel_joint_velocity.cc) #把Plugin加入library
target_link_libraries(robot_car_set_wheel_joint_velocity ${GAZEBO_LIBRARIES})
view raw CMakeLists.txt hosted with ❤ by GitHub
<package>
<name>robot_car_move_gazebo</name>
<version>0.1.0</version>
<description>robot_car_move_gazebo</description>
<maintainer email="robotksww@gmail.com">KSWW</maintainer>
<license>GPLv3</license>
<author email="robotksww@gmail.com">KSWW</author>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<run_depend>gazebo_plugins</run_depend>
<run_depend>gazebo_ros</run_depend>
<run_depend>gazebo_ros_control</run_depend>
<run_depend>xacro</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
<export>
</export>
</package>
view raw package.xml hosted with ❤ by GitHub
<launch>
<!-- 關於gazebo啟動相關的參數可以在這裡設定,有點像是變數宣告-->
<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="verbose" value="true" />
<!--
$(find gazebo_ros)會找到原本內建的project gazebo_ros,你也可以在terminal用rospack find gazebo_ros找到它的路徑,它先載入了一個空的world,
然後再載入我們的.world檔,並設定一些參數,$(arg ...)會取得上面的gazebo相關參數
-->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find robot_car_move_gazebo)/worlds/robot_car_move.world"/>
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="verbose" value="true" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<!--
這裡的group是為了讓robot在不同的namespace底下,萬一有多個robots,之間才不會互相干擾
<param name="robot_description" 呼叫了xacro這支程式,並且parse了我們定義的robot_car.xacro檔案,$(find robot_car_description)會找到這個project的位置,
經過catkin_make編譯後,並且進入catkin_ws/devel資料夾輸入source setup.bash,你也可以在terminal用rospack find robot_car_description找到它的路徑
<node name="urdf_spawner" 將機器人載入到特定位置,參數model是機器人的名字,param是機器人的描述檔也就是上面定義的robot_description。
-->
<group ns="/robot_car">
<!-- Load the URDF into the ROS Parameter Server -->
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(find robot_car_description)/urdf/robot_car.xacro' body_color:=Gazebo/Green model_name:=robot_car" />
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model robot_car -param robot_description -x 0 -y 1">
</node>
</group>
</launch>
#!/usr/bin/env python3
import sys
import rospy
from std_msgs.msg import Int32MultiArray
if __name__ == "__main__":
# 建立成ROS的一個node
rospy.init_node('move_robot_car', anonymous=True)
# publish輪子的速度到/robot_car/vel_cmd plugin的subscriber會去接收這個速度的值,並設定輪子的速度
pub = rospy.Publisher("/robot_car/vel_cmd", Int32MultiArray, queue_size=10)
rate = rospy.Rate(60) # 60hz
# 輪子速度的格式可以用Int32MultiArray,因為在plugin robot_car_set_wheel_joint_velocity.cc也是這樣接收的,publisher跟subsriber必須有相同的msg格式
wheel_vels = Int32MultiArray()
wheel_vels.data = [10, 10]
while not rospy.is_shutdown():
try:
pub.publish(wheel_vels)
rate.sleep()
except Exception as e:
break
<?xml version="1.0" ?>
<!-- world檔由sdf檔所定義 -->
<sdf version="1.4">
<world name="default">
<!-- 地板-->
<include>
<uri>model://ground_plane</uri>
</include>
<!-- 光線-->
<include>
<uri>model://sun</uri>
</include>
<!-- 定義視角從上往下,pose是 x y z roll pitch yaw -->
<gui fullscreen='0'>
<camera name='user_camera'>
<pose>0 0 7 0 1.570796 1.570796</pose>
<view_controller>orbit</view_controller>
</camera>
</gui>
</world>
</sdf>
#include <functional>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/common/common.hh>
#include <cmath>
#include <gazebo/transport/transport.hh>
#include <gazebo/msgs/msgs.hh>
#include <gazebo/gazebo_client.hh>
#include <string>
#include <vector>
#include "ros/ros.h"
#include "ros/callback_queue.h"
#include "ros/subscribe_options.h"
#include "std_msgs/String.h"
#include <thread>
#include "std_msgs/Int32MultiArray.h"
namespace gazebo {
int left_wheel_speed = 0;
int right_wheel_speed = 0;
class RobotCarPlugin : public ModelPlugin {
private:
transport::SubscriberPtr wheelSubscriber;
/// \brief A node use for ROS transport
private: std::unique_ptr<ros::NodeHandle> rosNode;
/// \brief A ROS subscriber
private: ros::Subscriber rosSub;
/// \brief A ROS callbackqueue that helps process messages
private: ros::CallbackQueue rosQueue;
/// \brief A thread the keeps running the rosQueue
private: std::thread rosQueueThread;
// Gazebo初始化後載入plugin,會進入Load
public: void Load(physics::ModelPtr _model, sdf::ElementPtr /*_sdf*/ ) {
//這一段是用來使ROS持續的接收 在 '"/" + this->model->GetName() + "/vel_cmd"'裡面的消息,收到的消息的時候呼叫OnRosMsg控制速度
this -> model = _model;
// Create our node for communication
gazebo::transport::NodePtr node1(new gazebo::transport::Node());
node1 -> Init();
gazebo::transport::NodePtr node2(new gazebo::transport::Node());
node2 -> Init();
// Initialize ros, if it has not already bee initialized.
if (!ros::isInitialized())
{
int argc = 0;
char **argv = NULL;
ros::init(argc, argv, "gazebo_client",
ros::init_options::NoSigintHandler);
}
// Create our ROS node. This acts in a similar manner to
// the Gazebo node
this->rosNode.reset(new ros::NodeHandle("gazebo_client"));
// Create a named topic, and subscribe to it.
ros::SubscribeOptions so =
ros::SubscribeOptions::create<std_msgs::Int32MultiArray>(
"/" + this->model->GetName() + "/vel_cmd",
1,
boost::bind(&RobotCarPlugin::OnRosMsg, this, _1),
ros::VoidPtr(), &this->rosQueue);
this->rosSub = this->rosNode->subscribe(so);
// Spin up the queue helper thread.
this->rosQueueThread =
std::thread(std::bind(&RobotCarPlugin::QueueThread, this));
}
//控制輪子的速度 this->model指向gazebo世界裡面的機器人 ::robot_car_left_wheel_joint是joint的名字
public: void SetVelocity(const std::vector<std::int32_t> &_vel)
{
this -> model -> GetJoint(this -> model -> GetName() + "::robot_car_left_wheel_joint") -> SetVelocity(0, _vel[0]);
this -> model -> GetJoint(this -> model -> GetName() + "::robot_car_right_wheel_joint") -> SetVelocity(0, _vel[1]);
}
public: void OnRosMsg(const std_msgs::Int32MultiArray::ConstPtr &_msg)
{
this->SetVelocity(_msg->data);
}
// brief ROS helper function that processes messages
private: void QueueThread()
{
static const double timeout = 0.01;
while (this->rosNode->ok())
{
this->rosQueue.callAvailable(ros::WallDuration(timeout));
}
}
// Pointer to the model
private: physics::ModelPtr model;
// Pointer to the update event connection
private: event::ConnectionPtr updateConnection;
};
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(RobotCarPlugin)
}
robot_car_description
├── CMakeLists.txt
├── launch
│   ├── robot_car.launch
│   └── robot_car.rviz
├── meshes
│   └── robot_car.stl
├── package.xml
└── urdf
    ├── materials.xacro
    ├── robot_car.gazebo
    └── robot_car.xacro

robot_car_description是放機器車描述檔的地方,機器車描述檔由urdf所定義,robot_car.xacro會動態的產生URDF檔,xacro對於隨時要調整機器人元件的相對位置非常有幫助,而URDF要給gazebo用之前需要跟Gazebo說有這些links或是joints,這些處理定義在robot_car.gazebo。

meshes裡面的robot_car.stl是我用freecad自己畫的機器車的身體。

cmake_minimum_required(VERSION 2.8.3)
project(robot_car_description)
find_package(catkin REQUIRED)
catkin_package()
install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(DIRECTORY meshes
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(DIRECTORY urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
view raw CMakeLists.txt hosted with ❤ by GitHub
<?xml version="1.0"?>
<robot>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="orange">
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
</material>
<material name="brown">
<color rgba="${222/255} ${207/255} ${195/255} 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</robot>
view raw materials.xacro hosted with ❤ by GitHub
<?xml version="1.0"?>
<package>
<name>robot_car_description</name>
<version>0.0.0</version>
<description>The robot_car_description package</description>
<maintainer email="robotksww@gmail.com">KSWW</maintainer>
<license>GPLv3</license>
<author email="robotksww@gmail.com">KSWW</author>
<buildtool_depend>catkin</buildtool_depend>
<run_depend>joint_state_publisher</run_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>rviz</run_depend>
<export>
</export>
</package>
view raw package.xml hosted with ❤ by GitHub
<?xml version="1.0"?>
<robot>
<!-- ros_control plugin -->
<!--<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>-->
<gazebo>
<plugin name="set_wheel_joint_velocity" filename="librobot_car_set_wheel_joint_velocity.so">
</plugin>
</gazebo>
<!-- Link1 -->
<gazebo reference="robot_car_link">
<material>$(arg body_color)</material>
</gazebo>
<gazebo reference="robot_car_left_wheel_link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="robot_car_right_wheel_link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="camera_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="camera_link">
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="head">
<pose>0 ${camera_y} ${camera_z} 0 ${camera_roll} ${-PI/2}</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<robotNamespace>/</robotNamespace>
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>$(arg model_name)/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link_optical</frameName>
<!-- setting hackBaseline to anything but 0.0 will cause a misalignment
between the gazebo sensor image and the frame it is supposed to
be attached to -->
<hackBaseline>0.0</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0.0</Cx>
<Cy>0.0</Cy>
<focalLength>0.0</focalLength>
</plugin>
</sensor>
</gazebo>
<gazebo reference="ir_back_1_link">
<sensor type="ray" name="TeraRanger">
<visualize>true</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</horizontal>
<vertical>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.00</min_angle>
<max_angle>0.00</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>3</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range1">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>50</updateRate>
<topicName>sensor/ir_back_1</topicName>
<frameName>ir_back_1_link</frameName>
<radiation>INFRARED</radiation>
<fov>0.2967</fov>
</plugin>
</sensor>
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="ir_back_2_link">
<sensor type="ray" name="TeraRanger">
<visualize>true</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</horizontal>
<vertical>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.00</min_angle>
<max_angle>0.00</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>3</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range2">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>50</updateRate>
<topicName>sensor/ir_back_2</topicName>
<frameName>ir_back_2_link</frameName>
<radiation>INFRARED</radiation>
<fov>0.2967</fov>
</plugin>
</sensor>
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="ir_back_3_link">
<sensor type="ray" name="TeraRanger">
<visualize>true</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</horizontal>
<vertical>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.00</min_angle>
<max_angle>0.00</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>3</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range3">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>50</updateRate>
<topicName>sensor/ir_back_3</topicName>
<frameName>ir_back_3_link</frameName>
<radiation>INFRARED</radiation>
<fov>0.2967</fov>
</plugin>
</sensor>
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="ir_front_1_link">
<sensor type="ray" name="TeraRanger">
<visualize>true</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</horizontal>
<vertical>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>3</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range4">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>50</updateRate>
<topicName>sensor/ir_front_1</topicName>
<frameName>ir_front_1_link</frameName>
<radiation>INFRARED</radiation>
<fov>0.2967</fov>
</plugin>
</sensor>
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="ir_front_2_link">
<sensor type="ray" name="TeraRanger">
<visualize>true</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</horizontal>
<vertical>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>3</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range5">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>50</updateRate>
<topicName>sensor/ir_front_2</topicName>
<frameName>ir_front_2_link</frameName>
<radiation>INFRARED</radiation>
<fov>0.2967</fov>
</plugin>
</sensor>
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="ir_front_3_link">
<sensor type="ray" name="TeraRanger">
<visualize>true</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</horizontal>
<vertical>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>3</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range6">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>50</updateRate>
<topicName>sensor/ir_front_3</topicName>
<frameName>ir_front_3_link</frameName>
<radiation>INFRARED</radiation>
<fov>0.2967</fov>
</plugin>
</sensor>
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="ir_front_4_link">
<sensor type="ray" name="TeraRanger">
<visualize>true</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</horizontal>
<vertical>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>3</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range7">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>50</updateRate>
<topicName>sensor/ir_front_4</topicName>
<frameName>ir_front_4_link</frameName>
<radiation>INFRARED</radiation>
<fov>0.2967</fov>
</plugin>
</sensor>
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="ir_front_5_link">
<sensor type="ray" name="TeraRanger">
<visualize>true</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</horizontal>
<vertical>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.02</min_angle>
<max_angle>0.02</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>3</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range8">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>50</updateRate>
<topicName>sensor/ir_front_5</topicName>
<frameName>ir_front_5_link</frameName>
<radiation>INFRARED</radiation>
<fov>0.2967</fov>
</plugin>
</sensor>
<material>Gazebo/Red</material>
</gazebo>
</robot>
<?xml version="1.0"?>
<!-- Revolute-Revolute Manipulator -->
<robot name="robot_car" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="mass" value="0.4" /> <!-- arbitrary value for mass -->
<xacro:property name="mass_wheel" value="0.3" />
<xacro:property name="inertia_factor" value="0.7" />
<xacro:property name="camera_link" value="0.05" /> <!-- Size of square 'camera' box -->
<xacro:property name="wheel_horizontal_shift" value="0.063" /> <!-- arbitrary value for mass -->
<xacro:property name="wheel_vertical_shift" value="0.030" />
<xacro:property name="wheel_pitch" value="${PI/2}" />
<xacro:property name="wheel_yaw" value="0" />
<xacro:property name="wheel_radius" value="0.03" />
<xacro:property name="wheel_length" value="0.02" />
<xacro:property name="body_x" value="0.067" />
<xacro:property name="body_y" value="0.085" />
<xacro:property name="body_z" value="0.020" />
<xacro:property name="wheel_r" value="0.030" />
<xacro:property name="wheel_h" value="0.024" />
<xacro:property name="camera_x" value="0.0" />
<xacro:property name="camera_y" value="-0.024" />
<xacro:property name="camera_z" value="0.1" />
<xacro:property name="camera_roll" value="${PI / 10}" />
<xacro:property name="camera_width" value="0.01" />
<xacro:property name="center_to_back" value="-0.1" />
<xacro:property name="center_to_front" value="0.07" />
<xacro:property name="ir_back_vertical_shift" value="0.005" />
<xacro:property name="ir_back_angle_diff" value="${PI/18}" />
<xacro:property name="ir_back_1_x" value="0.030" />
<xacro:property name="ir_back_1_y" value="${center_to_back + ir_back_vertical_shift}" />
<xacro:property name="ir_back_1_z" value="${body_z}" />
<xacro:property name="ir_back_1_yaw" value="${-PI/2 + ir_back_angle_diff}" />
<xacro:property name="ir_back_2_x" value="0.0" />
<xacro:property name="ir_back_2_y" value="${center_to_back}" />
<xacro:property name="ir_back_2_z" value="${body_z}" />
<xacro:property name="ir_back_2_yaw" value="${-PI/2}" />
<xacro:property name="ir_back_3_x" value="${-ir_back_1_x}" />
<xacro:property name="ir_back_3_y" value="${ir_back_1_y}" />
<xacro:property name="ir_back_3_z" value="${body_z}" />
<xacro:property name="ir_back_3_yaw" value="${-PI/2 - ir_back_angle_diff}" />
<xacro:property name="ir_front_horizontal_shift" value="0.015" />
<xacro:property name="ir_front_vertical_shift" value="0.005" />
<xacro:property name="ir_front_angle_diff" value="${PI/18}" />
<xacro:property name="ir_front_1_x" value="${ir_front_horizontal_shift * -2}" />
<xacro:property name="ir_front_1_y" value="${center_to_front + ir_front_vertical_shift * -2}" />
<xacro:property name="ir_front_1_z" value="${body_z}" />
<xacro:property name="ir_front_1_yaw" value="${PI/2 + ir_front_angle_diff * 2}" />
<xacro:property name="ir_front_2_x" value="${ir_front_horizontal_shift * -1}" />
<xacro:property name="ir_front_2_y" value="${center_to_front + ir_front_vertical_shift * -1}" />
<xacro:property name="ir_front_2_z" value="${body_z}" />
<xacro:property name="ir_front_2_yaw" value="${PI/2 + ir_front_angle_diff * 1}" />
<xacro:property name="ir_front_3_x" value="${ir_front_horizontal_shift * 0}" />
<xacro:property name="ir_front_3_y" value="${center_to_front}" />
<xacro:property name="ir_front_3_z" value="${body_z}" />
<xacro:property name="ir_front_3_yaw" value="${PI/2 + ir_front_angle_diff * 0}" />
<xacro:property name="ir_front_4_x" value="${ir_front_horizontal_shift * 1}" />
<xacro:property name="ir_front_4_y" value="${ir_front_2_y}" />
<xacro:property name="ir_front_4_z" value="${body_z}" />
<xacro:property name="ir_front_4_yaw" value="${PI/2 + ir_front_angle_diff * -1}" />
<xacro:property name="ir_front_5_x" value="${ir_front_horizontal_shift * 2}" />
<xacro:property name="ir_front_5_y" value="${ir_front_1_y}" />
<xacro:property name="ir_front_5_z" value="${body_z}" />
<xacro:property name="ir_front_5_yaw" value="${PI/2 + ir_front_angle_diff * -2}" />
<xacro:property name="ir_width" value="0.01" />
<xacro:arg name="body_color" default="Gazebo/Green"/>
<xacro:arg name="model_name" default="undefined"/>
<!-- Import all Gazebo-customization elements, including Gazebo colors -->
<xacro:include filename="$(find robot_car_description)/urdf/robot_car.gazebo" />
<!-- Import Rviz colors -->
<xacro:include filename="$(find robot_car_description)/urdf/materials.xacro" />
<!-- Used for fixing robot to Gazebo 'base_link' -->
<!-- Base Link -->
<link name="robot_car_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_car_description/meshes/robot_car.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_car_description/meshes/robot_car.stl" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 ${wheel_vertical_shift} 0" rpy="0 0 0"/>
<mass value="${mass}"/>
<inertia
ixx="${1/5 * mass * (body_y**2 + body_z**2)}" ixy="0.0" ixz="0.0"
iyy="${1/5 * mass * (body_x**2 + body_z**2)}" iyz="0.0"
izz="${1/5 * mass * (body_x**2 + body_y**2)}"/>
</inertial>
</link>
<link name="robot_car_left_wheel_link">
<collision>
<origin xyz="0 0 0" rpy="0 ${wheel_pitch} ${wheel_yaw}"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 ${wheel_pitch} ${wheel_yaw}"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${mass_wheel}"/>
<!--<inertia
ixx="${1/2 * mass_wheel * wheel_r ** 2}" ixy="0.0" ixz="0.0"
iyy="${1/12 * mass_wheel * (3 * wheel_r ** 2 + wheel_h ** 2)}" iyz="0.0"
izz="${1/12 * mass_wheel * (3 * wheel_r ** 2 + wheel_h ** 2)}"/>-->
<inertia
ixx="${1/2 * mass_wheel * wheel_r ** 2}" ixy="0.0" ixz="0.0"
iyy="${1/12 * mass_wheel * (3 * wheel_r ** 2 + wheel_h ** 2)}" iyz="0.0"
izz="${1/12 * mass_wheel * (3 * wheel_r ** 2 + wheel_h ** 2)}"/>
</inertial>
</link>
<link name="robot_car_right_wheel_link">
<collision>
<origin xyz="0 0 0" rpy="0 ${wheel_pitch} ${wheel_yaw}"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 ${wheel_pitch} ${wheel_yaw}"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${mass_wheel}"/>
<inertia
ixx="${1/2 * mass_wheel * wheel_r ** 2}" ixy="0.0" ixz="0.0"
iyy="${1/12 * mass_wheel * (3 * wheel_r ** 2 + wheel_h ** 2)}" iyz="0.0"
izz="${1/12 * mass_wheel * (3 * wheel_r ** 2 + wheel_h ** 2)}"/>
</inertial>
</link>
<joint name="robot_car_left_wheel_joint" type="continuous">
<axis xyz="-1 0 0" />
<origin xyz="${-wheel_horizontal_shift} ${wheel_vertical_shift} 0" rpy="0 0 0"/>
<parent link="robot_car_link"/>
<child link="robot_car_left_wheel_link"/>
</joint>
<joint name="robot_car_right_wheel_joint" type="continuous">
<axis xyz="-1 0 0" />
<origin xyz="${wheel_horizontal_shift} ${wheel_vertical_shift} 0" rpy="0 0 0"/>
<parent link="robot_car_link"/>
<child link="robot_car_right_wheel_link"/>
</joint>
<joint name="camera_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="robot_car_link"/>
<child link="camera_link"/>
</joint>
<!-- Camera -->
<link name="camera_link">
<collision>
<origin xyz="0 ${camera_y} ${camera_z}" rpy="${camera_roll} 0 0"/>
<geometry>
<box size="${camera_width} ${camera_width} ${camera_width}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 ${camera_y} ${camera_z}" rpy="${camera_roll} 0 0"/>
<geometry>
<box size="${camera_width} ${camera_width} ${camera_width}"/>
</geometry>
<material name="red"/>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="camera_optical_joint" type="fixed">
<!-- these values have to be these values otherwise the gazebo camera image
won't be aligned properly with the frame it is supposedly originating from -->
<origin xyz="0 ${camera_y} ${camera_z}" rpy="${-PI/2 - camera_roll} 0 ${-PI/2 -PI/2}"/>
<parent link="camera_link"/>
<child link="camera_link_optical"/>
</joint>
<link name="camera_link_optical">
</link>
<joint name="ir_back_1_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${ir_back_1_x} ${ir_back_1_y - ir_width/2} 0" rpy="0 0 ${ir_back_1_yaw}"/>
<parent link="robot_car_link"/>
<child link="ir_back_1_link"/>
</joint>
<link name="ir_back_1_link">
<collision>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</collision>
<visual>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="ir_back_2_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0 ${ir_back_2_y - ir_width/2} 0" rpy="0 0 ${ir_back_2_yaw}"/>
<parent link="robot_car_link"/>
<child link="ir_back_2_link"/>
</joint>
<link name="ir_back_2_link">
<collision>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</collision>
<visual>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="ir_back_3_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${ir_back_3_x} ${ir_back_3_y - ir_width/2} 0" rpy="0 0 ${ir_back_3_yaw}"/>
<parent link="robot_car_link"/>
<child link="ir_back_3_link"/>
</joint>
<link name="ir_back_3_link">
<collision>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</collision>
<visual>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="ir_front_1_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${ir_front_1_x} ${ir_front_4_y + ir_width/2} 0" rpy="0 0 ${ir_front_1_yaw}"/>
<parent link="robot_car_link"/>
<child link="ir_front_1_link"/>
</joint>
<link name="ir_front_1_link">
<collision>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</collision>
<visual>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="ir_front_2_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${ir_front_2_x} ${ir_front_4_y + ir_width/2} 0" rpy="0 0 ${ir_front_2_yaw}"/>
<parent link="robot_car_link"/>
<child link="ir_front_2_link"/>
</joint>
<link name="ir_front_2_link">
<collision>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</collision>
<visual>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="ir_front_3_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${ir_front_3_x} ${ir_front_4_y + ir_width/2} 0" rpy="0 0 ${ir_front_3_yaw}"/>
<parent link="robot_car_link"/>
<child link="ir_front_3_link"/>
</joint>
<link name="ir_front_3_link">
<collision>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</collision>
<visual>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="ir_front_4_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${ir_front_4_x} ${ir_front_4_y + ir_width/2} 0" rpy="0 0 ${ir_front_4_yaw}"/>
<parent link="robot_car_link"/>
<child link="ir_front_4_link"/>
</joint>
<link name="ir_front_4_link">
<collision>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</collision>
<visual>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="ir_front_5_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${ir_front_5_x} ${ir_front_4_y + ir_width/2} 0" rpy="0 0 ${ir_front_5_yaw}"/>
<parent link="robot_car_link"/>
<child link="ir_front_5_link"/>
</joint>
<link name="ir_front_5_link">
<collision>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</collision>
<visual>
<origin xyz="${-ir_width/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${ir_width} ${ir_width} ${ir_width}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="robot_car_left_wheel_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="robot_car_left_wheel_joint_actuator">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>7</mechanicalReduction>
</actuator>
</transmission>
<transmission name="tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="robot_car_right_wheel_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="robot_car_right_wheel_joint_actuator">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>7</mechanicalReduction>
</actuator>
</transmission>
</robot>
view raw robot_car.xacro hosted with ❤ by GitHub
這篇文章的重點是把幾個ROS, 跟Gazebo基本教學介紹的功能兜起來,也可以試試看執行roslaunch robot_car_description robot_car.launch,可以在rviz看到機器車,我都用來檢查機器人各位置的元件位置跟座標軸有沒有正確,啟動比Gazebo快多了。

之後的文章會繼續解析裡面的小元件,比如怎麼用freecad自己畫機器零件,然後導入gazebo,還有增加camera與sensors到機器車上。

歡迎給任何意見,一起互相學習!

留言

  1. 謝謝你的分享!講的真的很詳細!期待之後的文章 :)

    回覆刪除
  2. 想詢問一下,缺少了一個叫rospkg,要如何新增

    回覆刪除

張貼留言

熱門文章