Skip to content

Commit

Permalink
Merge pull request #57 from ut-amrl/intermediate_planner
Browse files Browse the repository at this point in the history
Intermediate planner (Most update to date planner)
  • Loading branch information
sadanand1120 authored Oct 10, 2024
2 parents 90a769a + 8d35e6b commit 1c294bb
Show file tree
Hide file tree
Showing 6 changed files with 1,669 additions and 973 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ SET(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
SET(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)

SET(libs roslib roscpp rosbag glog gflags amrl_shared_lib boost_system lua5.1
pthread)
pthread costmap_2d)

ADD_LIBRARY(shared_library
src/visualization/visualization.cc
Expand Down
24 changes: 21 additions & 3 deletions config/navigation.lua
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,12 @@ end

NavigationParameters = {
laser_topics = {
"/velodyne_2dscan",
"/scan",
-- "/velodyne_2dscan",
"/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 All @@ -20,7 +21,7 @@ NavigationParameters = {
max_angular_accel = 0.5;
max_angular_decel = 0.5;
max_angular_speed = 1.0;
carrot_dist = 10;
carrot_dist = 1.5;
system_latency = 0.24;
obstacle_margin = 0.15;
num_options = 31;
Expand All @@ -39,6 +40,23 @@ NavigationParameters = {
camera_calibration_path = "config/camera_calibration_kinect.yaml";
model_path = "../preference_learning_models/jit_cost_model_outdoor_6dim.pt";
evaluator_type = "linear";
intermediate_goal_dist = 10;
max_inflation_radius = 1;
min_inflation_radius = 0.3;
local_costmap_resolution = 0.05;
local_costmap_size = 20;
global_costmap_resolution = 0.1;
global_costmap_size_x = 100;
global_costmap_size_y = 100;
global_costmap_origin_x = -10;
global_costmap_origin_y = 0;
lidar_range_min = 0.1;
lidar_range_max = 10.0;
replan_dist = 2;
object_lifespan = 15;
inflation_coeff = 8;
distance_weight = 3;
recovery_carrot_dist = 0.7;
};

AckermannSampler = {
Expand Down
Loading

0 comments on commit 1c294bb

Please sign in to comment.