6 #include <geometry_msgs/Pose.h> 7 #include <cpswarm_msgs/OutOfBounds.h> 8 #include <cpswarm_msgs/GetSector.h> 35 double bearing (geometry_msgs::Pose p)
const;
43 geometry_msgs::Pose compute_goal (
double distance,
double direction)
const;
52 geometry_msgs::Pose compute_goal (geometry_msgs::Pose
start,
double distance,
double direction)
const;
59 double dist (geometry_msgs::Pose p)
const;
67 double dist (geometry_msgs::Pose p1, geometry_msgs::Pose p2)
const;
73 geometry_msgs::Pose get_pose ()
const;
79 double get_tolerance ()
const;
85 double get_yaw ()
const;
92 bool move (geometry_msgs::Pose pose);
99 bool occupied (geometry_msgs::Pose pose);
106 bool out_of_bounds (geometry_msgs::Pose pose);
125 double get_yaw (geometry_msgs::Pose pose)
const;
131 void pose_callback (
const geometry_msgs::PoseStamped::ConstPtr& msg);
176 geometry_msgs::PoseStamped
goal;
Publisher visualize_pub
Publisher to visualize the current goal.
double altitude
The altitude at which the CPS operates.
NodeHandle nh
A node handle for the main ROS node.
Rate * rate
The loop rate object for running the behavior control loops at a specific frequency.
bool pose_valid
Whether a valid position has been received.
geometry_msgs::PoseStamped goal
Current goal of the CPS.
geometry_msgs::Pose pose
Current position of the CPS.
double goal_tolerance
The distance that the CPS can be away from a goal while still being considered to have reached that g...
A class to provide position related functionalities.
Publisher pose_pub
Publisher for sending the goal position of the CPS to the position controller in the abstraction libr...
ServiceClient occupied_sector_client
Service client for determining the sector occupied by obstacles.
Subscriber pose_sub
Subscriber for the position of the CPS.
ServiceClient out_of_bounds_client
Service client for determining whether the goal is out of the area bounds.
bool visualize
Whether to publish the goal waypoint on a topic for visualization.
Duration move_timeout
The time in seconds that reaching a waypoint is allowed to take.