fix fake
This commit is contained in:
parent
37554e7dd7
commit
7891a9e12b
@ -51,7 +51,7 @@ bt_navigator:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
global_frame: map
|
||||
robot_base_frame: base_link_fake
|
||||
robot_base_frame: base_link
|
||||
odom_topic: /Odometry
|
||||
bt_loop_duration: 10
|
||||
default_server_timeout: 20
|
||||
@ -259,7 +259,7 @@ local_costmap:
|
||||
update_frequency: 20.0
|
||||
publish_frequency: 10.0
|
||||
global_frame: map
|
||||
robot_base_frame: base_link_fake
|
||||
robot_base_frame: base_link
|
||||
use_sim_time: False
|
||||
rolling_window: true
|
||||
width: 5
|
||||
@ -293,7 +293,7 @@ global_costmap:
|
||||
update_frequency: 5.0
|
||||
publish_frequency: 2.0
|
||||
global_frame: map
|
||||
robot_base_frame: base_link_fake
|
||||
robot_base_frame: base_link
|
||||
use_sim_time: False
|
||||
robot_radius: 0.2
|
||||
resolution: 0.04
|
||||
@ -383,7 +383,7 @@ recoveries_server:
|
||||
backup:
|
||||
plugin: "nav2_recoveries/BackUp"
|
||||
global_frame: odom
|
||||
robot_base_frame: base_link_fake
|
||||
robot_base_frame: base_link
|
||||
transform_timeout: 0.1
|
||||
use_sim_time: False
|
||||
simulate_ahead_time: 1.0
|
||||
|
||||
Loading…
Reference in New Issue
Block a user