position.h
Go to the documentation of this file.
1 #ifndef POSITION_H
2 #define POSITION_H
3 
4 #include <ros/ros.h>
5 #include <tf2/utils.h>
6 #include <geometry_msgs/Pose.h>
7 #include <cpswarm_msgs/OutOfBounds.h>
8 #include <cpswarm_msgs/GetSector.h>
9 
10 using namespace std;
11 using namespace ros;
12 
16 class position
17 {
18 public:
23  position (double altitude);
24 
28  ~position ();
29 
35  double bearing (geometry_msgs::Pose p) const;
36 
43  geometry_msgs::Pose compute_goal (double distance, double direction) const;
44 
52  geometry_msgs::Pose compute_goal (geometry_msgs::Pose start, double distance, double direction) const;
53 
59  double dist (geometry_msgs::Pose p) const;
60 
67  double dist (geometry_msgs::Pose p1, geometry_msgs::Pose p2) const;
68 
73  geometry_msgs::Pose get_pose () const;
74 
79  double get_tolerance () const;
80 
85  double get_yaw () const;
86 
92  bool move (geometry_msgs::Pose pose);
93 
99  bool occupied (geometry_msgs::Pose pose);
100 
106  bool out_of_bounds (geometry_msgs::Pose pose);
107 
112  bool reached ();
113 
117  void stop ();
118 
119 private:
125  double get_yaw (geometry_msgs::Pose pose) const;
126 
131  void pose_callback (const geometry_msgs::PoseStamped::ConstPtr& msg);
132 
137 
142 
147 
152 
157 
162 
167 
171  geometry_msgs::Pose pose;
172 
176  geometry_msgs::PoseStamped goal;
177 
182 
187 
192 
196  bool visualize;
197 
201  double altitude;
202 };
203 
204 #endif // POSITION_H
Publisher visualize_pub
Publisher to visualize the current goal.
Definition: position.h:156
double altitude
The altitude at which the CPS operates.
Definition: position.h:201
NodeHandle nh
A node handle for the main ROS node.
Definition: position.h:161
ROSCPP_DECL void start()
Rate * rate
The loop rate object for running the behavior control loops at a specific frequency.
Definition: position.h:166
bool pose_valid
Whether a valid position has been received.
Definition: position.h:181
geometry_msgs::PoseStamped goal
Current goal of the CPS.
Definition: position.h:176
geometry_msgs::Pose pose
Current position of the CPS.
Definition: position.h:171
double goal_tolerance
The distance that the CPS can be away from a goal while still being considered to have reached that g...
Definition: position.h:186
A class to provide position related functionalities.
Definition: position.h:16
Publisher pose_pub
Publisher for sending the goal position of the CPS to the position controller in the abstraction libr...
Definition: position.h:151
ServiceClient occupied_sector_client
Service client for determining the sector occupied by obstacles.
Definition: position.h:146
Subscriber pose_sub
Subscriber for the position of the CPS.
Definition: position.h:136
ServiceClient out_of_bounds_client
Service client for determining whether the goal is out of the area bounds.
Definition: position.h:141
bool visualize
Whether to publish the goal waypoint on a topic for visualization.
Definition: position.h:196
Duration move_timeout
The time in seconds that reaching a waypoint is allowed to take.
Definition: position.h:191


swarm_behaviors_position
Author(s):
autogenerated on Sat Feb 6 2021 03:11:33