35 #ifndef NAV_CORE_ADAPTER_LOCAL_PLANNER_ADAPTER_H 36 #define NAV_CORE_ADAPTER_LOCAL_PLANNER_ADAPTER_H 63 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& plan)
override;
84 std::shared_ptr<nav_2d_utils::OdomSubscriber>
odom_sub_;
99 #endif // NAV_CORE_ADAPTER_LOCAL_PLANNER_ADAPTER_H
bool hasGoalChanged(const nav_2d_msgs::Pose2DStamped &new_goal)
See if the back of the global plan matches the most recent goal pose.
std::shared_ptr< CostmapAdapter > costmap_adapter_
costmap_2d::Costmap2DROS * costmap_ros_
std::shared_ptr< nav_2d_utils::OdomSubscriber > odom_sub_
helper class for subscribing to odometry
bool isGoalReached() override
Collect the additional information needed by nav_core2 and call the child isGoalReached.
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel) override
Collect the additional information needed by nav_core2 and call the child computeVelocityCommands.
nav_2d_msgs::Pose2DStamped last_goal_
bool getRobotPose(nav_2d_msgs::Pose2DStamped &pose2d)
Get the robot pose from the costmap and store as Pose2DStamped.
used for employing a nav_core2 local planner (such as dwb) as a nav_core plugin, like in move_base...
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan) override
Convert from 2d to 3d and call child setPlan.
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) override
Load the nav_core2 local planner and initialize it.
std::shared_ptr< tf::TransformListener > TFListenerPtr
boost::shared_ptr< nav_core2::LocalPlanner > planner_
pluginlib::ClassLoader< nav_core2::LocalPlanner > planner_loader_