From ce6b38fe7618e7893fdda2c49780bf24c87a7c45 Mon Sep 17 00:00:00 2001 From: Cheng-Chun Hsu Date: Mon, 21 Oct 2024 12:34:17 -0500 Subject: [PATCH] commit config/cobot.lua; modify navigation_main --- CMakeLists.txt | 2 +- config/cobot.lua | 47 +++++++++++++++++++++++++++++++ src/navigation/navigation_main.cc | 6 ++-- 3 files changed, 51 insertions(+), 4 deletions(-) create mode 100644 config/cobot.lua diff --git a/CMakeLists.txt b/CMakeLists.txt index bacb688..235fa1a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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") diff --git a/config/cobot.lua b/config/cobot.lua new file mode 100644 index 0000000..47fbe71 --- /dev/null +++ b/config/cobot.lua @@ -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; +}; diff --git a/src/navigation/navigation_main.cc b/src/navigation/navigation_main.cc index 95ed9a3..d724d75 100644 --- a/src/navigation/navigation_main.cc +++ b/src/navigation/navigation_main.cc @@ -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};