Skip to content

Commit

Permalink
working intermediate planner and costmap in sim
Browse files Browse the repository at this point in the history
  • Loading branch information
alexcliu committed Apr 1, 2024
1 parent c4c5483 commit f309f25
Show file tree
Hide file tree
Showing 5 changed files with 453 additions and 148 deletions.
13 changes: 11 additions & 2 deletions config/navigation.lua
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,11 @@ end

NavigationParameters = {
laser_topics = {
"/velodyne_2dscan",
"/scan",
"/kinect_laserscan",
};
laser_frame = "base_link";
odom_topic = "/jackal_velocity_controller/odom";
odom_topic = "/odom";
localization_topic = "localization";
image_topic = "/camera/rgb/image_raw/compressed";
init_topic = "initialpose";
Expand Down Expand Up @@ -39,6 +39,15 @@ NavigationParameters = {
camera_calibration_path = "config/camera_calibration_kinect.yaml";
model_path = "../preference_learning_models/jit_cost_model_outdoor_6dim.pt";
evaluator_type = "linear";
intermediate_carrot_dist = 2;
local_costmap_inflation_size = 0.4;
local_costmap_resolution = 0.1;
local_costmap_radius = 10;
global_costmap_inflation_size = 0.4;
global_costmap_resolution = 0.2;
global_costmap_radius = 100;
range_min = 0.1;
range_max = 10.0;
};

AckermannSampler = {
Expand Down
Loading

0 comments on commit f309f25

Please sign in to comment.