git commit -m "first commit"
This commit is contained in:
117
navigations/nav_core_adapter/src/costmap_adapter.cpp
Executable file
117
navigations/nav_core_adapter/src/costmap_adapter.cpp
Executable file
@@ -0,0 +1,117 @@
|
||||
/*
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2018, Locus Robotics
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#include <nav_core_adapter/costmap_adapter.h>
|
||||
#include <nav_core2/exceptions.h>
|
||||
#include <pluginlib/class_list_macros.h>
|
||||
#include <string>
|
||||
|
||||
PLUGINLIB_EXPORT_CLASS(nav_core_adapter::CostmapAdapter, nav_core2::Costmap)
|
||||
|
||||
namespace nav_core_adapter
|
||||
{
|
||||
|
||||
nav_grid::NavGridInfo infoFromCostmap(costmap_2d::Costmap2DROS* costmap_ros)
|
||||
{
|
||||
nav_grid::NavGridInfo info;
|
||||
costmap_2d::Costmap2D* costmap = costmap_ros->getCostmap();
|
||||
info.width = costmap->getSizeInCellsX();
|
||||
info.height = costmap->getSizeInCellsY();
|
||||
info.resolution = costmap->getResolution();
|
||||
info.frame_id = costmap_ros->getGlobalFrameID();
|
||||
info.origin_x = costmap->getOriginX();
|
||||
info.origin_y = costmap->getOriginY();
|
||||
return info;
|
||||
}
|
||||
|
||||
CostmapAdapter::~CostmapAdapter()
|
||||
{
|
||||
if (needs_destruction_)
|
||||
{
|
||||
delete costmap_ros_;
|
||||
}
|
||||
}
|
||||
|
||||
void CostmapAdapter::initialize(costmap_2d::Costmap2DROS* costmap_ros, bool needs_destruction)
|
||||
{
|
||||
costmap_ros_ = costmap_ros;
|
||||
needs_destruction_ = needs_destruction;
|
||||
info_ = infoFromCostmap(costmap_ros_);
|
||||
costmap_ = costmap_ros_->getCostmap();
|
||||
}
|
||||
|
||||
void CostmapAdapter::initialize(const ros::NodeHandle& parent, const std::string& name, TFListenerPtr tf)
|
||||
{
|
||||
initialize(new costmap_2d::Costmap2DROS(name, *tf), true);
|
||||
}
|
||||
|
||||
nav_core2::Costmap::mutex_t* CostmapAdapter::getMutex()
|
||||
{
|
||||
return costmap_->getMutex();
|
||||
}
|
||||
|
||||
void CostmapAdapter::reset()
|
||||
{
|
||||
costmap_ros_->resetLayers();
|
||||
}
|
||||
|
||||
void CostmapAdapter::update()
|
||||
{
|
||||
info_ = infoFromCostmap(costmap_ros_);
|
||||
if (!costmap_ros_->isCurrent())
|
||||
throw nav_core2::CostmapDataLagException("Costmap2DROS is out of date somehow.");
|
||||
}
|
||||
|
||||
void CostmapAdapter::setValue(const unsigned int x, const unsigned int y, const unsigned char& value)
|
||||
{
|
||||
costmap_->setCost(x, y, value);
|
||||
}
|
||||
|
||||
unsigned char CostmapAdapter::getValue(const unsigned int x, const unsigned int y) const
|
||||
{
|
||||
unsigned int index = costmap_->getIndex(x, y);
|
||||
return costmap_->getCharMap()[index];
|
||||
}
|
||||
|
||||
void CostmapAdapter::setInfo(const nav_grid::NavGridInfo& new_info)
|
||||
{
|
||||
throw nav_core2::CostmapException("setInfo not implemented on CostmapAdapter");
|
||||
}
|
||||
|
||||
void CostmapAdapter::updateInfo(const nav_grid::NavGridInfo& new_info)
|
||||
{
|
||||
costmap_->updateOrigin(new_info.origin_x, new_info.origin_y);
|
||||
}
|
||||
|
||||
} // namespace nav_core_adapter
|
||||
97
navigations/nav_core_adapter/src/global_planner_adapter.cpp
Executable file
97
navigations/nav_core_adapter/src/global_planner_adapter.cpp
Executable file
@@ -0,0 +1,97 @@
|
||||
/*
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2017, Locus Robotics
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#include <nav_core_adapter/global_planner_adapter.h>
|
||||
#include <nav_core_adapter/costmap_adapter.h>
|
||||
#include <nav_2d_utils/conversions.h>
|
||||
#include <nav_2d_utils/tf_help.h>
|
||||
#include <nav_core2/exceptions.h>
|
||||
#include <pluginlib/class_list_macros.h>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
namespace nav_core_adapter
|
||||
{
|
||||
|
||||
GlobalPlannerAdapter::GlobalPlannerAdapter() :
|
||||
planner_loader_("nav_core2", "nav_core2::GlobalPlanner")
|
||||
{
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Load the nav_core2 global planner and initialize it
|
||||
*/
|
||||
void GlobalPlannerAdapter::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
|
||||
{
|
||||
costmap_ros_ = costmap_ros;
|
||||
costmap_adapter_ = std::make_shared<CostmapAdapter>();
|
||||
costmap_adapter_->initialize(costmap_ros);
|
||||
|
||||
ros::NodeHandle private_nh("~");
|
||||
ros::NodeHandle adapter_nh("~/" + name);
|
||||
std::string planner_name;
|
||||
adapter_nh.param("planner_name", planner_name, std::string("dlux_global_planner::DluxGlobalPlanner"));
|
||||
ROS_WARN("%s ,GlobalPlannerAdapter::initialize", name.c_str());
|
||||
ROS_INFO_NAMED("GlobalPlannerAdapter", "Loading plugin %s", planner_name.c_str());
|
||||
planner_ = planner_loader_.createInstance(planner_name);
|
||||
planner_->initialize(private_nh, planner_loader_.getName(planner_name), tf_, costmap_adapter_);
|
||||
path_pub_ = private_nh.advertise<nav_msgs::Path>("plan", 1);
|
||||
}
|
||||
|
||||
bool GlobalPlannerAdapter::makePlan(const geometry_msgs::PoseStamped& start,
|
||||
const geometry_msgs::PoseStamped& goal,
|
||||
std::vector<geometry_msgs::PoseStamped>& plan)
|
||||
{
|
||||
nav_2d_msgs::Pose2DStamped start2d = nav_2d_utils::poseStampedToPose2D(start),
|
||||
goal2d = nav_2d_utils::poseStampedToPose2D(goal);
|
||||
try
|
||||
{
|
||||
nav_2d_msgs::Path2D path2d = planner_->makePlan(start2d, goal2d);
|
||||
nav_msgs::Path path = nav_2d_utils::pathToPath(path2d);
|
||||
plan = path.poses;
|
||||
path_pub_.publish(path);
|
||||
return true;
|
||||
}
|
||||
catch (nav_core2::PlannerException& e)
|
||||
{
|
||||
ROS_ERROR_NAMED("GlobalPlannerAdapter", "makePlan Exception: %s", e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
} // namespace nav_core_adapter
|
||||
|
||||
|
||||
// register this planner as a BaseGlobalPlanner plugin
|
||||
PLUGINLIB_EXPORT_CLASS(nav_core_adapter::GlobalPlannerAdapter, nav_core::BaseGlobalPlanner)
|
||||
95
navigations/nav_core_adapter/src/global_planner_adapter2.cpp
Executable file
95
navigations/nav_core_adapter/src/global_planner_adapter2.cpp
Executable file
@@ -0,0 +1,95 @@
|
||||
/*
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2017, Locus Robotics
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#include <nav_core_adapter/global_planner_adapter2.h>
|
||||
#include <nav_core_adapter/costmap_adapter.h>
|
||||
#include <nav_2d_utils/conversions.h>
|
||||
#include <nav_2d_utils/tf_help.h>
|
||||
#include <nav_core2/exceptions.h>
|
||||
#include <pluginlib/class_list_macros.h>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
namespace nav_core_adapter
|
||||
{
|
||||
|
||||
GlobalPlannerAdapter2::GlobalPlannerAdapter2() :
|
||||
planner_loader_("nav_core", "nav_core::BaseGlobalPlanner")
|
||||
{
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Load the nav_core global planner and initialize it
|
||||
*/
|
||||
void GlobalPlannerAdapter2::initialize(const ros::NodeHandle& parent, const std::string& name,
|
||||
TFListenerPtr tf, nav_core2::Costmap::Ptr costmap)
|
||||
{
|
||||
costmap_ = costmap;
|
||||
std::shared_ptr<CostmapAdapter> ptr = std::static_pointer_cast<CostmapAdapter>(costmap);
|
||||
|
||||
if (!ptr)
|
||||
{
|
||||
ROS_FATAL_NAMED("GlobalPlannerAdapter2",
|
||||
"GlobalPlannerAdapter2 can only be used with the CostmapAdapter, not other Costmaps!");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
costmap_ros_ = ptr->getCostmap2DROS();
|
||||
|
||||
ros::NodeHandle planner_nh(parent, name);
|
||||
std::string planner_name;
|
||||
planner_nh.param("planner_name", planner_name, std::string("global_planner/GlobalPlanner"));
|
||||
ROS_INFO_NAMED("GlobalPlannerAdapter2", "Loading plugin %s", planner_name.c_str());
|
||||
planner_ = planner_loader_.createInstance(planner_name);
|
||||
planner_->initialize(planner_loader_.getName(planner_name), costmap_ros_);
|
||||
}
|
||||
|
||||
nav_2d_msgs::Path2D GlobalPlannerAdapter2::makePlan(const nav_2d_msgs::Pose2DStamped& start,
|
||||
const nav_2d_msgs::Pose2DStamped& goal)
|
||||
{
|
||||
geometry_msgs::PoseStamped start3d = nav_2d_utils::pose2DToPoseStamped(start),
|
||||
goal3d = nav_2d_utils::pose2DToPoseStamped(goal);
|
||||
std::vector<geometry_msgs::PoseStamped> plan;
|
||||
bool ret = planner_->makePlan(start3d, goal3d, plan);
|
||||
if (!ret)
|
||||
{
|
||||
throw nav_core2::PlannerException("Generic Global Planner Error");
|
||||
}
|
||||
return nav_2d_utils::posesToPath2D(plan);
|
||||
}
|
||||
} // namespace nav_core_adapter
|
||||
|
||||
|
||||
// register this planner as a GlobalPlanner plugin
|
||||
PLUGINLIB_EXPORT_CLASS(nav_core_adapter::GlobalPlannerAdapter2, nav_core2::GlobalPlanner)
|
||||
190
navigations/nav_core_adapter/src/local_planner_adapter.cpp
Executable file
190
navigations/nav_core_adapter/src/local_planner_adapter.cpp
Executable file
@@ -0,0 +1,190 @@
|
||||
/*
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2017, Locus Robotics
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#include <nav_core_adapter/local_planner_adapter.h>
|
||||
#include <nav_core_adapter/costmap_adapter.h>
|
||||
#include <nav_core_adapter/shared_pointers.h>
|
||||
#include <nav_2d_utils/conversions.h>
|
||||
#include <nav_2d_utils/tf_help.h>
|
||||
#include <nav_core2/exceptions.h>
|
||||
#include <pluginlib/class_list_macros.h>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
namespace nav_core_adapter
|
||||
{
|
||||
|
||||
LocalPlannerAdapter::LocalPlannerAdapter() :
|
||||
planner_loader_("nav_core2", "nav_core2::LocalPlanner")
|
||||
{
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Load the nav_core2 local planner and initialize it
|
||||
*/
|
||||
void LocalPlannerAdapter::initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros)
|
||||
{
|
||||
// ROS_WARN("LocalPlannerAdapter::initialize");
|
||||
tf_ = createSharedPointerWithNoDelete<tf2_ros::Buffer>(tf);
|
||||
costmap_ros_ = costmap_ros;
|
||||
costmap_adapter_ = std::make_shared<CostmapAdapter>();
|
||||
costmap_adapter_->initialize(costmap_ros);
|
||||
|
||||
ros::NodeHandle nh;
|
||||
ros::NodeHandle private_nh("~");
|
||||
ros::NodeHandle adapter_nh("~/" + name);
|
||||
std::string planner_name;
|
||||
adapter_nh.param("planner_name", planner_name, std::string("dwb_local_planner::DWBLocalPlanner"));
|
||||
ROS_INFO_NAMED("LocalPlannerAdapter", "Loading plugin %s", planner_name.c_str());
|
||||
planner_ = planner_loader_.createInstance(planner_name);
|
||||
// From void DWBLocalPlanner::initialize(const ros::NodeHandle& parent, const std::string& name,
|
||||
// TFListenerPtr tf, nav_core2::Costmap::Ptr costmap)
|
||||
planner_->initialize(private_nh, planner_loader_.getName(planner_name), tf_, costmap_adapter_);
|
||||
has_active_goal_ = false;
|
||||
|
||||
odom_sub_ = std::make_shared<nav_2d_utils::OdomSubscriber>(nh);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Collect the additional information needed by nav_core2 and call the child computeVelocityCommands
|
||||
*/
|
||||
bool LocalPlannerAdapter::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
|
||||
{
|
||||
if (!has_active_goal_)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
// Get the Pose
|
||||
nav_2d_msgs::Pose2DStamped pose2d;
|
||||
if (!getRobotPose(pose2d))
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
// Get the Velocity
|
||||
nav_2d_msgs::Twist2D velocity = odom_sub_->getTwist();
|
||||
nav_2d_msgs::Twist2DStamped cmd_vel_2d;
|
||||
try
|
||||
{ // to -> DWBLocalPlanner::computeVelocityCommands()
|
||||
cmd_vel_2d = planner_->computeVelocityCommands(pose2d, velocity);
|
||||
}
|
||||
catch (const nav_core2::PlannerException& e)
|
||||
{
|
||||
ROS_ERROR_NAMED("LocalPlannerAdapter", "computeVelocityCommands exception: %s", e.what());
|
||||
return false;
|
||||
}
|
||||
cmd_vel = nav_2d_utils::twist2Dto3D(cmd_vel_2d.velocity);
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Collect the additional information needed by nav_core2 and call the child isGoalReached
|
||||
*/
|
||||
bool LocalPlannerAdapter::isGoalReached()
|
||||
{
|
||||
// Get the Pose
|
||||
nav_2d_msgs::Pose2DStamped pose2d;
|
||||
if (!getRobotPose(pose2d))
|
||||
return false;
|
||||
|
||||
nav_2d_msgs::Twist2D velocity = odom_sub_->getTwist();
|
||||
bool ret = planner_->isGoalReached(pose2d, velocity);
|
||||
if (ret)
|
||||
{
|
||||
has_active_goal_ = false;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Convert from 2d to 3d and call child setPlan
|
||||
*/
|
||||
bool LocalPlannerAdapter::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan)
|
||||
{
|
||||
nav_2d_msgs::Path2D path = nav_2d_utils::posesToPath2D(orig_global_plan);
|
||||
try
|
||||
{
|
||||
if (path.poses.size() > 0)
|
||||
{
|
||||
nav_2d_msgs::Pose2DStamped goal_pose;
|
||||
goal_pose.header = path.header;
|
||||
goal_pose.pose = path.poses.back();
|
||||
|
||||
if (!has_active_goal_ || hasGoalChanged(goal_pose))
|
||||
{
|
||||
last_goal_ = goal_pose;
|
||||
has_active_goal_ = true;
|
||||
planner_->setGoalPose(goal_pose);
|
||||
}
|
||||
}
|
||||
|
||||
planner_->setPlan(path);
|
||||
return true;
|
||||
}
|
||||
catch (const nav_core2::PlannerException& e)
|
||||
{
|
||||
ROS_ERROR_NAMED("LocalPlannerAdapter", "setPlan Exception: %s", e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool LocalPlannerAdapter::hasGoalChanged(const nav_2d_msgs::Pose2DStamped& new_goal)
|
||||
{
|
||||
if (last_goal_.header.frame_id != new_goal.header.frame_id)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
return last_goal_.pose.x != new_goal.pose.x || last_goal_.pose.y != new_goal.pose.y ||
|
||||
last_goal_.pose.theta != new_goal.pose.theta;
|
||||
}
|
||||
|
||||
bool LocalPlannerAdapter::getRobotPose(nav_2d_msgs::Pose2DStamped& pose2d)
|
||||
{
|
||||
geometry_msgs::PoseStamped current_pose;
|
||||
if (!costmap_ros_->getRobotPose(current_pose))
|
||||
{
|
||||
ROS_ERROR_NAMED("LocalPlannerAdapter", "Could not get robot pose");
|
||||
return false;
|
||||
}
|
||||
pose2d = nav_2d_utils::poseStampedToPose2D(current_pose);
|
||||
return true;
|
||||
}
|
||||
|
||||
} // namespace nav_core_adapter
|
||||
|
||||
// register this planner as a BaseLocalPlanner plugin
|
||||
PLUGINLIB_EXPORT_CLASS(nav_core_adapter::LocalPlannerAdapter, nav_core::BaseLocalPlanner)
|
||||
Reference in New Issue
Block a user