This commit is contained in:
HiepLM 2025-12-25 11:04:24 +07:00
parent 3c728db668
commit a9a2445305
29 changed files with 228 additions and 102 deletions

View File

@ -1,5 +1,6 @@
global_costmap: global_costmap:
path_plugins: /home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Libraries/costmap_2d/libplugins.so library_path: libplugins
robot_base_frame: base_footprint
global_frame: map global_frame: map
update_frequency: 1.0 update_frequency: 1.0
publish_frequency: 1.0 publish_frequency: 1.0

View File

@ -1,6 +1,7 @@
local_costmap: local_costmap:
path_plugins: /home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Libraries/costmap_2d/libplugins.so library_path: libplugins
global_frame: odom global_frame: odom
robot_base_frame: base_footprint
update_frequency: 6.0 update_frequency: 6.0
publish_frequency: 6.0 publish_frequency: 6.0
rolling_window: true rolling_window: true

View File

@ -1,5 +1,6 @@
base_global_planner: CustomPlanner base_global_planner: CustomPlanner
CustomPlanner: CustomPlanner:
library_path: libcustom_planner
environment_type: XYThetaLattice environment_type: XYThetaLattice
planner_type: ARAPlanner planner_type: ARAPlanner
allocated_time: 10.0 allocated_time: 10.0
@ -9,9 +10,6 @@ CustomPlanner:
nominalvel_mpersecs: 0.8 nominalvel_mpersecs: 0.8
timetoturn45degsinplace_secs: 1.31 # = 0.6 rad/s timetoturn45degsinplace_secs: 1.31 # = 0.6 rad/s
allow_unknown: true allow_unknown: true
directory_to_save_paths: "/init/paths"
pathway_filename: "pathway.txt"
current_pose_topic_name: "/amcl_pose"
map_frame_id: "map"
base_frame_id: "base_link"

View File

@ -21,4 +21,5 @@ conservative_reset:
aggressive_reset: aggressive_reset:
reset_distance: 3.0 reset_distance: 3.0
MoveBase:
library_path: libmove_base

View File

@ -1,3 +1,4 @@
base_global_planner: TwoPointsPlanner base_global_planner: TwoPointsPlanner
TwoPointsPlanner: TwoPointsPlanner:
library_path: libtwo_points_planner
lethal_obstacle: 20 lethal_obstacle: 20

View File

