Public Member Functions | Private Member Functions | Private Attributes | List of all members
position Class Reference

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...
 
Raterate
 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...
 

Detailed Description

A class to provide position related functionalities.

Definition at line 16 of file position.h.

Constructor & Destructor Documentation

position::position ( double  altitude)

Constructor that initializes the private member variables.

Parameters
altitudeThe 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.

Member Function Documentation

double position::bearing ( geometry_msgs::Pose  p) const

Compute the bearing from the current pose of the CPS to a given pose.

Parameters
pThe pose to compute bearing of.
Returns
The bearing of the given pose relative to the current yaw of the CPS, counterclockwise.

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.

Parameters
distanceThe distance of the goal from the current position.
directionThe direction of the goal relative to the current position. It is in radian, counterclockwise starting from east / x-axis.
Returns
The goal pose.

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.

Parameters
startThe starting position.
distanceThe distance of the goal from start.
directionThe direction of the goal relative to start. It is in radian, counterclockwise starting from east / x-axis.
Returns
The goal pose.

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.

Parameters
pThe pose to compute distance to.
Returns
The distance in meters.

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.

Parameters
p1First pose.
p2Second pose.
Returns
The distance in meters.

Definition at line 81 of file position.cpp.

geometry_msgs::Pose position::get_pose ( ) const

Get the current pose of the CPS.

Returns
The current pose of the CPS in local coordinates.

Definition at line 86 of file position.cpp.

double position::get_tolerance ( ) const

Get the position tolerance.

Returns
The distance in meter that the CPS can be away from a goal while still being considered to have reached that goal.

Definition at line 91 of file position.cpp.

double position::get_yaw ( ) const

Get the current yaw orientation of the CPS.

Returns
The current yaw angle of the CPS counterclockwise starting from x-axis/east.

Definition at line 96 of file position.cpp.

double position::get_yaw ( geometry_msgs::Pose  pose) const
private

Get the yaw orientation from a pose.

Parameters
poseThe pose that contains the orientation.
Returns
The yaw angle of the given pose counterclockwise starting from x-axis/east.

Definition at line 217 of file position.cpp.

bool position::move ( geometry_msgs::Pose  pose)

Move the CPS to the given pose.

Parameters
poseThe position to move to.
Returns
Whether the CPS reached the goal position.

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.

Parameters
poseThe pose to check.
Returns
True, if there is an obstacle in the direction of the pose, false otherwise.

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.

Parameters
poseThe pose to check.
Returns
True, if the given pose is outside the mission area or it could not be checked, false otherwise.

Definition at line 164 of file position.cpp.

void position::pose_callback ( const geometry_msgs::PoseStamped::ConstPtr &  msg)
private

Callback function for position updates.

Parameters
msgPosition received from the CPS.

Definition at line 224 of file position.cpp.

bool position::reached ( )

Check whether the CPS has reached the current goal.

Returns
True if the CPS is close to the current goal, false otherwise.

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.

Member Data Documentation

double position::altitude
private

The altitude at which the CPS operates.

Definition at line 201 of file position.h.

geometry_msgs::PoseStamped position::goal
private

Current goal of the CPS.

Definition at line 176 of file position.h.

double position::goal_tolerance
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.

Duration position::move_timeout
private

The time in seconds that reaching a waypoint is allowed to take.

Definition at line 191 of file position.h.

NodeHandle position::nh
private

A node handle for the main ROS node.

Definition at line 161 of file position.h.

ServiceClient position::occupied_sector_client
private

Service client for determining the sector occupied by obstacles.

Definition at line 146 of file position.h.

ServiceClient position::out_of_bounds_client
private

Service client for determining whether the goal is out of the area bounds.

Definition at line 141 of file position.h.

geometry_msgs::Pose position::pose
private

Current position of the CPS.

Definition at line 171 of file position.h.

Publisher position::pose_pub
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.

Subscriber position::pose_sub
private

Subscriber for the position of the CPS.

Definition at line 136 of file position.h.

bool position::pose_valid
private

Whether a valid position has been received.

Definition at line 181 of file position.h.

Rate* position::rate
private

The loop rate object for running the behavior control loops at a specific frequency.

Definition at line 166 of file position.h.

bool position::visualize
private

Whether to publish the goal waypoint on a topic for visualization.

Definition at line 196 of file position.h.

Publisher position::visualize_pub
private

Publisher to visualize the current goal.

Definition at line 156 of file position.h.


The documentation for this class was generated from the following files:


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