RobotNavigator.h
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <nav_msgs/GetMap.h>
3 #include <std_srvs/Trigger.h>
7 #include <nav2d_navigator/MoveToPosition2DAction.h>
8 #include <nav2d_navigator/ExploreAction.h>
9 #include <nav2d_navigator/GetFirstMapAction.h>
10 #include <nav2d_navigator/LocalizeAction.h>
11 
16 
17 #include <queue>
18 
24 
26 {
27 public:
30 
31  bool receiveStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
32  bool receivePause(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
33  void receiveMoveGoal(const nav2d_navigator::MoveToPosition2DGoal::ConstPtr &goal);
34  void receiveExploreGoal(const nav2d_navigator::ExploreGoal::ConstPtr &goal);
35  void receiveGetMapGoal(const nav2d_navigator::GetFirstMapGoal::ConstPtr &goal);
36  void receiveLocalizeGoal(const nav2d_navigator::LocalizeGoal::ConstPtr &goal);
37 
38 private:
39  bool isLocalized();
40  bool setCurrentPosition();
41  bool getMap();
42  void stop();
43  bool correctGoalPose();
44  bool generateCommand();
45  bool preparePlan();
46  bool createPlan();
47  void publishPlan();
48 
49  // Everything related to ROS
58 
59  std::string mMapFrame;
60  std::string mRobotFrame;
61  std::string mMoveActionTopic;
62  std::string mExploreActionTopic;
63  std::string mGetMapActionTopic;
64  std::string mLocalizeActionTopic;
65 
70 
72 
73  // Current status and goals
74  bool mHasNewMap;
75  bool mIsPaused;
76  bool mIsStopped;
77  int mStatus;
78  int mRobotID;
79  unsigned int mGoalPoint;
80  unsigned int mStartPoint;
84 
85  // Everything related to the global map and plan
87  std::string mExplorationStrategy;
90  double* mCurrentPlan;
91 
92  double mFrequency;
94  double mRobotRadius;
95  unsigned int mCellInflationRadius;
96  unsigned int mCellRobotRadius;
97 
98  signed char mCostObstacle;
99  signed char mCostLethal;
100 
108 };
RobotNavigator::mIsPaused
bool mIsPaused
Definition: RobotNavigator.h:75
GetMapActionServer
actionlib::SimpleActionServer< nav2d_navigator::GetFirstMapAction > GetMapActionServer
Definition: RobotNavigator.h:21
ros::Publisher
RobotNavigator::mCommandTargetDistance
double mCommandTargetDistance
Definition: RobotNavigator.h:101
RobotNavigator::mCellInflationRadius
unsigned int mCellInflationRadius
Definition: RobotNavigator.h:95
class_loader.h
boost::shared_ptr< ExplorationPlanner >
RobotNavigator
Definition: RobotNavigator.h:25
GridMap
Definition: GridMap.h:7
RobotNavigator::mCurrentMap
GridMap mCurrentMap
Definition: RobotNavigator.h:89
ros.h
RobotNavigator::mInflationTool
MapInflationTool mInflationTool
Definition: RobotNavigator.h:86
RobotNavigator::preparePlan
bool preparePlan()
Definition: RobotNavigator.cpp:174
RobotNavigator::isLocalized
bool isLocalized()
Definition: RobotNavigator.cpp:921
RobotNavigator::mRobotRadius
double mRobotRadius
Definition: RobotNavigator.h:94
MoveActionServer
actionlib::SimpleActionServer< nav2d_navigator::MoveToPosition2DAction > MoveActionServer
Definition: RobotNavigator.h:19
RobotNavigator::receiveStop
bool receiveStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: RobotNavigator.cpp:143
RobotNavigator::mExplorationStrategy
std::string mExplorationStrategy
Definition: RobotNavigator.h:87
ExploreActionServer
actionlib::SimpleActionServer< nav2d_navigator::ExploreAction > ExploreActionServer
Definition: RobotNavigator.h:20
RobotNavigator::createPlan
bool createPlan()
Definition: RobotNavigator.cpp:197
RobotNavigator::mIsStopped
bool mIsStopped
Definition: RobotNavigator.h:76
RobotNavigator::mMoveActionServer
MoveActionServer * mMoveActionServer
Definition: RobotNavigator.h:66
RobotNavigator::mGetMapClient
ros::ServiceClient mGetMapClient
Definition: RobotNavigator.h:51
simple_action_server.h
RobotNavigator::mMaxReplanningPeriod
double mMaxReplanningPeriod
Definition: RobotNavigator.h:107
RobotNavigator::mInflationRadius
double mInflationRadius
Definition: RobotNavigator.h:93
RobotNavigator::mStopServer
ros::ServiceServer mStopServer
Definition: RobotNavigator.h:56
RobotNavigator::~RobotNavigator
~RobotNavigator()
Definition: RobotNavigator.cpp:99
RobotNavigator::mPauseServer
ros::ServiceServer mPauseServer
Definition: RobotNavigator.h:57
RobotNavigator::mCurrentPositionY
double mCurrentPositionY
Definition: RobotNavigator.h:83
RobotNavigator::mCostObstacle
signed char mCostObstacle
Definition: RobotNavigator.h:98
RobotNavigator::mNavigationGoalDistance
double mNavigationGoalDistance
Definition: RobotNavigator.h:102
ros::ServiceServer
RobotNavigator::mExploreActionServer
ExploreActionServer * mExploreActionServer
Definition: RobotNavigator.h:67
RobotNavigator::generateCommand
bool generateCommand()
Definition: RobotNavigator.cpp:419
RobotNavigator::setCurrentPosition
bool setCurrentPosition()
Definition: RobotNavigator.cpp:926
RobotNavigator::mMinReplanningPeriod
double mMinReplanningPeriod
Definition: RobotNavigator.h:106
RobotNavigator::mPlanLoader
PlanLoader * mPlanLoader
Definition: RobotNavigator.h:71
RobotNavigator::mMoveActionTopic
std::string mMoveActionTopic
Definition: RobotNavigator.h:61
RobotNavigator::RobotNavigator
RobotNavigator()
Definition: RobotNavigator.cpp:16
RobotNavigator::mMarkerPublisher
ros::Publisher mMarkerPublisher
Definition: RobotNavigator.h:55
RobotNavigator::mRobotFrame
std::string mRobotFrame
Definition: RobotNavigator.h:60
RobotNavigator::mCurrentDirection
double mCurrentDirection
Definition: RobotNavigator.h:81
GridMap.h
RobotNavigator::mNavigationHomingDistance
double mNavigationHomingDistance
Definition: RobotNavigator.h:104
RobotNavigator::mHasNewMap
bool mHasNewMap
Definition: RobotNavigator.h:74
RobotNavigator::mLocalizeActionTopic
std::string mLocalizeActionTopic
Definition: RobotNavigator.h:64
RobotNavigator::mGoalPoint
unsigned int mGoalPoint
Definition: RobotNavigator.h:79
RobotNavigator::mTfListener
tf::TransformListener mTfListener
Definition: RobotNavigator.h:50
ros::ServiceClient
RobotNavigator::mLocalizeActionServer
LocalizeActionServer * mLocalizeActionServer
Definition: RobotNavigator.h:69
RobotNavigator::getMap
bool getMap()
Definition: RobotNavigator.cpp:109
LocalizeActionServer
actionlib::SimpleActionServer< nav2d_navigator::LocalizeAction > LocalizeActionServer
Definition: RobotNavigator.h:22
pluginlib::ClassLoader
MapInflationTool
Definition: MapInflationTool.h:24
RobotNavigator::mRobotID
int mRobotID
Definition: RobotNavigator.h:78
RobotNavigator::mNavigationGoalAngle
double mNavigationGoalAngle
Definition: RobotNavigator.h:103
RobotNavigator::mExploreActionTopic
std::string mExploreActionTopic
Definition: RobotNavigator.h:62
RobotNavigator::receiveLocalizeGoal
void receiveLocalizeGoal(const nav2d_navigator::LocalizeGoal::ConstPtr &goal)
Definition: RobotNavigator.cpp:582
RobotNavigator::receiveMoveGoal
void receiveMoveGoal(const nav2d_navigator::MoveToPosition2DGoal::ConstPtr &goal)
Definition: RobotNavigator.cpp:636
transform_listener.h
RobotNavigator::receivePause
bool receivePause(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: RobotNavigator.cpp:151
RobotNavigator::mCellRobotRadius
unsigned int mCellRobotRadius
Definition: RobotNavigator.h:96
RobotNavigator::mFrequency
double mFrequency
Definition: RobotNavigator.h:92
RobotNavigator::mGoalSubscriber
ros::Subscriber mGoalSubscriber
Definition: RobotNavigator.h:52
RobotNavigator::mStartPoint
unsigned int mStartPoint
Definition: RobotNavigator.h:80
ExplorationPlanner.h
RobotNavigator::mCurrentPositionX
double mCurrentPositionX
Definition: RobotNavigator.h:82
RobotNavigator::correctGoalPose
bool correctGoalPose()
Definition: RobotNavigator.cpp:357
actionlib::SimpleActionServer
RobotNavigator::mGetMapActionTopic
std::string mGetMapActionTopic
Definition: RobotNavigator.h:63
RobotNavigator::mCurrentPlan
double * mCurrentPlan
Definition: RobotNavigator.h:90
MapInflationTool.h
RobotNavigator::mMapFrame
std::string mMapFrame
Definition: RobotNavigator.h:59
RobotNavigator::mPlanPublisher
ros::Publisher mPlanPublisher
Definition: RobotNavigator.h:53
RobotNavigator::mExplorationGoalDistance
double mExplorationGoalDistance
Definition: RobotNavigator.h:105
tf::TransformListener
RobotNavigator::receiveGetMapGoal
void receiveGetMapGoal(const nav2d_navigator::GetFirstMapGoal::ConstPtr &goal)
Definition: RobotNavigator.cpp:491
RobotNavigator::mCommandPublisher
ros::Publisher mCommandPublisher
Definition: RobotNavigator.h:54
PlanLoader
pluginlib::ClassLoader< ExplorationPlanner > PlanLoader
Definition: RobotNavigator.h:23
RobotNavigator::publishPlan
void publishPlan()
Definition: RobotNavigator.cpp:312
RobotNavigator::mStatus
int mStatus
Definition: RobotNavigator.h:77
commands.h
RobotNavigator::mCostLethal
signed char mCostLethal
Definition: RobotNavigator.h:99
RobotNavigator::mExplorationPlanner
boost::shared_ptr< ExplorationPlanner > mExplorationPlanner
Definition: RobotNavigator.h:88
RobotNavigator::stop
void stop()
Definition: RobotNavigator.cpp:408
RobotNavigator::mGetMapActionServer
GetMapActionServer * mGetMapActionServer
Definition: RobotNavigator.h:68
ros::Subscriber
RobotNavigator::receiveExploreGoal
void receiveExploreGoal(const nav2d_navigator::ExploreGoal::ConstPtr &goal)
Definition: RobotNavigator.cpp:792


nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:37