Autolabor Simulation Base 模塊介紹 | Autolabor Simulation

前期內(nèi)容:

功能介紹

Autolabor Simulation Base 主要用于模擬差速轉(zhuǎn)向的移動機器人底盤,其運作模式為訂閱 ROS速度信息 ,根據(jù)底盤自身參數(shù)限制(這里主要限制因素有最大速度與最大加速度),以及設(shè)置的噪音參數(shù)模擬小車運行速度。并根據(jù)速度控制小車在X-Y平面中行駛。

小車在運行過程中會發(fā)布 ROS里程計信息 此處里程計數(shù)據(jù)中包含噪聲,用于模擬真實情況下的里程計數(shù)據(jù)。

同時該模塊會發(fā)布兩個坐標(biāo)轉(zhuǎn)換信息

  • 里程計坐標(biāo)系 ——> 小車底盤坐標(biāo)系 的坐標(biāo)轉(zhuǎn)換
  • 小車底盤坐標(biāo)系 ——> 真實坐標(biāo)系 的坐標(biāo)轉(zhuǎn)換

note

在ROS中坐標(biāo)轉(zhuǎn)換樹中,一個子節(jié)點最多只能有一個父節(jié)點。作為子節(jié)點 小車底盤坐標(biāo)系 不能同時擁有兩個坐標(biāo)系(里程計坐標(biāo)系,*真實坐標(biāo)系),所以在坐標(biāo)轉(zhuǎn)換樹中將真實坐標(biāo)系* 作為 小車底盤坐標(biāo)系 的子節(jié)點。

節(jié)點信息

訂閱話題

話題名稱:/cmd_vel

消息類型:geometry_msgs/Twist

話題說明:用于控制機器人地盤運動的速度指令

geometry_msgs/Twist 數(shù)據(jù)類型說明

geometry_msgs/Vector3 linear    線速度 單位為 m/s
  float64 x                     前后移動的速度,+表示向前,-表示向后
  float64 y                     左右移動的速度,+表示向左,-表示向右
  float64 z                     上下移動的速度,+表示向上,-表示向下
geometry_msgs/Vector3 angular   角速度 單位為 rad/s
  float64 x                     橫滾角速度,正負號依據(jù)右手法則決定
  float64 y                     俯仰角速度,正負號依據(jù)右手法則決定
  float64 z                     航向角速度,俯視小車時,+表示逆時針旋轉(zhuǎn),-表示順時針旋轉(zhuǎn)

小車使用差速轉(zhuǎn)向,僅能前后運動,所以在 線速度 中只有 X分量 有數(shù)據(jù),其余分量為0
小車在水平面行駛,僅能水平轉(zhuǎn)動,所以在 角速度 中只有 Z分量 有數(shù)據(jù),其余分量為0

發(fā)布話題

話題名稱:/odom

消息類型:nav_msgs/Odometry

話題說明:發(fā)布機器人的輪速里程計信息(此處數(shù)據(jù)帶有噪音)

nav_msgs/Odometry 數(shù)據(jù)類型說明

std_msgs/Header header                     數(shù)據(jù)頭信息
  uint32 seq                               數(shù)據(jù)序列號
  time stamp                               數(shù)據(jù)時間戳信息
  string frame_id                          姿態(tài)數(shù)據(jù)(pose)所處的坐標(biāo)系
string child_frame_id                      速度數(shù)據(jù)(twist)所在的坐標(biāo)系
geometry_msgs/PoseWithCovariance pose
  geometry_msgs/Pose pose                  里程計姿態(tài)數(shù)據(jù)信息
    geometry_msgs/Point position           里程計姿態(tài)數(shù)據(jù)的位置信息
      float64 x
      float64 y
      float64 z
    geometry_msgs/Quaternion orientation   里程計姿態(tài)數(shù)據(jù)的方向信息(四元數(shù))
      float64 x
      float64 y
      float64 z
      float64 w
  float64[36] covariance                   姿態(tài)數(shù)據(jù)的協(xié)方差矩陣(x, y, z, roll, pitch, yaw)
geometry_msgs/TwistWithCovariance twist    里程計速度數(shù)據(jù)信息
  geometry_msgs/Twist twist
    geometry_msgs/Vector3 linear           線速度信息
      float64 x
      float64 y
      float64 z
    geometry_msgs/Vector3 angular          角速度信息
      float64 x
      float64 y
      float64 z
  float64[36] covariance                   速度信息的協(xié)方差矩陣(vx, vy, vz, v_roll, v_pitch, v_yaw)

