Compare commits
4 Commits
6ff54e4154
...
awc-devel
| Author | SHA1 | Date | |
|---|---|---|---|
| 768a257b33 | |||
| 3c8e1cdaf5 | |||
| cf0c6e7caf | |||
| 7baa7000b8 |
@@ -37,7 +37,7 @@ charger:
|
|||||||
- {name: charger, docking_planner: "DockPlanner", docking_nav: ""}
|
- {name: charger, docking_planner: "DockPlanner", docking_nav: ""}
|
||||||
|
|
||||||
charger:
|
charger:
|
||||||
maker_goal_frame: charger_goal
|
maker_goal_frame: charger
|
||||||
footprint: [[0.583,-0.48],[0.583,0.48],[-0.583,0.48],[-0.583,-0.48]]
|
footprint: [[0.583,-0.48],[0.583,0.48],[-0.583,0.48],[-0.583,-0.48]]
|
||||||
delay: 1.5 # Cấm sửa không là không chạy được
|
delay: 1.5 # Cấm sửa không là không chạy được
|
||||||
timeout: 60
|
timeout: 60
|
||||||
|
|||||||
@@ -398,7 +398,6 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXDockingLocalPlanner::S
|
|||||||
else if (!ret_nav_)
|
else if (!ret_nav_)
|
||||||
{
|
{
|
||||||
traj = nav_algorithm_->calculator(pose, velocity);
|
traj = nav_algorithm_->calculator(pose, velocity);
|
||||||
|
|
||||||
if (!dkpl_.empty() && dkpl_.front()->initialized_ && dkpl_.front()->is_detected_ && !dkpl_.front()->is_goal_reached_)
|
if (!dkpl_.empty() && dkpl_.front()->initialized_ && dkpl_.front()->is_detected_ && !dkpl_.front()->is_goal_reached_)
|
||||||
{
|
{
|
||||||
if (dkpl_.front()->docking_nav_ && !dkpl_.front()->docking_planner_)
|
if (dkpl_.front()->docking_nav_ && !dkpl_.front()->docking_planner_)
|
||||||
@@ -406,9 +405,17 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXDockingLocalPlanner::S
|
|||||||
traj = dkpl_.front()->docking_nav_->calculator(pose, velocity);
|
traj = dkpl_.front()->docking_nav_->calculator(pose, velocity);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
local_plan_.header.stamp = robot::Time::now();
|
||||||
|
robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getBaseFrameID(), robot::Time::now());
|
||||||
|
local_plan_ = robot_nav_2d_utils::pathToPath(path);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
{
|
||||||
traj = rotate_algorithm_->calculator(pose, velocity);
|
traj = rotate_algorithm_->calculator(pose, velocity);
|
||||||
|
local_plan_.header.stamp = robot::Time::now();
|
||||||
|
robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getBaseFrameID(), robot::Time::now());
|
||||||
|
local_plan_ = robot_nav_2d_utils::pathToPath(path);
|
||||||
|
}
|
||||||
|
|
||||||
cmd_vel.velocity = traj.velocity;
|
cmd_vel.velocity = traj.velocity;
|
||||||
return cmd_vel;
|
return cmd_vel;
|
||||||
@@ -553,7 +560,7 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::dockingHanlde(const robot_nav_
|
|||||||
{
|
{
|
||||||
if(!dkpl_.empty())
|
if(!dkpl_.empty())
|
||||||
{
|
{
|
||||||
if(dkpl_.front()) delete(dkpl_.front());
|
// if(dkpl_.front()) delete(dkpl_.front());
|
||||||
dkpl_.erase(dkpl_.begin());
|
dkpl_.erase(dkpl_.begin());
|
||||||
}
|
}
|
||||||
start_docking_ = false;
|
start_docking_ = false;
|
||||||
|
|||||||
@@ -66,7 +66,6 @@ std::string PluginLoaderHelper::findLibraryPath(const std::string& symbol_name)
|
|||||||
}
|
}
|
||||||
// Try to read from NodeHandle
|
// Try to read from NodeHandle
|
||||||
std::string library_path;
|
std::string library_path;
|
||||||
robot::log_info_at(__FILE__, __LINE__, "%s", symbol_name.c_str());
|
|
||||||
if (nh_.hasParam(param_path)) {
|
if (nh_.hasParam(param_path)) {
|
||||||
nh_.getParam(param_path, library_path, std::string(""));
|
nh_.getParam(param_path, library_path, std::string(""));
|
||||||
if (!library_path.empty()) {
|
if (!library_path.empty()) {
|
||||||
@@ -339,7 +338,7 @@ std::string PluginLoaderHelper::getBuildDirectory()
|
|||||||
std::string PluginLoaderHelper::getWorkspacePath()
|
std::string PluginLoaderHelper::getWorkspacePath()
|
||||||
{
|
{
|
||||||
// Method 1: Từ environment variable PNKX_NAV_CORE_DIR
|
// Method 1: Từ environment variable PNKX_NAV_CORE_DIR
|
||||||
const char* workspace_path = std::getenv("PNKX_NAV_CORE_LIBRARY_PATH");
|
const char* workspace_path = std::getenv("PNKX_NAV_CORE_DIR");
|
||||||
if (workspace_path && std::filesystem::exists(workspace_path)) {
|
if (workspace_path && std::filesystem::exists(workspace_path)) {
|
||||||
return std::string(workspace_path);
|
return std::string(workspace_path);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -271,6 +271,7 @@ void move_base::MoveBase::initialize(robot::TFListenerPtr tf)
|
|||||||
{
|
{
|
||||||
robot::PluginLoaderHelper loader;
|
robot::PluginLoaderHelper loader;
|
||||||
std::string path_file_so = loader.findLibraryPath(global_planner);
|
std::string path_file_so = loader.findLibraryPath(global_planner);
|
||||||
|
robot::log_info("[%s:%d]\n INFO: global_planner library path: %s", __FILE__, __LINE__, path_file_so.c_str());
|
||||||
planner_loader_ = boost::dll::import_alias<robot_nav_core::BaseGlobalPlanner::Ptr()>(
|
planner_loader_ = boost::dll::import_alias<robot_nav_core::BaseGlobalPlanner::Ptr()>(
|
||||||
path_file_so, global_planner, boost::dll::load_mode::append_decorations);
|
path_file_so, global_planner, boost::dll::load_mode::append_decorations);
|
||||||
|
|
||||||
@@ -314,6 +315,7 @@ void move_base::MoveBase::initialize(robot::TFListenerPtr tf)
|
|||||||
{
|
{
|
||||||
robot::PluginLoaderHelper loader;
|
robot::PluginLoaderHelper loader;
|
||||||
std::string path_file_so = loader.findLibraryPath(local_planner);
|
std::string path_file_so = loader.findLibraryPath(local_planner);
|
||||||
|
robot::log_info("[%s:%d]\n INFO: local_planner library path: %s", __FILE__, __LINE__, path_file_so.c_str());
|
||||||
controller_loader_ =
|
controller_loader_ =
|
||||||
boost::dll::import_alias<robot_nav_core::BaseLocalPlanner::Ptr()>(
|
boost::dll::import_alias<robot_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);
|
||||||
@@ -401,7 +403,7 @@ void move_base::MoveBase::swapPlanner(std::string base_global_planner)
|
|||||||
boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
|
boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
|
||||||
robot::PluginLoaderHelper loader;
|
robot::PluginLoaderHelper loader;
|
||||||
std::string path_file_so = loader.findLibraryPath(base_global_planner);
|
std::string path_file_so = loader.findLibraryPath(base_global_planner);
|
||||||
|
robot::log_info("[%s:%d]\n INFO: global_planner library path: %s", __FILE__, __LINE__, path_file_so.c_str());
|
||||||
auto new_loader = boost::dll::import_alias<robot_nav_core::BaseGlobalPlanner::Ptr()>(
|
auto new_loader = boost::dll::import_alias<robot_nav_core::BaseGlobalPlanner::Ptr()>(
|
||||||
path_file_so, base_global_planner, boost::dll::load_mode::append_decorations);
|
path_file_so, base_global_planner, boost::dll::load_mode::append_decorations);
|
||||||
auto new_planner = new_loader();
|
auto new_planner = new_loader();
|
||||||
@@ -2005,6 +2007,7 @@ bool move_base::MoveBase::loadRecoveryBehaviors(const robot::NodeHandle &node)
|
|||||||
std::string behavior_name = behavior["name"].as<std::string>();
|
std::string behavior_name = behavior["name"].as<std::string>();
|
||||||
robot::PluginLoaderHelper loader;
|
robot::PluginLoaderHelper loader;
|
||||||
std::string path_file_so = loader.findLibraryPath(behavior_type);
|
std::string path_file_so = loader.findLibraryPath(behavior_type);
|
||||||
|
robot::log_info("Loading recovery behavior '%s' of type '%s' from '%s'", behavior_name.c_str(), behavior_type.c_str(), path_file_so.c_str());
|
||||||
// Load the factory function from the shared library
|
// Load the factory function from the shared library
|
||||||
recovery_loaders_[behavior_name] = boost::dll::import_alias<robot_nav_core::RecoveryBehavior::Ptr()>(
|
recovery_loaders_[behavior_name] = boost::dll::import_alias<robot_nav_core::RecoveryBehavior::Ptr()>(
|
||||||
path_file_so, behavior_type, boost::dll::load_mode::append_decorations);
|
path_file_so, behavior_type, boost::dll::load_mode::append_decorations);
|
||||||
|
|||||||
Reference in New Issue
Block a user