A class to provide position related functionalities. More...
#include <position.h>
Public Member Functions | |
double | bearing (geometry_msgs::Pose p) const |
Compute the bearing from the current pose of the CPS to a given pose. More... | |
geometry_msgs::Pose | compute_goal (double distance, double direction) const |
Compute the goal coordinates relative to the current position. More... | |
geometry_msgs::Pose | compute_goal (geometry_msgs::Pose start, double distance, double direction) const |
Compute the goal coordinates relative to a given start position. More... | |
double | dist (geometry_msgs::Pose p) const |
Compute the straight-line distance from the current position to the given position. More... | |
double | dist (geometry_msgs::Pose p1, geometry_msgs::Pose p2) const |
Compute the straight-line distance between two positions. More... | |
geometry_msgs::Pose | get_pose () const |
Get the current pose of the CPS. More... | |
double | get_tolerance () const |
Get the position tolerance. More... | |
double | get_yaw () const |
Get the current yaw orientation of the CPS. More... | |
bool | move (geometry_msgs::Pose pose) |
Move the CPS to the given pose. More... | |
bool | occupied (geometry_msgs::Pose pose) |
Check whether there is an obstacle in the direction of the given pose. More... | |
bool | out_of_bounds (geometry_msgs::Pose pose) |
Check whether a given pose is out of the mission area boundaries. More... | |
position (double altitude) | |
Constructor that initializes the private member variables. More... | |
bool | reached () |
Check whether the CPS has reached the current goal. More... | |
void | stop () |
Stop moving by publishing the current position as goal. More... | |
~position () | |
Destructor that deletes the private member objects. More... | |
Private Member Functions | |
double | get_yaw (geometry_msgs::Pose pose) const |
Get the yaw orientation from a pose. More... | |
void | pose_callback (const geometry_msgs::PoseStamped::ConstPtr &msg) |
Callback function for position updates. More... | |
Private Attributes | |
double | altitude |
The altitude at which the CPS operates. More... | |
geometry_msgs::PoseStamped | goal |
Current goal of the CPS. More... | |
double | goal_tolerance |
The distance that the CPS can be away from a goal while still being considered to have reached that goal. More... | |
Duration | move_timeout |
The time in seconds that reaching a waypoint is allowed to take. More... | |
NodeHandle | nh |
A node handle for the main ROS node. More... | |
ServiceClient | occupied_sector_client |
Service client for determining the sector occupied by obstacles. More... | |
ServiceClient | out_of_bounds_client |
Service client for determining whether the goal is out of the area bounds. More... | |
geometry_msgs::Pose | pose |
Current position of the CPS. More... | |
Publisher | pose_pub |
Publisher for sending the goal position of the CPS to the position controller in the abstraction library. More... | |
Subscriber | pose_sub |
Subscriber for the position of the CPS. More... | |
bool | pose_valid |
Whether a valid position has been received. More... | |
Rate * | rate |
The loop rate object for running the behavior control loops at a specific frequency. More... | |
bool | visualize |
Whether to publish the goal waypoint on a topic for visualization. More... | |
Publisher | visualize_pub |
Publisher to visualize the current goal. More... | |
A class to provide position related functionalities.
Definition at line 16 of file position.h.
position::position | ( | double | altitude | ) |
Constructor that initializes the private member variables.
altitude | The altitude at which the CPS operates. |
Definition at line 3 of file position.cpp.
position::~position | ( | ) |
Destructor that deletes the private member objects.
Definition at line 41 of file position.cpp.
double position::bearing | ( | geometry_msgs::Pose | p | ) | const |
Compute the bearing from the current pose of the CPS to a given pose.
p | The pose to compute bearing of. |
Definition at line 46 of file position.cpp.
geometry_msgs::Pose position::compute_goal | ( | double | distance, |
double | direction | ||
) | const |
Compute the goal coordinates relative to the current position.
distance | The distance of the goal from the current position. |
direction | The direction of the goal relative to the current position. It is in radian, counterclockwise starting from east / x-axis. |
Definition at line 54 of file position.cpp.
geometry_msgs::Pose position::compute_goal | ( | geometry_msgs::Pose | start, |
double | distance, | ||
double | direction | ||
) | const |
Compute the goal coordinates relative to a given start position.
start | The starting position. |
distance | The distance of the goal from start. |
direction | The direction of the goal relative to start. It is in radian, counterclockwise starting from east / x-axis. |
Definition at line 59 of file position.cpp.
double position::dist | ( | geometry_msgs::Pose | p | ) | const |
Compute the straight-line distance from the current position to the given position.
p | The pose to compute distance to. |
Definition at line 76 of file position.cpp.
double position::dist | ( | geometry_msgs::Pose | p1, |
geometry_msgs::Pose | p2 | ||
) | const |
Compute the straight-line distance between two positions.
p1 | First pose. |
p2 | Second pose. |
Definition at line 81 of file position.cpp.
geometry_msgs::Pose position::get_pose | ( | ) | const |
Get the current pose of the CPS.
Definition at line 86 of file position.cpp.
double position::get_tolerance | ( | ) | const |
Get the position tolerance.
Definition at line 91 of file position.cpp.
double position::get_yaw | ( | ) | const |
Get the current yaw orientation of the CPS.
Definition at line 96 of file position.cpp.
|
private |
Get the yaw orientation from a pose.
pose | The pose that contains the orientation. |
Definition at line 217 of file position.cpp.
bool position::move | ( | geometry_msgs::Pose | pose | ) |
Move the CPS to the given pose.
pose | The position to move to. |
Definition at line 101 of file position.cpp.
bool position::occupied | ( | geometry_msgs::Pose | pose | ) |
Check whether there is an obstacle in the direction of the given pose.
pose | The pose to check. |
Definition at line 141 of file position.cpp.
bool position::out_of_bounds | ( | geometry_msgs::Pose | pose | ) |
Check whether a given pose is out of the mission area boundaries.
pose | The pose to check. |
Definition at line 164 of file position.cpp.
|
private |
Callback function for position updates.
msg | Position received from the CPS. |
Definition at line 224 of file position.cpp.
bool position::reached | ( | ) |
Check whether the CPS has reached the current goal.
Definition at line 177 of file position.cpp.
void position::stop | ( | ) |
Stop moving by publishing the current position as goal.
Definition at line 202 of file position.cpp.
|
private |
The altitude at which the CPS operates.
Definition at line 201 of file position.h.
|
private |
Current goal of the CPS.
Definition at line 176 of file position.h.
|
private |
The distance that the CPS can be away from a goal while still being considered to have reached that goal.
Definition at line 186 of file position.h.
|
private |
The time in seconds that reaching a waypoint is allowed to take.
Definition at line 191 of file position.h.
|
private |
A node handle for the main ROS node.
Definition at line 161 of file position.h.
|
private |
Service client for determining the sector occupied by obstacles.
Definition at line 146 of file position.h.
|
private |
Service client for determining whether the goal is out of the area bounds.
Definition at line 141 of file position.h.
|
private |
Current position of the CPS.
Definition at line 171 of file position.h.
|
private |
Publisher for sending the goal position of the CPS to the position controller in the abstraction library.
Definition at line 151 of file position.h.
|
private |
Subscriber for the position of the CPS.
Definition at line 136 of file position.h.
|
private |
Whether a valid position has been received.
Definition at line 181 of file position.h.
|
private |
The loop rate object for running the behavior control loops at a specific frequency.
Definition at line 166 of file position.h.
|
private |
Whether to publish the goal waypoint on a topic for visualization.
Definition at line 196 of file position.h.
|
private |
Publisher to visualize the current goal.
Definition at line 156 of file position.h.