SMACC
Loading...
Searching...
No Matches
forward_global_planner.h
Go to the documentation of this file.
1/*****************************************************************************************************************
2 * ReelRobotix Inc. - Software License Agreement Copyright (c) 2018
3 * Authors: Pablo Inigo Blasco, Brett Aldrich
4 *
5 ******************************************************************************************************************/
6#pragma once
7#include <nav_core/base_global_planner.h>
8#include <nav_msgs/GetPlan.h>
9#include <nav_msgs/Path.h>
10#include <ros/ros.h>
11
12namespace cl_move_base_z
13{
14namespace forward_global_planner
15{
16class ForwardGlobalPlanner : public nav_core::BaseGlobalPlanner
17{
18public:
20
21 bool makePlan(const geometry_msgs::PoseStamped &start,
22 const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan);
23
24 bool makePlan(const geometry_msgs::PoseStamped &start,
25 const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan,
26 double &cost);
27
28 void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros_);
29
30private:
31 ros::NodeHandle nh_;
32
33 ros::Publisher planPub_;
34
36 costmap_2d::Costmap2DROS *costmap_ros_;
37
39
40 double puresSpinningRadStep_; // rads
41};
42} // namespace forward_global_planner
43} // namespace cl_move_base_z
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros_)
costmap_2d::Costmap2DROS * costmap_ros_
stored but almost not used
bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)