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

A class to provide velocity related functionalities. More...

#include <velocity.h>

Public Member Functions

geometry_msgs::Vector3 compute_velocity (geometry_msgs::Point goal, double velocity)
 Compute the velocity vector required to reach a goal point from the current position while traveling with a given maximum velocity. More...
 
geometry_msgs::Vector3 get_velocity () const
 Get the current velocity of the CPS. More...
 
void move (geometry_msgs::Vector3 velocity)
 Move the CPS with a given velocity. More...
 
cpswarm_msgs::Vector rel_velocity (geometry_msgs::Vector3 v) const
 Compute the velocity difference of the CPS to a given velocity. More...
 
 velocity (double altitude)
 Constructor that initializes the private member variables. More...
 
 ~velocity ()
 Destructor that deletes the private member objects. More...
 

Private Member Functions

void vel_callback (const geometry_msgs::TwistStamped::ConstPtr &msg)
 Callback function for velocity updates. More...
 

Private Attributes

geometry_msgs::Twist current_vel
 Current velocity of the CPS. More...
 
NodeHandle nh
 A node handle for the main ROS node. More...
 
position pos
 A helper object for position related tasks. More...
 
Raterate
 The loop rate object for running the behavior control loops at a specific frequency. More...
 
Publisher vel_pub
 Publisher for sending the target velocity of the CPS to the velocity controller in the abstraction library. More...
 
Subscriber vel_sub
 Subscriber for the velocity of the CPS. More...
 
bool vel_valid
 Whether a valid velocity has been received. More...
 

Detailed Description

A class to provide velocity related functionalities.

Definition at line 18 of file velocity.h.

Constructor & Destructor Documentation

velocity::velocity ( double  altitude)

Constructor that initializes the private member variables.

Parameters
altitudeThe altitude at which the CPS operates.

Definition at line 3 of file velocity.cpp.

velocity::~velocity ( )

Destructor that deletes the private member objects.

Definition at line 26 of file velocity.cpp.

Member Function Documentation

geometry_msgs::Vector3 velocity::compute_velocity ( geometry_msgs::Point  goal,
double  velocity 
)

Compute the velocity vector required to reach a goal point from the current position while traveling with a given maximum velocity.

Parameters
goalThe goal coordinates.
velocityThe velocity magnitude.
Returns
The linear velocity vector that moves the CPS in the direction of the goal point.

Definition at line 31 of file velocity.cpp.

geometry_msgs::Vector3 velocity::get_velocity ( ) const

Get the current velocity of the CPS.

Returns
The current linear velocity of the CPS.

Definition at line 54 of file velocity.cpp.

void velocity::move ( geometry_msgs::Vector3  velocity)

Move the CPS with a given velocity.

/**

Parameters
velocityThe velocity at which the CPS shall move.

Definition at line 59 of file velocity.cpp.

cpswarm_msgs::Vector velocity::rel_velocity ( geometry_msgs::Vector3  v) const

Compute the velocity difference of the CPS to a given velocity.

Parameters
vThe velocity to compare.
Returns
The velocity relative to the current velocity of the CPS as magnitude and direction.

Definition at line 69 of file velocity.cpp.

void velocity::vel_callback ( const geometry_msgs::TwistStamped::ConstPtr &  msg)
private

Callback function for velocity updates.

Parameters
msgVelocity received from the CPS FCU.

Definition at line 84 of file velocity.cpp.

Member Data Documentation

geometry_msgs::Twist velocity::current_vel
private

Current velocity of the CPS.

Definition at line 94 of file velocity.h.

NodeHandle velocity::nh
private

A node handle for the main ROS node.

Definition at line 69 of file velocity.h.

position velocity::pos
private

A helper object for position related tasks.

Definition at line 89 of file velocity.h.

Rate* velocity::rate
private

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

Definition at line 84 of file velocity.h.

Publisher velocity::vel_pub
private

Publisher for sending the target velocity of the CPS to the velocity controller in the abstraction library.

Definition at line 79 of file velocity.h.

Subscriber velocity::vel_sub
private

Subscriber for the velocity of the CPS.

Definition at line 74 of file velocity.h.

bool velocity::vel_valid
private

Whether a valid velocity has been received.

Definition at line 99 of file velocity.h.


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


swarm_behaviors_velocity
Author(s):
autogenerated on Sat Feb 6 2021 03:11:35