Skip to content

Commit

Permalink
Updated run creste to use costmap lua config
Browse files Browse the repository at this point in the history
  • Loading branch information
artzha committed Jan 24, 2025
1 parent 54b5eb1 commit 9a9a81a
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 6 deletions.
2 changes: 1 addition & 1 deletion config/navigation_carrot.lua
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ NavigationParameters = {
model_path = "../preference_learning_models/jit_cost_model_outdoor_6dim.pt";
evaluator_type = "linear";
carrot_planner_type = "service"; -- geometric, service
intermediate_goal_tolerance = 10; -- final goal distance will be half this (meters)
intermediate_goal_tolerance = 15; -- final goal distance will be half this (meters)
max_inflation_radius = 1;
min_inflation_radius = 0.3;
local_costmap_resolution = 0.05;
Expand Down
2 changes: 1 addition & 1 deletion config/navigation_costmap.lua
Original file line number Diff line number Diff line change
Expand Up @@ -109,4 +109,4 @@ DeepCostMapEvaluatorService = {
-- visualization
viz_radius = 3;
viz_thickness = 2;
};
};
6 changes: 3 additions & 3 deletions config/navigation_creste.lua
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ OSMPlannerParameters = {

NavigationParameters = {
laser_topics = {
"/scan",
-- "/scan",
"/velodyne_2dscan_lowbeam",
-- "/kinect_laserscan",
};
Expand Down Expand Up @@ -44,13 +44,13 @@ NavigationParameters = {
target_dist_tolerance = 0.1;
target_vel_tolerance = 0.1;
target_angle_tolerance = 0.05;
local_fov = deg2rad(270);
local_fov = deg2rad(120);
use_kinect = true;
camera_calibration_path = "config/camera_calibration_left_flir.yaml";
model_path = "../preference_learning_models/jit_cost_model_outdoor_6dim.pt";
evaluator_type = "cost_map_service"; -- linear, cost_map_service
carrot_planner_type = "geometric"; -- geometric, service
intermediate_goal_tolerance = 15; -- final goal distance will be half this (meters)
intermediate_goal_tolerance = 12; -- final goal distance will be half this (meters)
max_inflation_radius = 1;
min_inflation_radius = 0.3;
local_costmap_resolution = 0.01; -- for bev homography
Expand Down
2 changes: 1 addition & 1 deletion scripts/run_creste.sh
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
#!/bin/bash
./bin/navigation --robot_config config/navigation_creste.lua -v 2
./bin/navigation --robot_config config/navigation_costmap.lua -v 2

0 comments on commit 9a9a81a

Please sign in to comment.