@ -287,7 +287,16 @@ namespace NavigationExample
return; return;
} }
if (!NavigationAPI.tf_listener_set_static_transform(tfHandle, "odom", "base_link", if (!NavigationAPI.tf_listener_set_static_transform(tfHandle, "odom", "base_footprint",
0, 0, 0,
0, 0, 0, 1))
{
LogError("Failed to inject static TF map -> base_link");
NavigationAPI.tf_listener_destroy(tfHandle);
return;
}
if (!NavigationAPI.tf_listener_set_static_transform(tfHandle, "base_footprint", "base_link",
0, 0, 0, 0, 0, 0,
0, 0, 0, 1)) 0, 0, 0, 1))
{ {

View File

@ -287,7 +287,16 @@ namespace NavigationExample
return; return;
} }
if (!NavigationAPI.tf_listener_set_static_transform(tfHandle, "odom", "base_link", if (!NavigationAPI.tf_listener_set_static_transform(tfHandle, "odom", "base_footprint",
0, 0, 0,
0, 0, 0, 1))
{
LogError("Failed to inject static TF map -> base_link");
NavigationAPI.tf_listener_destroy(tfHandle);
return;
}
if (!NavigationAPI.tf_listener_set_static_transform(tfHandle, "base_footprint", "base_link",
0, 0, 0, 0, 0, 0,
0, 0, 0, 1)) 0, 0, 0, 1))
{ {

View File

@ -7,7 +7,7 @@ set -e
SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
PROJECT_ROOT="$(cd "$SCRIPT_DIR/.." && pwd)" PROJECT_ROOT="$(cd "$SCRIPT_DIR/.." && pwd)"
BUILD_DIR="$PROJECT_ROOT/build" BUILD_DIR="$PROJECT_ROOT/build"
LIB_DIR="$BUILD_DIR/src/APIs/c_api" LIB_DIR="$BUILD_DIR"
EXAMPLE_DIR="$SCRIPT_DIR" EXAMPLE_DIR="$SCRIPT_DIR"
echo "==========================================" echo "=========================================="

View File

@ -37,6 +37,10 @@ target_link_libraries(nav_c_api
${PACKAGES_DIR} ${PACKAGES_DIR}
) )
set_target_properties(nav_c_api PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
# Set include directories # Set include directories
target_include_directories(nav_c_api target_include_directories(nav_c_api
PUBLIC PUBLIC

View File

@ -12,6 +12,7 @@
#include <cstring> #include <cstring>
#include <cstdlib> #include <cstdlib>
#include <boost/dll/import.hpp> #include <boost/dll/import.hpp>
#include <robot/plugin_loader_helper.h>
// ============================================================================ // ============================================================================
@ -227,9 +228,10 @@ extern "C" bool navigation_initialize(NavigationHandle handle, TFListenerHandle
printf("[%s:%d]\n Initialize navigation\n", __FILE__, __LINE__); printf("[%s:%d]\n Initialize navigation\n", __FILE__, __LINE__);
move_base_core::BaseNavigation* nav = static_cast<move_base_core::BaseNavigation*>(handle); move_base_core::BaseNavigation* nav = static_cast<move_base_core::BaseNavigation*>(handle);
auto* tf_ptr = static_cast<std::shared_ptr<tf3::BufferCore>*>(tf_handle); auto* tf_ptr = static_cast<std::shared_ptr<tf3::BufferCore>*>(tf_handle);
robot::PluginLoaderHelper loader;
std::string lib_path = loader.findLibraryPath("MoveBase");
auto create_plugin = boost::dll::import_alias<move_base_core::BaseNavigation::Ptr()>( auto create_plugin = boost::dll::import_alias<move_base_core::BaseNavigation::Ptr()>(
"/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Navigations/Packages/move_base/libmove_base.so", lib_path,
"MoveBase", "MoveBase",
boost::dll::load_mode::append_decorations); boost::dll::load_mode::append_decorations);

View File

@ -29,7 +29,12 @@ target_link_libraries(score_algorithm
PRIVATE PRIVATE
Boost::filesystem Boost::filesystem
Boost::system Boost::system
)
set_target_properties(score_algorithm PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
) )
target_include_directories(score_algorithm PUBLIC target_include_directories(score_algorithm PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>) $<INSTALL_INTERFACE:include>)

View File

@ -32,6 +32,10 @@ target_link_libraries(kalman
Eigen3::Eigen Eigen3::Eigen
) )
set_target_properties(kalman PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
# Set include directories # Set include directories
target_include_directories(kalman target_include_directories(kalman
PUBLIC PUBLIC
@ -48,6 +52,10 @@ target_link_libraries(kalman_node
Eigen3::Eigen Eigen3::Eigen
) )
set_target_properties(kalman_node PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
# Cài đt header files # Cài đt header files
install(DIRECTORY include/kalman install(DIRECTORY include/kalman
DESTINATION include DESTINATION include

View File

@ -57,6 +57,10 @@ target_link_libraries(mkt_algorithm_diff
Eigen3::Eigen Eigen3::Eigen
) )
set_target_properties(mkt_algorithm_diff PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
# Set include directories # Set include directories
target_include_directories(mkt_algorithm_diff target_include_directories(mkt_algorithm_diff
PUBLIC PUBLIC

View File

@ -55,6 +55,10 @@ target_link_libraries(${PROJECT_NAME}_goal_checker
PRIVATE Boost::boost PRIVATE Boost::boost
) )
set_target_properties(${PROJECT_NAME}_goal_checker PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
target_include_directories(${PROJECT_NAME}_goal_checker target_include_directories(${PROJECT_NAME}_goal_checker
PUBLIC PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
@ -74,6 +78,10 @@ target_link_libraries(${PROJECT_NAME}_standard_traj_generator
PRIVATE Boost::boost PRIVATE Boost::boost
) )
set_target_properties(${PROJECT_NAME}_standard_traj_generator PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
target_include_directories(${PROJECT_NAME}_standard_traj_generator target_include_directories(${PROJECT_NAME}_standard_traj_generator
PUBLIC PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>

View File

@ -46,6 +46,10 @@ target_link_libraries(two_points_planner
PRIVATE Boost::boost PRIVATE Boost::boost
) )
set_target_properties(two_points_planner PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
# Set include directories # Set include directories
target_include_directories(two_points_planner target_include_directories(two_points_planner
PUBLIC PUBLIC

View File

@ -56,6 +56,10 @@ target_link_libraries(${PROJECT_NAME}_utils
PRIVATE Boost::boost PRIVATE Boost::boost
) )
set_target_properties(${PROJECT_NAME}_utils PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
# Set include directories cho utils # Set include directories cho utils
target_include_directories(${PROJECT_NAME}_utils target_include_directories(${PROJECT_NAME}_utils
PUBLIC PUBLIC
@ -78,6 +82,10 @@ target_link_libraries(${PROJECT_NAME}
PRIVATE Boost::boost PRIVATE Boost::boost
) )
set_target_properties(${PROJECT_NAME} PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
# Set include directories cho thư vin chính # Set include directories cho thư vin chính
target_include_directories(${PROJECT_NAME} target_include_directories(${PROJECT_NAME}
PUBLIC PUBLIC

View File

@ -60,7 +60,6 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent,
throw nav_core2::CostmapDataLagException("Costmap2DROBOT is out of date somehow."); throw nav_core2::CostmapDataLagException("Costmap2DROBOT is out of date somehow.");
parent_ = parent; parent_ = parent;
robot::log_warning_at(__FILE__, __LINE__, "Parent namespace: %s", parent_.getNamespace().c_str());
planner_nh_ = robot::NodeHandle(parent_, name); planner_nh_ = robot::NodeHandle(parent_, name);
// planner_nh_.printRootParams(); // planner_nh_.printRootParams();
this->getParams(planner_nh_); this->getParams(planner_nh_);

@ -1 +1 @@
Subproject commit b3be5da393abee4ef535f68f702cd84c02f3b98b Subproject commit 10521c1629301d3e81f040213f08de7881bc5e59

View File

@ -39,6 +39,10 @@ target_link_libraries(conversions
Boost::thread Boost::thread
) )
set_target_properties(conversions PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
add_library(path_ops src/path_ops.cpp) add_library(path_ops src/path_ops.cpp)
target_include_directories(path_ops target_include_directories(path_ops
PUBLIC PUBLIC
@ -58,22 +62,28 @@ target_include_directories(polygons
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include> $<INSTALL_INTERFACE:include>
) )
target_link_libraries(polygons
PUBLIC
nav_2d_msgs
geometry_msgs
robot_cpp
PRIVATE
${xmlrpcpp_LIBRARIES}
)
if(xmlrpcpp_FOUND) if(xmlrpcpp_FOUND)
target_include_directories(polygons PRIVATE ${xmlrpcpp_INCLUDE_DIRS}) target_include_directories(polygons PRIVATE ${xmlrpcpp_INCLUDE_DIRS})
target_link_libraries(polygons
PUBLIC nav_2d_msgs geometry_msgs robot_cpp
PRIVATE ${xmlrpcpp_LIBRARIES})
elseif(XmlRpcCpp_FOUND) elseif(XmlRpcCpp_FOUND)
target_include_directories(polygons PRIVATE ${XmlRpcCpp_INCLUDE_DIRS}) target_include_directories(polygons PRIVATE ${XmlRpcCpp_INCLUDE_DIRS})
target_link_libraries(polygons PRIVATE ${XmlRpcCpp_LIBRARIES}) target_link_libraries(polygons
PUBLIC nav_2d_msgs geometry_msgs robot_cpp
PRIVATE ${XmlRpcCpp_LIBRARIES})
else()
target_include_directories(polygons PRIVATE ${xmlrpcpp_INCLUDE_DIRS})
target_link_libraries(polygons
PUBLIC nav_2d_msgs geometry_msgs robot_cpp
PRIVATE ${xmlrpcpp_LIBRARIES})
endif() endif()
set_target_properties(polygons PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
add_library(bounds src/bounds.cpp) add_library(bounds src/bounds.cpp)
target_include_directories(bounds target_include_directories(bounds
PUBLIC PUBLIC
@ -87,6 +97,10 @@ target_link_libraries(bounds
robot_cpp robot_cpp
) )
set_target_properties(bounds PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
add_library(tf_help src/tf_help.cpp) add_library(tf_help src/tf_help.cpp)
target_include_directories(tf_help target_include_directories(tf_help
PUBLIC PUBLIC
@ -102,6 +116,10 @@ target_link_libraries(tf_help
robot_cpp robot_cpp
) )
set_target_properties(tf_help PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
# Create an INTERFACE library that represents all nav_2d_utils libraries # Create an INTERFACE library that represents all nav_2d_utils libraries
add_library(nav_2d_utils INTERFACE) add_library(nav_2d_utils INTERFACE)
target_include_directories(nav_2d_utils target_include_directories(nav_2d_utils

@ -1 +1 @@
Subproject commit 754042654785374e19d614a2d5927362735ed7ca Subproject commit c54064a3196792b2ad4362fae2b2294aa9b6872c

View File

@ -14,6 +14,9 @@ include_directories(include ${console_bridge_INCLUDE_DIRS})
#CPP Libraries #CPP Libraries
add_library(tf3 src/cache.cpp src/buffer_core.cpp src/static_cache.cpp) add_library(tf3 src/cache.cpp src/buffer_core.cpp src/static_cache.cpp)
target_link_libraries(tf3 ${Boost_LIBRARIES} ${console_bridge_LIBRARIES}) target_link_libraries(tf3 ${Boost_LIBRARIES} ${console_bridge_LIBRARIES})
set_target_properties(tf3 PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
target_include_directories(tf3 PUBLIC target_include_directories(tf3 PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>) $<INSTALL_INTERFACE:include>)
@ -21,7 +24,9 @@ target_include_directories(tf3 PUBLIC
add_executable(simple_tf3_example examples/simple_tf3_example.cpp) add_executable(simple_tf3_example examples/simple_tf3_example.cpp)
target_include_directories(simple_tf3_example PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) target_include_directories(simple_tf3_example PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
target_link_libraries(simple_tf3_example PRIVATE tf3 pthread ${console_bridge_LIBRARIES}) target_link_libraries(simple_tf3_example PRIVATE tf3 pthread ${console_bridge_LIBRARIES})
set_target_properties(simple_tf3_example PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
)
install(TARGETS tf3 install(TARGETS tf3
ARCHIVE DESTINATION lib ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib LIBRARY DESTINATION lib

View File

@ -9,6 +9,9 @@
#include <geometry_msgs/Pose2D.h> #include <geometry_msgs/Pose2D.h>
#include <geometry_msgs/Vector3.h> #include <geometry_msgs/Vector3.h>
// robot protocol msgs
#include <robot_protocol_msgs/Order.h>
// tf // tf
#include <tf3/buffer_core.h> #include <tf3/buffer_core.h>
#include <tf3/utils.h> #include <tf3/utils.h>
@ -60,35 +63,35 @@ namespace move_base_core
switch (state) switch (state)
{ {
case State::PENDING: case State::PENDING:
return "PENDING"; // Chờ xử lý return "PENDING"; // Chờ xử lý
case State::ACTIVE: case State::ACTIVE:
return "ACTIVE"; // Đang hoạt động return "ACTIVE"; // Đang hoạt động
case State::PREEMPTED: case State::PREEMPTED:
return "PREEMPTED"; // Đã bị huỷ bởi yêu cầu mới return "PREEMPTED"; // Đã bị huỷ bởi yêu cầu mới
case State::SUCCEEDED: case State::SUCCEEDED:
return "SUCCEEDED"; // Thành công return "SUCCEEDED"; // Thành công
case State::ABORTED: case State::ABORTED:
return "ABORTED"; // Bị lỗi return "ABORTED"; // Bị lỗi
case State::REJECTED: case State::REJECTED:
return "REJECTED"; // Từ chối bởi planner hoặc controller return "REJECTED"; // Từ chối bởi planner hoặc controller
case State::PREEMPTING: case State::PREEMPTING:
return "PREEMPTING"; // Đang huỷ bỏ theo yêu cầu return "PREEMPTING"; // Đang huỷ bỏ theo yêu cầu
case State::RECALLING: case State::RECALLING:
return "RECALLING"; // Đang huỷ bỏ nội bộ return "RECALLING"; // Đang huỷ bỏ nội bộ
case State::RECALLED: case State::RECALLED:
return "RECALLED"; // Đã được thu hồi return "RECALLED"; // Đã được thu hồi
case State::LOST: case State::LOST:
return "LOST"; // Mất trạng thái return "LOST"; // Mất trạng thái
case State::PLANNING: case State::PLANNING:
return "PLANNING"; // Đang lập kế hoạch đường đi return "PLANNING"; // Đang lập kế hoạch đường đi
case State::CONTROLLING: case State::CONTROLLING:
return "CONTROLLING"; // Đang điều khiển robot di chuyển theo plan return "CONTROLLING"; // Đang điều khiển robot di chuyển theo plan
case State::CLEARING: case State::CLEARING:
return "CLEARING"; // Đang dọn dẹp bản đồ / costmap return "CLEARING"; // Đang dọn dẹp bản đồ / costmap
case State::PAUSED: case State::PAUSED:
return "PAUSED"; // Tạm dừng return "PAUSED"; // Tạm dừng
default: default:
return "UNKNOWN_STATE"; // Không xác định return "UNKNOWN_STATE"; // Không xác định
} }
} }
@ -165,7 +168,7 @@ namespace move_base_core
* @param fprt A vector of points representing the robot's footprint polygon. * @param fprt A vector of points representing the robot's footprint polygon.
* The points should be ordered counter-clockwise. * The points should be ordered counter-clockwise.
* Example: * Example:
* *
^ Y ^ Y
| |
| P3(-0.3, 0.2) P2(0.3, 0.2) | P3(-0.3, 0.2) P2(0.3, 0.2)
@ -196,6 +199,19 @@ namespace move_base_core
double xy_goal_tolerance = 0.0, double xy_goal_tolerance = 0.0,
double yaw_goal_tolerance = 0.0) = 0; double yaw_goal_tolerance = 0.0) = 0;
/**
* @brief Send a goal for the robot to navigate to.
* @param msg Order message.
* @param goal Target pose in the global frame.
* @param xy_goal_tolerance Acceptable error in X/Y (meters).
* @param yaw_goal_tolerance Acceptable angular error (radians).
* @return True if goal was accepted and sent successfully.
*/
virtual bool moveTo(const robot_protocol_msgs::Order &msg,
const geometry_msgs::PoseStamped &goal,
double xy_goal_tolerance = 0.0,
double yaw_goal_tolerance = 0.0) = 0;
/** /**
* @brief Send a docking goal to a predefined marker (e.g. charger). * @brief Send a docking goal to a predefined marker (e.g. charger).
* @param maker Marker name or ID. * @param maker Marker name or ID.
@ -209,6 +225,19 @@ namespace move_base_core
double xy_goal_tolerance = 0.0, double xy_goal_tolerance = 0.0,
double yaw_goal_tolerance = 0.0) = 0; double yaw_goal_tolerance = 0.0) = 0;
/**
* @brief Send a docking goal to a predefined marker (e.g. charger).
* @param msg Order message.
* @param goal Target pose for docking.
* @param xy_goal_tolerance Acceptable XY error (meters).
* @param yaw_goal_tolerance Acceptable heading error (radians).
* @return True if docking command succeeded.
*/
virtual bool dockTo(const robot_protocol_msgs::Order &msg,
const geometry_msgs::PoseStamped &goal,
double xy_goal_tolerance = 0.0,
double yaw_goal_tolerance = 0.0) = 0;
/** /**
* @brief Move straight toward the target position (X-axis). * @brief Move straight toward the target position (X-axis).
* @param goal Target pose. * @param goal Target pose.

View File

@ -66,19 +66,13 @@ set(_NAV_CORE_ADAPTER_RPATH
) )
set_target_properties(costmap_adapter PROPERTIES set_target_properties(costmap_adapter PROPERTIES
BUILD_RPATH "${_NAV_CORE_ADAPTER_RPATH}" LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
INSTALL_RPATH "${_NAV_CORE_ADAPTER_RPATH}"
LINK_FLAGS "-Wl,--disable-new-dtags"
) )
set_target_properties(local_planner_adapter PROPERTIES set_target_properties(local_planner_adapter PROPERTIES
BUILD_RPATH "${_NAV_CORE_ADAPTER_RPATH}" LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
INSTALL_RPATH "${_NAV_CORE_ADAPTER_RPATH}"
LINK_FLAGS "-Wl,--disable-new-dtags"
) )
set_target_properties(global_planner_adapter PROPERTIES set_target_properties(global_planner_adapter PROPERTIES
BUILD_RPATH "${_NAV_CORE_ADAPTER_RPATH}" LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
INSTALL_RPATH "${_NAV_CORE_ADAPTER_RPATH}"
LINK_FLAGS "-Wl,--disable-new-dtags"
) )
# Cài đt header files # Cài đt header files

View File

@ -93,10 +93,9 @@ namespace nav_core_adapter
planner_name = nav_2d_utils::searchAndGetParam(adapter_nh_, "position_planner_name", std::string("dwb_local_planner::DWBLocalPlanner")); planner_name = nav_2d_utils::searchAndGetParam(adapter_nh_, "position_planner_name", std::string("dwb_local_planner::DWBLocalPlanner"));
adapter_nh_.setParam("planner_name", planner_name); adapter_nh_.setParam("planner_name", planner_name);
} }
std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Algorithms/Packages/local_planners/pnkx_local_planner/libpnkx_local_planner.so";
try try
{ {
std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Algorithms/Packages/local_planners/pnkx_local_planner/libpnkx_local_planner.so";
planner_loader_ = boost::dll::import_alias<nav_core2::LocalPlanner::Ptr()>( planner_loader_ = boost::dll::import_alias<nav_core2::LocalPlanner::Ptr()>(
path_file_so, planner_name, boost::dll::load_mode::append_decorations); path_file_so, planner_name, boost::dll::load_mode::append_decorations);
planner_ = planner_loader_(); planner_ = planner_loader_();

View File

@ -157,9 +157,7 @@ else()
# Set RPATH đ ưu tiên thư vin build cc b # Set RPATH đ ưu tiên thư vin build cc b
set_target_properties(move_base PROPERTIES set_target_properties(move_base PROPERTIES
BUILD_RPATH "${CMAKE_BINARY_DIR}/src/Libraries/costmap_2d:${CMAKE_BINARY_DIR}/src/Libraries/node_handle:${CMAKE_BINARY_DIR}/src/Libraries/tf3:${CMAKE_BINARY_DIR}/src/Libraries/robot_time:${CMAKE_BINARY_DIR}/src/Libraries/xmlrpcpp" LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
INSTALL_RPATH "${CMAKE_BINARY_DIR}/src/Libraries/costmap_2d:${CMAKE_BINARY_DIR}/src/Libraries/node_handle:${CMAKE_BINARY_DIR}/src/Libraries/tf3:${CMAKE_BINARY_DIR}/src/Libraries/robot_time:${CMAKE_BINARY_DIR}/src/Libraries/xmlrpcpp"
LINK_FLAGS "-Wl,--disable-new-dtags"
) )
endif() endif()

View File

@ -27,6 +27,7 @@
#include <costmap_2d/costmap_2d_robot.h> #include <costmap_2d/costmap_2d_robot.h>
#include <costmap_2d/costmap_2d.h> #include <costmap_2d/costmap_2d.h>
#include <nav_msgs/GetPlan.h> #include <nav_msgs/GetPlan.h>
#include <robot_protocol_msgs/Order.h>
#include <robot/node_handle.h> #include <robot/node_handle.h>
#include <robot/console.h> #include <robot/console.h>
@ -94,6 +95,19 @@ namespace move_base
double xy_goal_tolerance = 0.0, double xy_goal_tolerance = 0.0,
double yaw_goal_tolerance = 0.0) override; double yaw_goal_tolerance = 0.0) override;
/**
* @brief Send a goal for the robot to navigate to.
* @param msg Order message.
* @param goal Target pose in the global frame.
* @param xy_goal_tolerance Acceptable error in X/Y (meters).
* @param yaw_goal_tolerance Acceptable angular error (radians).
* @return True if goal was accepted and sent successfully.
*/
virtual bool moveTo(const robot_protocol_msgs::Order &msg,
const geometry_msgs::PoseStamped &goal,
double xy_goal_tolerance = 0.0,
double yaw_goal_tolerance = 0.0) override;
/** /**
* @brief Send a docking goal to a predefined marker (e.g. charger). * @brief Send a docking goal to a predefined marker (e.g. charger).
* @param maker Marker name or ID. * @param maker Marker name or ID.
@ -107,8 +121,22 @@ namespace move_base
double xy_goal_tolerance = 0.0, double xy_goal_tolerance = 0.0,
double yaw_goal_tolerance = 0.0) override; double yaw_goal_tolerance = 0.0) override;
/**
* @brief Send a docking goal to a predefined marker (e.g. charger).
* @param msg Order message.
* @param goal Target pose for docking.
* @param xy_goal_tolerance Acceptable XY error (meters).
* @param yaw_goal_tolerance Acceptable heading error (radians).
* @return True if docking command succeeded.
*/
virtual bool dockTo(const robot_protocol_msgs::Order &msg,
const geometry_msgs::PoseStamped &goal,
double xy_goal_tolerance = 0.0,
double yaw_goal_tolerance = 0.0) override;
/** /**
* @brief Move straight toward the target position (X-axis). * @brief Move straight toward the target position (X-axis).
* @param msg Order message.
* @param goal Target pose. * @param goal Target pose.
* @param xy_goal_tolerance Acceptable positional error (meters). * @param xy_goal_tolerance Acceptable positional error (meters).
* @return True if command issued successfully. * @return True if command issued successfully.
@ -206,22 +234,6 @@ namespace move_base
*/ */
void swapPlanner(std::string base_global_planner); void swapPlanner(std::string base_global_planner);
// /**
// * @brief A service call that clears the costmaps of obstacles
// * @param req The service request
// * @param resp The service response
// * @return True if the service call succeeds, false otherwise
// */
// bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
// /**
// * @brief A service call that can be made when the action is inactive that will return a plan
// * @param req The goal request
// * @param resp The plan request
// * @return True if planning succeeded, false otherwise
// */
// bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
/** /**
* @brief Make a new global plan * @brief Make a new global plan
* @param goal The goal to plan to * @param goal The goal to plan to

View File

@ -0,0 +1,7 @@
<class_libraries>
<library path="lib/libmove_base">
<class type="move_base::MoveBase" base_class_type="move_base_core::BaseNavigation">
<description></description>
</class>
</library>
</class_libraries>

View File

@ -15,6 +15,7 @@
#include <boost/thread.hpp> #include <boost/thread.hpp>
#include <boost/dll/import.hpp> #include <boost/dll/import.hpp>
#include <boost/dll/alias.hpp> #include <boost/dll/alias.hpp>
#include <robot/plugin_loader_helper.h>
move_base::MoveBase::MoveBase() move_base::MoveBase::MoveBase()
: initialized_(false), : initialized_(false),
@ -156,34 +157,24 @@ void move_base::MoveBase::initialize(TFListenerPtr tf)
// we'll assume the radius of the robot to be consistent with what's specified for the costmaps // we'll assume the radius of the robot to be consistent with what's specified for the costmaps
// From config param // From config param
double inscribed_radius; double inscribed_radius;
robot::log_info("[%s:%d] inscribed_radius: %f", __FILE__, __LINE__, inscribed_radius);
private_nh_.getParam("local_costmap/inscribed_radius", inscribed_radius, 0.2); private_nh_.getParam("local_costmap/inscribed_radius", inscribed_radius, 0.2);
double circumscribed_radius; double circumscribed_radius;
private_nh_.getParam("local_costmap/circumscribed_radius", circumscribed_radius, 0.3); private_nh_.getParam("local_costmap/circumscribed_radius", circumscribed_radius, 0.3);
robot::log_info("[%s:%d] circumscribed_radius: %f", __FILE__, __LINE__, circumscribed_radius);
inscribed_radius_ = inscribed_radius; inscribed_radius_ = inscribed_radius;
circumscribed_radius_ = circumscribed_radius; circumscribed_radius_ = circumscribed_radius;
private_nh_.getParam("clearing_radius", clearing_radius_, 0.0); private_nh_.getParam("clearing_radius", clearing_radius_, 0.0);
robot::log_info("[%s:%d] clearing_radius: %f", __FILE__, __LINE__, clearing_radius_);
double conservative_reset_dist; double conservative_reset_dist;
private_nh_.getParam("conservative_reset_dist", conservative_reset_dist, 0.0); private_nh_.getParam("conservative_reset_dist", conservative_reset_dist, 0.0);
robot::log_info("[%s:%d] conservative_reset_dist: %f", __FILE__, __LINE__, conservative_reset_dist);
conservative_reset_dist_ = conservative_reset_dist; conservative_reset_dist_ = conservative_reset_dist;
robot::log_info("[%s:%d] shutdown_costmaps: %f", __FILE__, __LINE__, shutdown_costmaps_);
private_nh_.getParam("shutdown_costmaps", shutdown_costmaps_, false); private_nh_.getParam("shutdown_costmaps", shutdown_costmaps_, false);
robot::log_info("[%s:%d] clearing_rotation_allowed: %f", __FILE__, __LINE__, clearing_rotation_allowed_);
private_nh_.getParam("clearing_rotation_allowed", clearing_rotation_allowed_, true); private_nh_.getParam("clearing_rotation_allowed", clearing_rotation_allowed_, true);
robot::log_info("[%s:%d] recovery_behavior_enabled: %f", __FILE__, __LINE__, recovery_behavior_enabled_);
private_nh_.getParam("recovery_behavior_enabled", recovery_behavior_enabled_, true); private_nh_.getParam("recovery_behavior_enabled", recovery_behavior_enabled_, true);
// create the ros wrapper for the planner's costmap... and initializer a pointer we'll use with the underlying map // create the ros wrapper for the planner's costmap... and initializer a pointer we'll use with the underlying map
robot::log_info("[%s:%d] create the ros wrapper for the planner's costmap...");
try try
{ {
planner_costmap_robot_ = new costmap_2d::Costmap2DROBOT("global_costmap", *tf_); planner_costmap_robot_ = new costmap_2d::Costmap2DROBOT("global_costmap", *tf_);
robot::log_info("[%s:%d] planner_costmap_robot_->pause()");
planner_costmap_robot_->pause(); planner_costmap_robot_->pause();
robot::log_info("[%s:%d] planner_costmap_robot_->pause()");
} }
catch (const std::exception &ex) catch (const std::exception &ex)
{ {
@ -193,10 +184,10 @@ void move_base::MoveBase::initialize(TFListenerPtr tf)
// initialize the global planner // initialize the global planner
try try
{ {
robot::PluginLoaderHelper loader;
std::string path_file_so = loader.findLibraryPath("CustomPlanner");
planner_loader_ = boost::dll::import_alias<nav_core::BaseGlobalPlanner::Ptr()>( planner_loader_ = boost::dll::import_alias<nav_core::BaseGlobalPlanner::Ptr()>(
"/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Algorithms/Packages/global_planners/two_points_planner/libtwo_points_planner.so", path_file_so, global_planner, boost::dll::load_mode::append_decorations);
global_planner,
boost::dll::load_mode::append_decorations);
planner_ = planner_loader_(); planner_ = planner_loader_();
if (!planner_) if (!planner_)
@ -214,13 +205,22 @@ void move_base::MoveBase::initialize(TFListenerPtr tf)
robot::log_error("[%s:%d]\n EXCEPTION in global planner: %s", __FILE__, __LINE__, ex.what()); robot::log_error("[%s:%d]\n EXCEPTION in global planner: %s", __FILE__, __LINE__, ex.what());
throw std::runtime_error("Failed to create the " + global_planner + " planner"); throw std::runtime_error("Failed to create the " + global_planner + " planner");
} }
// create the ros wrapper for the controller's costmap... and initializer a pointer we'll use with the underlying map
controller_costmap_robot_ = new costmap_2d::Costmap2DROBOT("local_costmap", *tf_); try
controller_costmap_robot_->pause(); {
controller_costmap_robot_ = new costmap_2d::Costmap2DROBOT("local_costmap", *tf_);
controller_costmap_robot_->pause();
}
catch (const std::exception &ex)
{
robot::log_error("[%s:%d]\n EXCEPTION: %s", __FILE__, __LINE__, ex.what());
throw std::runtime_error("Failed to create the controller_costmap_robot_");
}
// create a local planner // create a local planner
try try
{ {
std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Navigations/Cores/nav_core_adapter/liblocal_planner_adapter.so"; robot::PluginLoaderHelper loader;
std::string path_file_so = loader.findLibraryPath("LocalPlannerAdapter");
controller_loader_ = controller_loader_ =
boost::dll::import_alias<nav_core::BaseLocalPlanner::Ptr()>( boost::dll::import_alias<nav_core::BaseLocalPlanner::Ptr()>(
path_file_so, local_planner, boost::dll::load_mode::append_decorations); path_file_so, local_planner, boost::dll::load_mode::append_decorations);
@ -363,15 +363,18 @@ bool move_base::MoveBase::moveTo(const geometry_msgs::PoseStamped &goal, double
if (cancel_ctr_) if (cancel_ctr_)
cancel_ctr_ = false; cancel_ctr_ = false;
// move_base_msgs::MoveBaseActionGoal action_goal;
// action_goal.header.stamp = robot::Time::now();
// action_goal.goal.target_pose = goal;
// action_goal_pub_.publish(action_goal);
lock.unlock(); lock.unlock();
return true; return true;
} }
bool move_base::MoveBase::moveTo(const robot_protocol_msgs::Order &msg,
const geometry_msgs::PoseStamped &goal,
double xy_goal_tolerance, double yaw_goal_tolerance)
{
return false;
}
bool move_base::MoveBase::dockTo(const std::string &maker, const geometry_msgs::PoseStamped &goal, bool move_base::MoveBase::dockTo(const std::string &maker, const geometry_msgs::PoseStamped &goal,
double xy_goal_tolerance, double yaw_goal_tolerance) double xy_goal_tolerance, double yaw_goal_tolerance)
{ {
@ -454,14 +457,17 @@ bool move_base::MoveBase::dockTo(const std::string &maker, const geometry_msgs::
if (cancel_ctr_) if (cancel_ctr_)
cancel_ctr_ = false; cancel_ctr_ = false;
// move_base_msgs::MoveBaseActionGoal action_goal;
// action_goal.header.stamp = robot::Time::now();
// action_goal.goal.target_pose = goal;
// action_goal_pub_.publish(action_goal);
lock.unlock(); lock.unlock();
return true; return true;
} }
bool move_base::MoveBase::dockTo(const robot_protocol_msgs::Order &msg,
const geometry_msgs::PoseStamped &goal,
double xy_goal_tolerance, double yaw_goal_tolerance)
{
return false;
}
bool move_base::MoveBase::moveStraightTo(const geometry_msgs::PoseStamped &goal, double xy_goal_tolerance) bool move_base::MoveBase::moveStraightTo(const geometry_msgs::PoseStamped &goal, double xy_goal_tolerance)
{ {
if (setup_) if (setup_)
@ -505,10 +511,6 @@ bool move_base::MoveBase::moveStraightTo(const geometry_msgs::PoseStamped &goal,
} }
if (cancel_ctr_) if (cancel_ctr_)
cancel_ctr_ = false; cancel_ctr_ = false;
// move_base_msgs::MoveBaseActionGoal action_goal;
// action_goal.header.stamp = robot::Time::now();
// action_goal.goal.target_pose = goal;
// action_goal_pub_.publish(action_goal);
lock.unlock(); lock.unlock();
return true; return true;