節(jié)點參數(shù)


參數(shù)名稱:~odom_frame

參數(shù)類型:string

默認數(shù)據(jù):odom

參數(shù)說明:里程計坐標(biāo)系的名稱


參數(shù)名稱:~base_link_frame

參數(shù)類型:string

默認數(shù)據(jù):base_link

參數(shù)說明:小車坐標(biāo)系的名稱


參數(shù)名稱:~real_map_frame

參數(shù)類型:string

默認數(shù)據(jù):real_map

參數(shù)說明:真實坐標(biāo)系的名稱


關(guān)于以上三個坐標(biāo)系的介紹,請看前期內(nèi)容ROS坐標(biāo)轉(zhuǎn)換講解


參數(shù)名稱:~noise_v_linear

參數(shù)類型:double

默認數(shù)據(jù):0.0

參數(shù)限制:必須大于等于0

參數(shù)說明:模擬行駛過程中在線速度中添加白噪音的標(biāo)準(zhǔn)差,單位為m/s,默認為不添加噪音


參數(shù)名稱:~noise_v_theta

參數(shù)類型:double

默認數(shù)據(jù):0.0

參數(shù)限制:必須大于等于0

參數(shù)說明:模擬行駛過程中在角速度中添加白噪音的標(biāo)準(zhǔn)差,單位為rad/s,默認為不添加噪音


參數(shù)名稱:~max_a_linear

參數(shù)類型:double

默認數(shù)據(jù):999.0

參數(shù)限制:必須大于0

參數(shù)說明:小車底盤行駛最大線加速度,單位為 m/s^2, 默認是一個比較大的值,在正常模擬情況下。小車能直接達到所給的速度


參數(shù)名稱:~max_a_theta

參數(shù)類型:double

默認數(shù)據(jù):999.0

參數(shù)限制:必須大于0

參數(shù)說明:小車底盤行駛最大角加速度,單位為 rad/s^2, 默認是一個比較大的值,在正常模擬情況下。小車能直接達到所給的速度


參數(shù)名稱:~max_v_linear

參數(shù)類型:double

默認數(shù)據(jù):1.0

參數(shù)限制:必須大于0

參數(shù)說明:小車底盤行駛線速度絕對值的最大值,單位為 m/s,比如在默認情況下,小車行駛速度為 -1.0 m/s \leq v \leq 1.0 m/s, 當(dāng)控制速度超出這個范圍,小車按照離控制速度最近的極值運行


參數(shù)名稱:~max_v_theta

參數(shù)類型:double

默認數(shù)據(jù):1.57

參數(shù)限制:必須大于0

參數(shù)說明:小車底盤行駛角速度絕對值的最大值,單位為 rad/s,說明與 max_v_linear 類似


參數(shù)名稱:~rate

參數(shù)類型:int

默認數(shù)據(jù):30

參數(shù)限制:必須大于0

參數(shù)說明:小車模擬行駛更新位置的頻率,也是里程計信息發(fā)布的頻率,這個值越大,小車模擬行駛越平滑,同時需要計算量也就越大


使用示例

以下的實驗步驟必須在安裝好ROS環(huán)境以及編譯Autolabor Simulation功能包(如何編譯)的基礎(chǔ)下進行,如果您還未執(zhí)行上述操作,請先參考前面的使用文檔。假設(shè)ROS工作目錄為 ~/catkin_ws,并且Autolabor Simulation的源碼放在 ~/catkin_ws/src 中,如果你的環(huán)境和上述不一致,需要在下面的腳本中做相應(yīng)的替換。

進入ROS工作目錄

cd ~/catkin_ws

編譯模擬器(如果您已經(jīng)編譯過,可忽略此步)

catkin_make

添加模擬器相關(guān)環(huán)境變量

source devel/setup.bash

執(zhí)行添加鍵盤映射腳本(此操作只需操作一次)

cd ~/catkin_ws/autolabor_simulation-master/script
./add_keyboard_udev

進入autolabor_simulation_base包的launch文件夾

roscd autolabor_simulation_base/launch

創(chuàng)建ROS腳本文件

