diff --git a/.gitmodules b/.gitmodules index dbfc26f..3168e0f 100644 --- a/.gitmodules +++ b/.gitmodules @@ -28,3 +28,6 @@ [submodule "src/Libraries/xmlrpcpp"] path = src/Libraries/xmlrpcpp url = https://git.pnkr.asia/DuongTD/xmlrpcpp.git +[submodule "src/Libraries/laser_filter"] + path = src/Libraries/laser_filter + url = https://git.pnkr.asia/DuongTD/laser_filter.git diff --git a/CMakeLists.txt b/CMakeLists.txt index 2a0f509..f949b57 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -74,6 +74,10 @@ if (NOT TARGET robot_nav_2d_utils) add_subdirectory(${CMAKE_SOURCE_DIR}/src/Libraries/robot_nav_2d_utils) endif() +if (NOT TARGET laser_filter) + add_subdirectory(${CMAKE_SOURCE_DIR}/src/Libraries/laser_filter) +endif() + if (NOT TARGET robot_nav_core) add_subdirectory(${CMAKE_SOURCE_DIR}/src/Navigations/Cores/robot_nav_core) endif() diff --git a/config/pnkx_local_planner_params.yaml b/config/pnkx_local_planner_params.yaml index 4783027..cf46a84 100644 --- a/config/pnkx_local_planner_params.yaml +++ b/config/pnkx_local_planner_params.yaml @@ -41,8 +41,8 @@ PNKXRotateLocalPlanner: LimitedAccelGenerator: library_path: libmkt_plugins_standard_traj_generator - max_vel_x: 0.2 - min_vel_x: -0.2 + max_vel_x: 1.0 + min_vel_x: -1.0 max_vel_y: 0.0 # diff drive robot min_vel_y: 0.0 # diff drive robot @@ -50,7 +50,7 @@ LimitedAccelGenerator: max_speed_xy: 2.0 # max_trans_vel: 0.8 # choose slightly less than the base's capability min_speed_xy: 0.25 # min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity - max_vel_theta: 0.7 # max_rot_vel: 1.0 # choose slightly less than the base's capability + max_vel_theta: 0.4 # max_rot_vel: 1.0 # choose slightly less than the base's capability min_vel_theta: 0.05 # min_rot_vel: 0.1 default: 0.4 # this is the min angular velocity when there is negligible translational velocity acc_lim_x: 1.5 diff --git a/src/Libraries/laser_filter b/src/Libraries/laser_filter new file mode 160000 index 0000000..db25b6b --- /dev/null +++ b/src/Libraries/laser_filter @@ -0,0 +1 @@ +Subproject commit db25b6bb2845d7389d86824b5221ade1c6538bb3 diff --git a/src/Navigations/Packages/move_base/CMakeLists.txt b/src/Navigations/Packages/move_base/CMakeLists.txt index ae8564e..f1af110 100644 --- a/src/Navigations/Packages/move_base/CMakeLists.txt +++ b/src/Navigations/Packages/move_base/CMakeLists.txt @@ -45,6 +45,7 @@ if (NOT BUILDING_WITH_CATKIN) robot_nav_2d_utils robot_cpp robot_move_base_msgs + laser_filter ) find_library(TF3_LIBRARY NAMES tf3 PATHS /usr/lib /usr/local/lib /usr/lib/x86_64-linux-gnu) else() diff --git a/src/Navigations/Packages/move_base/src/move_base.cpp b/src/Navigations/Packages/move_base/src/move_base.cpp index 0b22f55..aef61aa 100644 --- a/src/Navigations/Packages/move_base/src/move_base.cpp +++ b/src/Navigations/Packages/move_base/src/move_base.cpp @@ -31,6 +31,7 @@ #include #include #include +#include move_base::MoveBase::MoveBase() : initialized_(false), @@ -499,13 +500,17 @@ robot_nav_msgs::OccupancyGrid move_base::MoveBase::getStaticMap(const std::strin void move_base::MoveBase::addLaserScan(const std::string &laser_scan_name, robot_sensor_msgs::LaserScan laser_scan) { auto it = laser_scans_.find(laser_scan_name); + laser_filter::LaserScanSOR sor; + sor.setMeanK(10); // xét 10 điểm láng giềng gần nhất + sor.setStddevMulThresh(1.0); // ngưỡng = mean + 1.0 * stddev + robot_sensor_msgs::LaserScan laser_scan_filter = sor.filter(laser_scan); if (it == laser_scans_.end()) { - laser_scans_[laser_scan_name] = laser_scan; + laser_scans_[laser_scan_name] = laser_scan_filter; } else { - it->second = laser_scan; + it->second = laser_scan_filter; } // robot::log_info("stamp: %ld.%ld", laser_scan.header.stamp.sec, laser_scan.header.stamp.nsec); // robot::log_info("frame_id: %s", laser_scan.header.frame_id.c_str()); @@ -529,8 +534,8 @@ void move_base::MoveBase::addLaserScan(const std::string &laser_scan_name, robot // } // robot::log_error("intensities: %s", intensities_str.str().c_str()); - updateLocalCostmap(laser_scan, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name); - updateGlobalCostmap(laser_scan, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name); + updateLocalCostmap(laser_scan_filter, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name); + updateGlobalCostmap(laser_scan_filter, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name); } robot_sensor_msgs::LaserScan move_base::MoveBase::getLaserScan(const std::string &laser_scan_name)