Hiep update

This commit is contained in:
HiepLM 2025-12-30 10:20:42 +07:00
parent 9c84e64253
commit b5a1b7b6d8
5 changed files with 15 additions and 15 deletions

View File

@ -47,10 +47,10 @@ target_link_libraries(dock_planner
robot_visualization_msgs
robot_nav_msgs
tf3
tf3_geometry_msgs
robot_tf3_geometry_msgs
robot_time
data_convert
costmap_2d
robot_costmap_2d
nav_core
robot_cpp
robot_nav_2d_utils
@ -73,8 +73,8 @@ install(TARGETS dock_planner
INCLUDES DESTINATION include # Cài đt include
)
# --- Xut export set costmap_2dTargets thành file CMake module ---
# --- To file lib/cmake/dock_planner/costmap_2dTargets.cmake ---
# --- Xut export set robot_costmap_2dTargets thành file CMake module ---
# --- To file lib/cmake/dock_planner/robot_costmap_2dTargets.cmake ---
# --- File này cha cu hình giúp project khác có th dùng ---
# --- Find_package(dock_planner REQUIRED) ---
# --- Target_link_libraries(my_app PRIVATE dock_planner::dock_planner) ---

View File

@ -8,9 +8,9 @@
#include <robot_nav_msgs/OccupancyGrid.h>
#include <robot_nav_msgs/GetPlan.h>
#include <costmap_2d/costmap_2d_robot.h>
#include <costmap_2d/costmap_2d.h>
#include <costmap_2d/inflation_layer.h>
#include <robot_costmap_2d/costmap_2d_robot.h>
#include <robot_costmap_2d/costmap_2d.h>
#include <robot_costmap_2d/inflation_layer.h>
#include <tf3/LinearMath/Quaternion.h>
@ -120,7 +120,7 @@ namespace dock_planner
public:
//Params
costmap_2d::Costmap2D* costmap_;
robot_costmap_2d::Costmap2D* costmap_;
int cost_threshold_; // Threshold for obstacle detection
double safety_distance_; // Safety distance from obstacles

View File

@ -11,9 +11,9 @@ namespace dock_planner {
{
public:
DockPlanner();
DockPlanner(std::string name, costmap_2d::Costmap2DROBOT* costmap_robot);
DockPlanner(std::string name, robot_costmap_2d::Costmap2DROBOT* costmap_robot);
bool initialize(std::string name, costmap_2d::Costmap2DROBOT* costmap_robot);
bool initialize(std::string name, robot_costmap_2d::Costmap2DROBOT* costmap_robot);
bool makePlan(const robot_geometry_msgs::PoseStamped& start,
const robot_geometry_msgs::PoseStamped& goal,
@ -21,8 +21,8 @@ namespace dock_planner {
private:
// Core components
costmap_2d::Costmap2DROBOT* costmap_robot_;
costmap_2d::Costmap2D* costmap_;
robot_costmap_2d::Costmap2DROBOT* costmap_robot_;
robot_costmap_2d::Costmap2D* costmap_;
bool initialized_;
std::string frame_id_;
// ros::Publisher plan_pub_;

View File

@ -728,7 +728,7 @@ namespace dock_planner
// check_y >= 0 && check_y < costmap_->getSizeInCellsY())
// {
// unsigned char cost = costmap_->getCost(check_x, check_y);
// if (cost >= costmap_2d::LETHAL_OBSTACLE)
// if (cost >= robot_costmap_2d::LETHAL_OBSTACLE)
// {
// double dx = pose.position.x - space_footprint[i].x;
// double dy = pose.position.y - space_footprint[i].y;

View File

@ -21,7 +21,7 @@ namespace dock_planner
* @param costmap_robot Pointer tới costmap ROS wrapper
* Tự đng gọi initialize() nếu đưc cung cấp costmap
*/
DockPlanner::DockPlanner(std::string name, costmap_2d::Costmap2DROBOT* costmap_robot)
DockPlanner::DockPlanner(std::string name, robot_costmap_2d::Costmap2DROBOT* costmap_robot)
: costmap_robot_(nullptr),
costmap_(nullptr),
initialized_(false),
@ -43,7 +43,7 @@ namespace dock_planner
* - Load parameters từ ROS parameter server
* - Đánh dấu trạng thái initialized
*/
bool DockPlanner::initialize(std::string name, costmap_2d::Costmap2DROBOT* costmap_robot)
bool DockPlanner::initialize(std::string name, robot_costmap_2d::Costmap2DROBOT* costmap_robot)
{
if (!initialized_)
{