Seirios RNS 導航軟體有提供REST APIs 給您使用,讓你可以整合和更進階的部署功能,
請在電腦上輸入localhost:8000 或是 <IPaddress>:8000 ,就可看到一連串APIs的列表。
或是你也可以在此下載檔案瀏覽APIs的相關資訊 ⬇️
The Pebble Planner 是一個簡單的本地規劃器,旨在密切遵循全球規劃。其優點包括更少的可配置參數,調整指引和更少的擺動運動。
Pebble planner takes the global plan, decimates it to space out the poses as “pebbles”, then tries to reach them one by one.
It does this by rotating towards the next pebble, then accelerating until max velocity is reached.
Filepath: catkin_ws/movel_ai/config/movel/config/
File to modify: base_local_planner_params.yaml
Same steps as setting up for TEB Local Planner. In the file, uncomment the section PebbleLocalPlanner to set your local planner to use Pebble.
Filepath: catkin_ws/movel_ai/config/velocity_setter/config/
File to modify: velocity_setter.yaml
Change the param local_planner: "PebbleLocalPlanner".
Make sure you changed the params in both files or else error may be thrown.
PebbleLocalPlanner:
d_min: 0.30
robot_frame: base_link
map_frame: map
xy_goal_tolerance: 0.15
yaw_goal_tolerance: 0.3925
kp_linear: 1.0
ki_linear: 0.0
kd_linear: 0.0
kp_angular: 1.0
ki_angular: 0.0
kd_angular: 0.1
max_vel_x: 0.3
max_vel_theta: 0.785
acc_lim_x: 0.5
acc_lim_theta: 0.785
allow_reverse: true
th_turn: 1.0472 #1.0472 : 60 deg, how far the robot faces from the waypoint before suppressing linear motion
local_obstacle_avoidance: true # whether to let the local planner do obsav. If false, rely on the global planner, and planning frequency must not be zero
N_lookahead: 3 # how many multiples of d_min to look ahead when eval'ing obstaclesCompared to TEB, pebble planner has fewer configurable params.
Can be generally classified as Probably Important, Optional and Can Be Ignored.
d_min - Min distance of the next pose, to qualify as a pebble. If you feel the robot is oscillating too much, increasing this value helps.
allow_reverse - Determines whether the robot can move backwards or not. Set this value to false if you don't want your robot to be moving backwards. Recommended if your robot doesn't have sensors at the back.
acc_lim_theta - Limits the angular rotation. Pebble planner will rotate the robot towards the next pebble, then accelerates towards it (till max speed). Planned path may be straighter if angular acceleration is lowered.
xy_goal_tolerance - Tolerable distance away from the intended goal.
yaw_goal_tolerance - Angular tolerance between where you want the robot to face and where it actually faces.
acc_lim_x - Limits how fast the robot speeds up to the next pebble. Robots need time to think and stop when it sees an obstacle. Robots may have less time to react if it is previously speeding.
local_obstacle_avoidance - Whether you want Pebble Planner to handle obstacle avoidance or not. Else, obstacle avoidance will be handled by global planner.
N_lookahead - How many pebbles to look ahead when evaluating obstacles.
max_vel_x, max_vel_theta - These values will be set by the UI depending on what values you give there. Can ignore if you are using the UI.
(kp, ki, kd values) - Probably just configurations for differential drive.
Seirios可支援各式各樣的感測器,也支援各種不同的組合,提供給不同應用層面的機器人 。
以下展示的感測器,皆經過Seirios RNS安裝測試過,都可以在各式的機器人種類上順利執行。
電腦、迷你 PC 和其他開發板配備 x86 或 ARM64 芯片。 點擊下一步,以查看經過 Seirios 測試硬件。
電腦處理能力對於在機器人上運行 Seirios RNS 至關重要。 隨著安裝的感測器越多,將需要分配更多的計算能力 - Seirios 可用的計算能力將減少
以下是推薦的 PC/板規格,以讓 Seirios RNS 上的每個功能,都可以享受到此效能:
PC with x86 processor (4 cores with 8 threads @ >3.1GhZ) 或是 ARM64 (8 cores)
8GB DDR4 RAM
256GB SSD
Ubuntu 20.04 & ROS Noetic (x86) 或是 Ubuntu 18.04 & ROS Melodic (ARM64)
WiFi connectivity 802.11a/b/g/n/ac
以下為我們使用 Seirios RNS 測試過的特定 PC 和開發板。
Coming soon!
如果您不確定您的感測器是否有被支援,請來信 [email protected] 聯繫我們。
external_process_handler 外部設備整合包是一套完整的程序,可以提供使用者去執行外部的任務,整合到Seirios的介面上。
Pre-setup: 請確保你的Seirios運行正常。
本指南向您展示如何使用 external_process_handler 外部設備整合包,將您自己的程序作為插件整合到 Seirios 中。
您將會需要:
Seirios 導航軟體
您自備的程式碼
請確認您的ROS版本。
若您是 Ubuntu 20.04, ROS Noetic的使用者 :
請至以下連結下載 .deb package: https://drive.google.com/drive/folders/1hpi5NaSkFyr6QVXs83taxeHjWLulw8SH
移動 .deb 此安裝包的你的資料夾,打開終端視窗,請執行此指令 sudo apt install ./ros-noetic-movel-seirios-msgs_0.0.0-0focalXXX64.deb 以下載安裝。
其餘版本的使用者:
Git clone this repo here: https://gitlab.com/movelai_public/movel_seirios_msgs/-/tree/master/srv into your catkin workspace.
Run catkin_make this repo to compile so that it will be usable.
你需要功能去與 external_program_handler溝通,以執行你啟動的指令和停止的指令。
你的程式中必須有一些東西可以告訴 Seirios 啟動程序和停止程序。 啟動時,可以使用 ROS 服務或啟動文件來完成。 需要停止時,可以使用 ROS 服務或訂閱主題來完成
以下為程式碼範例 (python and c++)
啟動Starting
在您的程序中,添加一個服務,將其命名為 service_start 。 編寫一個處理程序 start_handler作為回調來處理您的啟動程式碼。
停止Stopping
將另一個服務初始化為service_stop。 同樣,編寫一個回調 stop_handler來處理您的程式碼以停止程序。
你必須使用Seirios程式包。
movel_seirios_msgs以執行service_start和service_stop。要使用該程式包,請在下面添加導入語句。 如果您使用 C++,還必須包括其他配置。
from movel_seirios_msgs.srv import StringTrigger, StringTriggerResponse # like setbool#include <movel_seirios_msgs/StringTrigger.h>C++ 的額外配置
對於 C++ 程序,您還必須在自己包中的 package.xml 中添加 movel_seirios_msgs 包作為相依
<depend>movel_seirios_msgs</depend>在自己的程式包CMakeLists.txt中, 添加 movel_seirios_msgs ,在此 find_package 之下。
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
movel_seirios_msgs
)如果您是從 UI 發布停止主題來停止程序,請參閱本節。 否則,忽略它。
請撰寫訂閱者 topic_process_cancel去訂閱此UI主題, 其中 handle_publish_cancel的回調中,請包含您的停止程式碼。
1.3. 發布客戶的狀態
如果您從啟動文件啟動程序,請參閱本節。 否則,忽略它。
這樣做的目的,是要檢查從啟動文件,啟動程序後您的程序,是否有運行成功。
請撰寫發布者 client_status ,如果運行成功,請發佈2 ; 如果運行失敗,請發布3。
您可以參考範例程式碼,了解如何使用外部設備整合包,來去啟動程序和停止程序。
回調函數中的程式碼,只是用於測試 external_process_handler 的填充代碼。 可以使用您自己的開始程式碼和停止程式碼來替換它們。
#!/usr/bin/env python
import rospy
from movel_seirios_msgs.srv import StringTrigger, StringTriggerResponse # like setbool
from std_msgs.msg import Bool, UInt8
class Pytest:
def __init__(self):
print('starting test node')
self.node = rospy.init_node('python_test')
self.service_start = rospy.Service('/external_process/trigger_detecting', StringTrigger, self.start_handler)
self.service_stop = rospy.Service('/external_process/stop_detecting', StringTrigger, self.stop_handler)
# IGNORE dummy_publisher - just to simulate UI cancel topic
self.dummy_publisher = rospy.Publisher('/cancel_publish', Bool, queue_size=1)
self.topic_process_cancel = rospy.Subscriber('/cancel_publish', Bool, self.handle_publish_cancel)
self.client_status = rospy.Publisher('/external_process/client_status', UInt8, queue_size=1)
self.flag = True
def start_handler(self, req):
print('inside start handler')
start_msg = StringTriggerResponse()
start_msg.success = True
start_msg.message = 'starting detect'
self.flag = True
self.publish_client_status()
while(self.flag):
print('executing something')
rospy.sleep(1)
return start_msg # return must be [success, message format]
def stop_handler(self, req):
print('inside stop handler')
self.flag = False
print('stop handler called')
stop_msg = StringTriggerResponse()
stop_msg.success = False
stop_msg.message = 'stopping detect'
return stop_msg
# IGNORE if you are not using a topic to stop your code
def handle_publish_cancel(self, req):
print("inside publish cancel", req.data)
cancel_trigger = req.data
if(cancel_trigger):
print('executing cancel stuff') # replace print statement
# IGNORE if you are not using launch files
def publish_client_status(self):
print("publish client status called")
cstatus = UInt8()
#Dummy code
#Decide how do you determine if your launch file is successful
#And replace the if-else statement
if (self.flag == True):
cstatus.data = 2 # if start_handler successfully called, task is successful and return 2
else:
cstatus.data = 3 # else task not successful, return 3
self.client_status.publish(cstatus)
if __name__ == '__main__':
py_test = Pytest()
#py_test.publish_cancel()
rospy.spin()#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <std_msgs/UInt8.h>
#include <movel_seirios_msgs/StringTrigger.h>
class Cpptest {
private:
ros::ServiceServer service_start;
ros::ServiceServer service_stop;
ros::Publisher dummy_publisher;
ros::Subscriber topic_process_cancel;
ros::Publisher client_status;
bool flag;
public:
Cpptest(ros::NodeHandle *nh) {
service_start = nh->advertiseService("/external_package/triggering_detect_cpp", &Cpptest::start_handler, this);
service_stop = nh->advertiseService("/external_package/stopping_detect_cpp", &Cpptest::stop_handler, this);
// Ignore dummy_publisher - just to simulate ui cancel button
dummy_publisher = nh->advertise<std_msgs::Bool>("/cancel_publish_cpp", 10);
topic_process_cancel = nh->subscribe("/cancel_publish_cpp", 1, &Cpptest::handle_publish_cancel, this);
client_status = nh->advertise<std_msgs::UInt8>("/external_process/client_status_cpp", 10);
}
bool start_handler(movel_seirios_msgs::StringTrigger::Request &req, movel_seirios_msgs::StringTrigger::Response &res) {
std::cout << "inside start handler\n";
res.success = true;
res.message = "starting detect";
//std::cout << res << "\n";
flag = true;
publish_client_status();
std::cout << "start handler flag "<< flag << "\n";
return true;
}
bool stop_handler(movel_seirios_msgs::StringTrigger::Request &req, movel_seirios_msgs::StringTrigger::Response &res) {
std::cout << "inside stop handler\n";
res.success = false;
res.message = "stopping detect";
//std::cout << res << "\n";
flag = false;
std::cout << "stop handler flag "<< flag << "\n";
return true;
}
// Ignore this method if not subscribing to stop topic
void handle_publish_cancel(const std_msgs::Bool& msg) {
std::cout << "inside handle publish cancel\n";
bool cancel_trigger;
cancel_trigger = msg.data;
//std::cout << "published msg " << cancel_trigger << "\n";
if(cancel_trigger){
std::cout << "do canceling stuff. cancel_trigger: " << cancel_trigger << "\n";
}
}
// Ignore this method if not using launch
void publish_client_status() {
std::cout << "publish client status called\n";
std_msgs::UInt8 cstatus;
if(flag) {
cstatus.data = 2;
}
else {
cstatus.data = 3;
}
std::cout << "client status " << cstatus << "2 for success, 3 for fail \n";
client_status.publish(cstatus);
}
};
int main(int argc, char** argv) {
ros::init(argc, argv, "cpp_test");
ros::NodeHandle nh;
Cpptest cpp_test(&nh);
ros::spin();
return 0;
}更改您自己的程式碼後,你還需要去配置task_supervisor,才能讓Seirios在你的程式上運行。
external_process_handler watchdog_rate: 2.0
watchdog_timeout: 0
service_req: true
# Below 4 params are COMPULSORY if service_req is true
service_start: "/external_process/trigger_detecting"
service_start_msg: "" # Optional, may put blank string
service_stop: "/external_process/stop_detecting"
service_stop_msg: "" # Optional, may put blank string
launch_req: false
# Below 3 params COMPULSORY if launch_req is true
launch_package:
launch_file:
launch_nodes:
topic_cancel_req: true
# topic_process_cancel required if topic_cancel_req is true
topic_process_cancel: "external_process/cancel_publish"
client_status: # Required if launch_req true, optional otherwise根據您啟動/停止程序的方式設置 service_req、launch_req 和 topic_cancel_req 的布爾狀態。
參數 service_start、service_stop、topic_process_cancel、client_status 必須與您在自己的文件中提供的主題和服務的名稱相匹配。
將您的程式作為插件添加到task supervisor,以便 Seirios 運行,將配置插入 task_supervisor.yaml
Filepath: ../config/task_supervisor/config/
File to modify: task_supervisor.yaml
警告:yaml 文件禁止tab鍵。 編輯 yaml 文件時,不要使用tab鍵來縮排。
在task supervisor的插件部分下,插入以下程式碼。 縮排必須與其他插件對齊。 您可以提供任何name和type,但要確保它們不會與其他插件衝突。 請不要更改class。
plugins:
- {name: detecting, type: 10, class: 'external_process_handler::ExternalProcessHandler'}在文件的末尾中,使用您在上面提供的name創建一個新部分。 請貼上該參數。
detecting:
watchdog_rate: 2.0
watchdog_timeout: 0
service_req: true
launch_req: false
service_start: "/external_process/trigger_detecting" #required if service_req is true
service_start_msg: "" #optional if there is any particular msg needs to sent or else empty string
service_stop: "/external_process/stop_detecting" #required if service_req is true
service_start_msg: "" #optional if there is any particular msg needs to sent or else empty string
#launch_package: "yocs_velocity_smoother" #required if launch_req is true
#launch_file: "standalone.launch" #required if launch_req is true
#launch_nodes: "/nodelet_manager /velocity_smoother" #required if launch_req is true
topic_cancel_req: true
topic_process_cancel: "external_process/cancel_publish"對於 C++ 程式,請記住在您自己的程式包中,要正確設置 CMakeLists.txt 和 package.xml。
欲了解更多信息,請點擊此處。 click here.
Timed Elastic Band (TEB)根據執行時間、與障礙物的距離、和運動學約束,來執行優化機器人的軌跡。
teb_local_planner 改善導航功能此指引是給那些選擇使用 teb_local_planner 的人,導航您的機器人。更多資訊,請點擊 click here.
Filepath: catkin_ws/movel_ai/config/movel/config/
File to modify: base_local_planner_params.yaml
請注意,local planner的配置文件位於 movel 安裝包中。在 yaml 文件本身中,裡面包含 3 個local planner,但我們只會使用其中一個。 取消註釋 TebLocalPlannerROS 下的整個部分。
這些是可以配置的參數,以下將解釋如何調整這些參數。
TebLocalPlannerROS:
odom_topic: /odom
#odom_topic: /rtabmap/odom
map_frame: map
# Trajectory
teb_autosize: True
dt_ref: 0.3 #0.2
dt_hysteresis: 0.1
global_plan_overwrite_orientation: True
max_global_plan_lookahead_dist: 3.0
feasibility_check_no_poses: 5
# Robot
max_vel_x: 0.40 #0.25
max_vel_x_backwards: 0.4 #0.2
max_vel_theta: 1.0 #0.5
acc_lim_x: 0.5 # 0.2
acc_lim_theta: 0.6283 #0.5, 0.26
min_turning_radius: 0.0
footprint_model: # types: "point", "circular", "two_circles", "line", "polygon"
type: "polygon" #"circular"
radius: 0.38 # for type "circular"
#line_start: [-0.3, 0.0] # for type "line"
#line_end: [0.3, 0.0] # for type "line"
#front_offset: 0.2 # for type "two_circles"
#front_radius: 0.2 # for type "two_circles"
#rear_offset: 0.2 # for type "two_circles"
#rear_radius: 0.2 # for type "two_circles"
vertices: [ [0.26, 0.26], [0.26, -0.26], [-0.26, -0.26], [-0.26,0.26] ] # for type "polygon"
# GoalTolerance
xy_goal_tolerance: 0.2 #0.2
yaw_goal_tolerance: 0.1571
free_goal_vel: False
# Obstacles
min_obstacle_dist: 0.05
inflation_dist: 0.0
dynamic_obstacle_inflation_dist: 0.05
include_costmap_obstacles: True
costmap_obstacles_behind_robot_dist: 0.1
obstacle_poses_affected: 25 #30
costmap_converter_plugin: ""
costmap_converter_spin_thread: True
costmap_converter_rate: 5
# Optimization
no_inner_iterations: 5 #5
no_outer_iterations: 4 #4
optimization_activate: True
optimization_verbose: False
penalty_epsilon: 0.1
weight_max_vel_x: 2 #2
weight_max_vel_theta: 1 #1
weight_acc_lim_x: 1 # 1
weight_acc_lim_theta: 1 # 1
weight_kinematics_nh: 1000 #1000
weight_kinematics_forward_drive: 1000 #1000
weight_kinematics_turning_radius: 1 #1 #only for car-like robots
weight_optimaltime: 1.0 #1
weight_obstacle: 50 #50
weight_viapoint: 5.0 #5.0 #1.0
weight_inflation: 0.1 #0.1
weight_dynamic_obstacle: 10 # not in use yet
selection_alternative_time_cost: False # not in use yet
# Homotopy Class Planner
enable_homotopy_class_planning: False #True
enable_multithreading: True
simple_exploration: False
max_number_classes: 2 #4
roadmap_graph_no_samples: 15
roadmap_graph_area_width: 5
h_signature_prescaler: 0.5
h_signature_threshold: 0.1
obstacle_keypoint_offset: 0.1
obstacle_heading_threshold: 0.45
visualize_hc_graph: False
#ViaPoints
global_plan_viapoint_sep: 0.5 #negative if none
via_points_ordered: False #adhere to order of via points
#Feedback
publish_feedback: true #false警告:yaml禁止tab鍵。 編輯 yaml 文件時不要使用tab鍵來縮排。 此外,檢查縮排是否正確對齊。
使用TEB Planner去配置Seirios後,需要同步TEB Planner指定的最大速度。
Filepath: catkin_ws/movel_ai/config/velocity_setter/config/
File to modify: velocity_setter.yaml
local_planner: "TebLocalPlannerROS"
parameter_name_linear: "max_vel_x"
parameter_name_angular: "max_vel_theta"檢查local_planner在base local planner的配置中,是否匹配planner的名稱。 您將配置在TEB Planner中指定的最大速度。
rviz:使用 2D Pose Estimator 工具,在地圖上精確定位機器人的位置。 您可以使用 LaserScan 來幫助您 - 將尺寸 (m) 增加到至少 0.05,並嘗試將 LaserScan 中的線條與地圖盡可能匹配。
Seirios:請至導航定位此功能,使用鍵盤或操縱桿按鈕,將激光的線條與地圖盡可能地對齊。
Filepath: catkin_ws/movel_ai/config/movel/config/amcl.yaml
File to modify: amcl.yaml
Amcl 配置文件與 base_local_planner_params.yaml 位於同一目錄中。
同樣地,Amcl 文件中有很多參數,儘管我們只需要這兩個參數:
min_particles: 50
max_particles: 1000配置min_particles 和 max_particles 來調整精確度。
teb_local_planner 參數本節提供,關於 TebLocalPlannerROS 的參數列表中數值的建議。 返回到相同的 base_local_planner_params.yaml 文件。
可調整的參數,可以分為以下幾類:
Robot機器人
Goal Tolerance目標容錯
Trajectory機器人軌道
Obstacles障礙物
Optimisation機器人優化
請根據製造商指定的配置,調整機器人相關參數。 即為速度和加速度設置的值,不應超過機器人的硬體限制。
運動學Kinematics
vel 參數限制了機器人的移動速度, acc 參數限制機器人可以加速的速度, _x 指定線性運動學,而 _theta 指定角度運動學。
max_vel_x: 0.40 #0.25
max_vel_x_backwards: 0.4 #0.2
max_vel_theta: 1.0 #0.5
acc_lim_x: 0.5 # 0.2
acc_lim_theta: 0.6283 #0.5, 0.26足跡模型Footprint Model
從字面上看,就是指腳印,理想情況下,將佔地面積配置為略大於機器人的實際測量值, 應該根據機器人的測量來配置footprint_model。
footprint_model: # types: "point", "circular", "two_circles", "line", "polygon"
type: "polygon" #"circular"
radius: 0.38 # for type "circular"
#line_start: [-0.3, 0.0] # for type "line"
#line_end: [0.3, 0.0] # for type "line"
#front_offset: 0.2 # for type "two_circles"
#front_radius: 0.2 # for type "two_circles"
#rear_offset: 0.2 # for type "two_circles"
#rear_radius: 0.2 # for type "two_circles"
vertices: [ [0.26, 0.26], [0.26, -0.26], [-0.26, -0.26], [-0.26,0.26] ] # for type "polygon"您必須指名機器人足跡的類型type。 不同的類型包括多邊形polygon、圓形circular、two_circles、線line、點point等。為簡單起見,足跡通常是圓形或多邊形。更多資訊,請點擊此連結 Click here。
半徑radius 需要輸入此類型 type: "circular"
頂點vertices 需要輸入此類型 type: "polygon"
目標容錯Goal Tolerance可指定您願意容忍的偏離目標點的程度。
xy_goal_tolerance: 0.2 #0.2
yaw_goal_tolerance: 0.1571xy_goal_tolerance 是距離目標可接受的直線距離,以meter為單位。
yaw_goal_tolerance 是機器人方向的偏差。 例如:目標指定機器人應直接面向牆壁,但實際上,機器人稍微面向左側。
指的是決定機器人在障礙物前應如何表現。
需要進行實驗來調整planner以最適合地方式接近障礙物。 風險高的配置將允許機器人,在障礙重重的路徑中移動,例如:在狹窄的走廊,但它可能會卡在障礙物周圍或撞到障礙物;更保守的配置可能會導致機器人排除其唯一可用的路徑,因為它認為它離障礙物太近了。
最棘手的部分是,要如何在這兩種情況之間取得平衡。
min_obstacle_dist: 0.05 inflation_dist: 0.0
dynamic_obstacle_inflation_dist: 0.05
include_costmap_obstacles: True
costmap_obstacles_behind_robot_dist: 0.1
obstacle_poses_affected: 25 #30
costmap_converter_plugin: ""
costmap_converter_spin_thread: True
costmap_converter_rate: 5min_obstacle_dist 是您希望與障礙物保持的最小距離。
inflation_dist 是在障礙物周圍添加的緩衝區。
有關避障與罰則,請點擊此連結Click here 。
其他避障參數調整的相關問題,請點擊此連結click here。
除了在local planner,配置障礙物行為處理外,我們還可以配置代價圖。
代價地圖會告訴機器人,機器人移動到特定點需要多少成本。 成本越高,機器人越不應該去那裡。致命的障礙物可能損壞機器人,將會付出超高的成本。
Filepath: catkin_ws/movel_ai/config/movel/config/
File to modify: costmap_common_params.yaml
文件在同一目錄中base_local_planner_params。
footprint: [ [0.26, 0.26], [0.26, -0.26], [-0.26, -0.26], [-0.26,0.26] ]
# robot_radius: 0.38 #0.38
# footprint_padding: 0.05
map_type: voxel
#track_unknown_space: true
obstacle_layer:
origin_z: -0.1
z_resolution: 1.8 #1.5 This must be higher than the z coordinate of the mounted lidar
z_voxels: 1
obstacle_range: 10.0 #10.0
raytrace_range: 15.0 #15.0
observation_sources: laser_scan_sensor
track_unknown_space: true
lethal_cost_threshold: 100
unknown_cost_value: 255
laser_scan_sensor: {data_type: LaserScan, topic: /scan, marking: true, clearing: true, min_obstacle_height: 0.00, max_obstacle_height: 3.00}
#point_cloud_sensor: {sensor_frame: lslidar_c16_frame, data_type: PointCloud2, topic: /lslidar_c16/lslidar_point_cloud, marking: true, clearing: true}
lowbstacle_layer:
origin_z: -0.1
z_resolution: 1.8
z_voxels: 1
obstacle_range: 3.5 #if beyond this threshold, then will not mark as obstacle
raytrace_range: 5.0 #5.0 Lower this value to detect nearer obstacles with better accuracy
observation_sources: obs_cloud mock_scan #butt_scan1 butt_scan2
publish_voxel_map: true
track_unknown_space: true
lethal_cost_threshold: 100
unknown_cost_value: 255
obs_cloud:
data_type: PointCloud2
topic: /obstacles_cloud
marking: true
clearing: true
min_obstacle_height: 0.01
max_obstacle_height: 0.99
mock_scan:
data_type: LaserScan
topic: /obstacles_scan
marking: false
clearing: true
min_obstacle_height: 0.00
max_obstacle_height: 1.00
inf_is_valid: true
inflation_layer:
enabled: true
cost_scaling_factor: 6.0 #added in by John
inflation_radius: 0.39 #0.45 #Minimum value: 0.379
dynamic_obstacle_layer:
enabled: false
map_tolerance: 0.2
footprint_radius: 0.5
range: 2.0代價圖中添加了幾個圖層,通常我們遵循這裡的規範 here。
footprint必須與base_local_planner_params.yaml中指定的測量相匹配。
你可以選擇將common_costmap_params 中的部分或全部圖層添加到global_costmap_params 和local_costmap_params。
對於您決定使用的代價地圖圖層,您必須將這些圖層作為插件安裝到 global_costmap_params.yaml 和 local_costmap_params.yaml 中。更多有關global和local的代價地圖差異資訊,請點擊該連結 Click here。
plugins:
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
- {name: lowbstacle_layer, type: "costmap_2d::VoxelLayer"}
- {name: dynamic_obstacle_layer, type: "dynamic_obstacle_layer::DynamicLayer"} # Uncomment to apply dynamic_obstacle_layer
- {name: inflation_layer, type: "costmap_2d::InflationLayer"} plugins:
- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
- {name: lowbstacle_layer, type: "costmap_2d::VoxelLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
# - {name: range_sensor_layer, type: "range_sensor_layer::RangeSensorLayer"}
這一層膨脹了致命障礙物周圍的邊緣,且可指定你想讓障礙物膨脹多少。
inflation_layer:
enabled: true
cost_scaling_factor: 6.0 #added in by John
inflation_radius: 0.39 #0.45 #Minimum value: 0.379inflation_radius 是地圖將障礙物成本值膨脹到的半徑,以meter為單位。 通常它是機器人的寬度,加上一些額外的空間。
cost_scaling_factors 是在膨脹期間,應用於代價縮放因子。
額外的正確配置資訊 (directly lifted from here)
The
inflation_radiusis actually the radius to which the cost scaling function is applied, not a parameter of the cost scaling function. Inside the inflation radius, the cost scaling function is applied, but outside the inflation radius, the cost of a cell is not inflated using the cost function.You'll have to make sure to set the inflation radius large enough that it includes the distance you need the cost function to be applied out to, as anything outside the inflation_radius will not have the cost function applied.
For the correct
cost_scaling_factor, solve the equation there ( exp(-1.0 * cost_scaling_factor * (distance_from_obstacle - inscribed_radius)) * (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1)), using your distance from obstacle and the cost value you want that cell to have.
理想情況下,我們希望設置這兩個參數,使膨脹層幾乎覆蓋走廊,機器人在障礙物之間的中心移動。
(請見下圖)
障礙層在代價地圖上標出障礙物,它會追蹤感測器數據記錄的障礙物。
obstacle_layer:
origin_z: -0.1
z_resolution: 1.8 #1.5 This must be higher than the z coordinate of the mounted lidar
z_voxels: 1
obstacle_range: 10.0 #10.0
raytrace_range: 15.0 #15.0
observation_sources: laser_scan_sensor
track_unknown_space: true
lethal_cost_threshold: 100
unknown_cost_value: 255
laser_scan_sensor: {data_type: LaserScan, topic: /scan, marking: true, clearing: true, min_obstacle_height: 0.00, max_obstacle_height: 3.00}
#point_cloud_sensor: {sensor_frame: lslidar_c16_frame, data_type: PointCloud2, topic: /lslidar_c16/lslidar_point_cloud, marking: true, clearing: true}若要建置2D地圖,一定要選擇laser_scan_sensor。
obstacle_range是將障礙物插入代價圖後,與機器人的最大距離。 其數值為 10,表示代價地圖將標出距離機器人10 米以內的障礙物。
raytrace_range是光線追蹤障礙物的範圍(以meter為單位),此數值必須根據您的感測器做設置。
max_obstacle_height 是添加到代價地圖的障礙物的最大高度。若此障礙物非常高,請增加此數值,並根據你的感測器去做設置。
體素層參數Voxel layer parameters
體素是在空間中具有相對位置的 3D 立方體,可用於深度相機的 3D 重建,如果您不使用 3D,請忽略以下參數。更多相關訊息,請點擊連結 here
origin_z 是地圖的 z 原點(米)。
z_resolution是立方體的高度。
z_resolutioncontrols how dense the voxels is on the z-axis. If it is higher, the voxel layers are denser. If the value is too low (e.g. 0.01), you won’t get useful costmap information. If you set z resolution to a higher value, your intention should be to obtain obstacles better, therefore you need to increasez_voxelsparameter which controls how many voxels in each vertical column. It is also useless if you have too many voxels in a column but not enough resolution, because each vertical column has a limit in height.
z_voxels 是體素的數量。
低障礙層是障礙層,但帶有附加參數。 將您的observation_sources更改為,您要從中獲取數據的主題。
如果您想要 PointCloud (3D),請使用 obs_cloud;如果您想要 LaserScan (2D),請使用 mock_scan。 或者您可以指定自己的方法。
lowbstacle_layer:
origin_z: -0.1
z_resolution: 1.8
z_voxels: 1
obstacle_range: 3.5 #if beyond this threshold, then will not mark as obstacle
raytrace_range: 5.0 #5.0 Lower this value to detect nearer obstacles with better accuracy
observation_sources: obs_cloud mock_scan #butt_scan1 butt_scan2
publish_voxel_map: true
track_unknown_space: true
lethal_cost_threshold: 100
unknown_cost_value: 255
obs_cloud:
data_type: PointCloud2
topic: /obstacles_cloud
marking: true
clearing: true
min_obstacle_height: 0.01
max_obstacle_height: 0.99
mock_scan:
data_type: LaserScan
topic: /obstacles_scan
marking: false
clearing: true
min_obstacle_height: 0.00
max_obstacle_height: 1.00
inf_is_valid: true這裡有兩個重要參數,需要特別注意。
min_obstacle_height 是機器人底座下方障礙物的高度。 像是包括樓梯,調整此參數,以便機器人可以檢測到下方的障礙物,並防止其掉入坑中..
max_obstacle_height 是障礙物的最大高度,通常指的是機器人的高度。
參數調整時,一定會需要有實驗的過程,在這過程中一定會有些問題,所以建議您在修改 yaml 文件之前先在控制台中測試您的值。
rosrun rqt_reconfigure rqt_reconfigure
問題#1: 讓機器人去狹窄路徑的另一邊的問題。
從觀察中可以看出,機器人將返回目標失敗,或者機器人會將自己靠近牆壁並卡在那裡。
問題 #2: 讓機器人旋轉90度的問題。
The planner不知為何無視牆壁的存在,並指示機器人穿越過它,而不是繞過牆壁迴轉 90 度。 儘管似乎大多數機器人都足夠聰明,可以識別出它們無法穿過牆壁,並且執行中止目標,或是嘗試中陷入困境。
解決方案 #1: 降低速度和加速度。 直覺是,通過減慢機器人的運動和旋轉速度,The planner可能有更多時間對障礙物做出反應並做出相應的計劃。
解決方案 #2: (對於那些拒絕去走廊另一邊的機器人。)
縮小兩個代價地圖中的inflation_radius,使其不覆蓋走廊。(如右圖)觀察注意到,如果半徑覆蓋整個走廊,機器人可能會拒絕移動。
如需更多資訊有關Planners和Tuning Planners,請詳閱以下為外部資源。
ROS Wiki


