echo '<!-- autolabor_simulation_base demo -->
<launch>
    <arg name="model" />
    <arg name="gui" default="false" />

    <param name="use_sim_time" value="false"/>
    <param name="robot_description" textfile="$(find autolabor_description)/urdf/autolabor_pro1.urdf" />
    <param name="use_gui" value="$(arg gui)" />

    <node pkg="autolabor_simulation_base" type="simulation_base_node" name="autolabor_driver" output="screen">
        <param name="odom_frame" value="odom"/>
        <param name="base_link_frame" value="base_link"/>
        <param name="real_map_frame" value="real_map"/>

        <param name="noise_v_linear" value="0"/>
        <param name="noise_v_theta" value="0"/>

        <param name="max_a_linear" value="999.0"/>
        <param name="max_a_theta" value="999.0"/>

        <param name="max_v_linear" value="1.0"/>
        <param name="max_v_theta" value="1.57"/>

        <param name="rate" value="100"/>
    </node>

    <node name="keyboard_control" pkg="autolabor_keyboard_control" type="keyboard_control_node">
        <param name="linear_min" value="0.2" />
        <param name="linear_max" value="1.0" />
        <param name="linear_step" value="0.2" />

        <param name="angular_min" value="0.5" />
        <param name="angular_max" value="1.57" />
        <param name="angular_step" value="0.5" />
    </node>

    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
    <node name="rviz" pkg="rviz" type="rviz"/>
</launch>
' > demo_simulation_base.launch

執(zhí)行剛才我們建立的ROS腳本

roslaunch autolabor_simulation_base demo_simulation_base.launch

此時我們會發(fā)現(xiàn)打開了一個窗口,如圖所示

rviz窗口

在rviz的左側(cè)Displays窗口,找到 Global Options -> Fixed Frame,并將后面的值選成odom,如下圖

修改Fixed Frame

點擊rviz左下角的Add按鈕,在跳出的窗口中選擇 rviz -> TF,并單擊OK按鈕

Add TF

同上操作步驟,點擊rviz左下角的Add按鈕,添加 rviz -> RobotModel,并單擊OK按鈕

Add RobotModel

我們在中間區(qū)域看到一個小黃車,此時我們就可以使用鍵盤上的上,下,左,右控制小車行進。

控制小車行駛

我們再來詳細看一下坐標(biāo)轉(zhuǎn)換關(guān)系,關(guān)閉小車模型,將視窗放大。

TF轉(zhuǎn)換關(guān)系

根據(jù)默認設(shè)置,base_link表示小車坐標(biāo)系,隨著通過鍵盤控制,base_link坐標(biāo)系在移動,在中間兩個靜止的坐標(biāo)系分別是odom(里程計編碼器)和real_map(真實坐標(biāo)系)。由于我們沒有設(shè)置里程計噪音real_map和odom始終重合,也就意味著里程計信息完全準(zhǔn)確。

這個時候我們可以嘗試修改ROS腳本文件demo_simulation_base.launch,將noise_v_linear改成0.2,noise_v_theta改成0.5。

首先在剛才打開Terminal的窗口使用Ctrl+C,結(jié)束之前的命令,并輸入下面內(nèi)容。

sed -i 's/<param name="noise_v_linear" value="0"\/>/<param name="noise_v_linear" value="0.2"\/>/' demo_simulation_base.launch
sed -i 's/<param name="noise_v_theta" value="0"\/>/<param name="noise_v_theta" value="0.5"\/>/' demo_simulation_base.launch

此時再運行該腳本

roslaunch autolabor_simulation_base demo_simulation_base.launch

按照上面的方法在rviz中添加tf數(shù)據(jù)顯示

帶噪音的情況

會發(fā)現(xiàn)在小車行駛過程中,odom和real_map之間發(fā)生相對變化,這個變化就是里程計偏離真實位置的情況。

?著作權(quán)歸作者所有,轉(zhuǎn)載或內(nèi)容合作請聯(lián)系作者
【社區(qū)內(nèi)容提示】社區(qū)部分內(nèi)容疑似由AI輔助生成,瀏覽時請結(jié)合常識與多方信息審慎甄別。
平臺聲明:文章內(nèi)容(如有圖片或視頻亦包括在內(nèi))由作者上傳并發(fā)布,文章內(nèi)容僅代表作者本人觀點,簡書系信息發(fā)布平臺,僅提供信息存儲服務(wù)。

相關(guān)閱讀更多精彩內(nèi)容

友情鏈接更多精彩內(nèi)容