안녕하세요.
ROS2 foxy 환경에서 R1mini Navigation을 테스트하고 있습니다.
R1mini는 제공해주시는 Nano 이미지를 받아 write하여 사용하고 있습니다.
Firmware 버전은 2.3.1입니다.
가이드를 참고하여 ‘Navigation2 Goal’ 버튼으로 주행을 시키는 데
가이드페이지에 올려주신 동영상과 달리 멈칫멈칫하며 부자연스러운 주행을 합니다.
(올려주신 동영상의 환경과 유사한 사무실 내에서 주행을 시도하였습니다.)
Path 재설정 혹은 회피 동작 같은 것을 하며 바퀴가 "급정지 후, 주행"동작을 반복하는 것으로 추정되는데
동영상과 같이 자연스러운 주행을 하기 위해 파라미터를 변경하거나 추가로 작업해야 되는 내용이 있는지 문의드립니다.
Kyu
2월 14, 2022, 11:11오후
#2
SLAM 성능은 환경의 영향을 많이 받습니다.
주변에 특징적인 사물이 많이 있는게 좋고 단조롭거나 일정한 패턴이 있는 환경에서는 위치 추정을 잘 못하는 경향이 있습니다.
혹시 주변 환경이 어떠한지 사진이나 캡쳐한 영상을 올려주시면 좀더 도움이 될꺼 같네요.
감사합니다.
간단히 환경 설명드리면 주변에 옷걸이스탠드, 기둥, 책상, 의자, 바닥에 위치한 모니터 등 특징적인 사물은 어느 정도 존재하고, 주행공간의 폭은 0.8~1.3m 정도로 너무 넓지도 좁지도 않은 것으로 보입니다.
죄송하지만, 주변 환경 사진이나 영상 제공은 어렵고, SLAM으로 생성한 map 이미지로 대신 전달해드려도 될까요?
파일은 사정상 게시판 업로드가 불가하여 수신 가능하신 메일 주소 알려주시면 메일로 전달해드리겠습니다.
Kyu
2월 15, 2022, 12:58오전
#4
네 kyuhyong@omorobot.com 으로 보내주시면 확인해보도록 하겠습니다.
Kyu
2월 15, 2022, 2:14오전
#5
깃허브 프로젝트에서
파라미터는 크게 변경된 부분은 없습니다.
cost_scaling_factor 값을 좀더 낮춰보시거나
transform_tolerance 값과
xy_goal_tolerance 값을 수정해보는것도 방법입니다.
amcl:
ros__parameters:
use_sim_time: False
alpha1: 0.2
alpha2: 0.2
alpha3: 0.2
alpha4: 0.2
alpha5: 0.2
base_frame_id: "base_footprint"
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3
do_beamskip: false
global_frame_id: "map"
lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_max_range: 10.0
laser_min_range: 0.12
laser_model_type: "likelihood_field"
max_beams: 60
max_particles: 2000
min_particles: 500
odom_frame_id: "odom"
pf_err: 0.05
pf_z: 0.99
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
resample_interval: 1
robot_model_type: "differential"
save_pose_rate: 0.5
sigma_hit: 0.2
tf_broadcast: true
transform_tolerance: 1.0
update_min_a: 0.2
update_min_d: 0.25
z_hit: 0.5
z_max: 0.05
z_rand: 0.5
z_short: 0.05
amcl_map_client:
ros__parameters:
use_sim_time: False
amcl_rclcpp_node:
ros__parameters:
use_sim_time: False
bt_navigator:
ros__parameters:
use_sim_time: False
global_frame: map
robot_base_frame: base_link
odom_topic: /odom
default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_back_up_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_distance_traveled_condition_bt_node
bt_navigator_rclcpp_node:
ros__parameters:
use_sim_time: False
controller_server:
ros__parameters:
use_sim_time: False
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
controller_plugins: ["FollowPath"]
# DWB parameters
FollowPath:
plugin: "dwb_core::DWBLocalPlanner"
debug_trajectory_details: True
min_vel_x: -0.20
min_vel_y: 0.0
max_vel_x: 0.20
max_vel_y: 0.0
max_vel_theta: 3.4
min_speed_xy: 0.0
max_speed_xy: 0.30
min_speed_theta: 0.0
acc_lim_x: 0.07
acc_lim_y: 0.0
acc_lim_theta: 1.0
decel_lim_x: -0.07
decel_lim_y: 0.0
decel_lim_theta: -1.0
vx_samples: 20
vy_samples: 5
vtheta_samples: 20
sim_time: 1.7
linear_granularity: 0.05
angular_granularity: 0.025
transform_tolerance: 0.1 #0.2
xy_goal_tolerance: 0.05 #0.25
trans_stopped_velocity: 0.25
short_circuit_trajectory_evaluation: True
stateful: True
critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
BaseObstacle.scale: 0.02
PathAlign.scale: 32.0
PathAlign.forward_point_distance: 0.1
GoalAlign.scale: 24.0
GoalAlign.forward_point_distance: 0.1
PathDist.scale: 32.0
GoalDist.scale: 24.0
RotateToGoal.scale: 32.0
RotateToGoal.slowing_factor: 5.0
RotateToGoal.lookahead_time: -1.0
controller_server_rclcpp_node:
ros__parameters:
use_sim_time: False
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 5.0
publish_frequency: 2.0
global_frame: odom
robot_base_frame: base_link
use_sim_time: False
rolling_window: true
width: 3
height: 3
resolution: 0.05
robot_radius: 0.150
plugins: ["obstacle_layer", "voxel_layer", "inflation_layer"]
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
mark_threshold: 0
observation_sources: pointcloud
pointcloud:
topic: /intel_realsense_r200_depth/points
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "PointCloud2"
static_layer:
map_subscribe_transient_local: True
always_send_full_costmap: True
local_costmap_client:
ros__parameters:
use_sim_time: False
local_costmap_rclcpp_node:
ros__parameters:
use_sim_time: False
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
global_frame: map
robot_base_frame: base_link
use_sim_time: False
robot_radius: 0.150
resolution: 0.05
plugins: ["static_layer", "obstacle_layer", "voxel_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
mark_threshold: 0
observation_sources: pointcloud
pointcloud:
topic: /intel_realsense_r200_depth/points
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "PointCloud2"
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
always_send_full_costmap: True
global_costmap_client:
ros__parameters:
use_sim_time: False
global_costmap_rclcpp_node:
ros__parameters:
use_sim_time: False
map_server:
ros__parameters:
use_sim_time: False
yaml_filename: "maps.yaml"
map_saver:
ros__parameters:
use_sim_time: False
save_map_timeout: 5000
free_thresh_default: 0.25
occupied_thresh_default: 0.65
planner_server:
ros__parameters:
expected_planner_frequency: 20.0
use_sim_time: False
planner_plugins: ["GridBased"]
GridBased:
plugin: "nav2_navfn_planner/NavfnPlanner"
tolerance: 0.5
use_astar: false
allow_unknown: true
planner_server_rclcpp_node:
ros__parameters:
use_sim_time: False
recoveries_server:
ros__parameters:
costmap_topic: local_costmap/costmap_raw
footprint_topic: local_costmap/published_footprint
cycle_frequency: 10.0
recovery_plugins: ["spin", "backup", "wait"]
spin:
plugin: "nav2_recoveries/Spin"
backup:
plugin: "nav2_recoveries/BackUp"
wait:
plugin: "nav2_recoveries/Wait"
global_frame: odom
robot_base_frame: base_link
transform_timeout: 0.1
use_sim_time: False
simulate_ahead_time: 2.0
max_rotational_vel: 1.0
min_rotational_vel: 0.4
rotational_acc_lim: 1.0 #3.2
robot_state_publisher:
ros__parameters:
use_sim_time: False
감사합니다.
여러가지 테스트해보던 중, 문제가 해결되어 답변드립니다.
Remote PC의 nav2_bringup 패키지의 문제였던 것 같습니다.
Remote PC에서 navigation2, nav2-bringup 패키지를 업그레이드하고 멈칫하는 현상이 없어지는 것을 확인하였습니다. 감사합니다.
1개의 좋아요