Skip to content

Commit

Permalink
commit config/cobot.lua; modify navigation_main
Browse files Browse the repository at this point in the history
  • Loading branch information
chengchunhsu committed Oct 21, 2024
1 parent e54b078 commit ce6b38f
Show file tree
Hide file tree
Showing 3 changed files with 51 additions and 4 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ MESSAGE(STATUS "Using compiler: ${CMAKE_CXX_COMPILER}")
MESSAGE(STATUS "Build Type: ${CMAKE_BUILD_TYPE}")
MESSAGE(STATUS "Arch: ${CMAKE_SYSTEM_PROCESSOR}")

SET(CMAKE_CXX_FLAGS "-std=c++14 -Wall -Werror")
SET(CMAKE_CXX_FLAGS "-std=c++17 -Wall -Werror")
SET(LIBRARY_NAME "graph_nav_lib"
CACHE STRING "Name of compiled library")

Expand Down
47 changes: 47 additions & 0 deletions config/cobot.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
function deg2rad(deg)
return deg * (math.pi / 180)
end

NavigationParameters = {
laser_topic = "/Cobot/Laser";
odom_topic = "/odom";
localization_topic = "/localization";
image_topic = "/camera/rgb/image_raw/compressed";
init_topic = "/initialpose";
enable_topic = "autonomy_arbiter/enabled";
laser_loc = {
x = 0.065;
y = 0;
};
dt = 0.025;
max_linear_accel = 0.5;
max_linear_decel = 0.5;
max_linear_speed = 0.5;
max_angular_accel = 0.5;
max_angular_decel = 0.5;
max_angular_speed = 1.0;
carrot_dist = 100; --10;
system_latency = 1.0; --0.24;
obstacle_margin = 0.15;
num_options = 31;
robot_width = 0.6; --0.44;
robot_length = 0.6; --0.5;
base_link_offset = 0;
max_free_path_length = 100.0; --6.0;
max_clearance = 1.0;
can_traverse_stairs = false;
use_map_speed = true;
target_dist_tolerance = 0.1;
target_vel_tolerance = 0.1;
target_angle_tolerance = 0.008; --0.01;
local_fov = deg2rad(15);
use_kinect = true;
camera_calibration_path = "/home/cchsu/cobot-moma/graph_navigation/config/camera_calibration_kinect.yaml";
model_path = "../preference_learning_models/jit_cost_model_outdoor_6dim.pt";
evaluator_type = "linear";
};

AckermannSampler = {
max_curvature = 20; --2.5;
clearance_path_clip_fraction = 0.8;
};
6 changes: 3 additions & 3 deletions src/navigation/navigation_main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -112,15 +112,15 @@ CONFIG_STRING(enable_topic, "NavigationParameters.enable_topic");
CONFIG_FLOAT(laser_loc_x, "NavigationParameters.laser_loc.x");
CONFIG_FLOAT(laser_loc_y, "NavigationParameters.laser_loc.y");

DEFINE_string(map, "UT_Campus", "Name of navigation map file");
DEFINE_string(twist_drive_topic, "navigation/cmd_vel", "Drive Command Topic");
DEFINE_string(map, "AHG2v2", "Name of navigation map file");
DEFINE_string(twist_drive_topic, "/navigation/cmd_vel", "Drive Command Topic");
DEFINE_bool(debug_images, false, "Show debug images");

// DECLARE_int32(v);

bool run_ = true;
bool simulate_ = false;
bool enabled_ = false;
bool enabled_ = true;
bool received_odom_ = false;
bool received_laser_ = false;
Vector2f goal_ = {0, 0};
Expand Down

0 comments on commit ce6b38f

Please sign in to comment.