Typedefs | Functions | Variables
target_monitor.cpp File Reference
#include <ros/ros.h>
#include <tf2/utils.h>
#include <actionlib/server/simple_action_server.h>
#include <geometry_msgs/Pose.h>
#include <cpswarm_msgs/TaskAllocatedEvent.h>
#include <cpswarm_msgs/TargetPositionEvent.h>
#include <cpswarm_msgs/TargetTracking.h>
#include <cpswarm_msgs/TargetAction.h>
#include "lib/targets.h"
Include dependency graph for target_monitor.cpp:

Go to the source code of this file.

Typedefs

typedef actionlib::SimpleActionServer< cpswarm_msgs::TargetAction > action_server_t
 An action server type that allows to set the state of a target. More...
 

Functions

void assigned_callback (const cpswarm_msgs::TaskAllocatedEvent::ConstPtr &msg)
 Callback function to receive information about targets assigned to a CPSs. More...
 
void done_callback (const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
 Callback function for incoming target done events. More...
 
void found_callback (const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
 Callback function to receive information about targets found by other CPSs. More...
 
void lost_callback (const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
 Callback function to receive information about targets lost by other CPSs. More...
 
int main (int argc, char **argv)
 Main function to be executed by ROS. More...
 
void pose_callback (const geometry_msgs::PoseStamped::ConstPtr &msg)
 Callback function for position updates. More...
 
geometry_msgs::Quaternion rotate (geometry_msgs::Quaternion rotation)
 Compute the orientation resulting from the rotated CPS orientation. More...
 
void set_done (const cpswarm_msgs::TargetGoalConstPtr &goal, action_server_t *as)
 Callback of the action server which sets the target state to done. More...
 
void tracking_callback (const cpswarm_msgs::TargetTracking::ConstPtr &msg)
 Callback function for target position. More...
 
void update_callback (const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
 Callback function to receive updated information about targets from other CPSs. More...
 
double yaw ()
 Compute the current yaw orientation of the CPS. More...
 

Variables

targetsmonitor
 The targets being monitored. More...
 
geometry_msgs::Pose pose
 Current position of the CPS. More...
 
bool pose_valid
 Whether a valid position has been received. More...
 

Typedef Documentation

typedef actionlib::SimpleActionServer<cpswarm_msgs::TargetAction> action_server_t

An action server type that allows to set the state of a target.

Definition at line 17 of file target_monitor.cpp.

Function Documentation

void assigned_callback ( const cpswarm_msgs::TaskAllocatedEvent::ConstPtr &  msg)

Callback function to receive information about targets assigned to a CPSs.

Parameters
msgID and position of target.

Definition at line 102 of file target_monitor.cpp.

void done_callback ( const cpswarm_msgs::TargetPositionEvent::ConstPtr &  msg)

Callback function for incoming target done events.

Parameters
msgID and last position of target.

Definition at line 124 of file target_monitor.cpp.

void found_callback ( const cpswarm_msgs::TargetPositionEvent::ConstPtr &  msg)

Callback function to receive information about targets found by other CPSs.

Parameters
msgID and position of target.

Definition at line 84 of file target_monitor.cpp.

void lost_callback ( const cpswarm_msgs::TargetPositionEvent::ConstPtr &  msg)

Callback function to receive information about targets lost by other CPSs.

Parameters
msgID and last known position of target.

Definition at line 115 of file target_monitor.cpp.

int main ( int  argc,
char **  argv 
)

Main function to be executed by ROS.

Parameters
argcNumber of command line arguments.
argvArray of command line arguments.
Returns
Success.

Definition at line 172 of file target_monitor.cpp.

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

Callback function for position updates.

Parameters
msgPosition received from the CPS.

Definition at line 133 of file target_monitor.cpp.

geometry_msgs::Quaternion rotate ( geometry_msgs::Quaternion  rotation)

Compute the orientation resulting from the rotated CPS orientation.

Returns
The rotation to apply to the CPS orientation.

Definition at line 49 of file target_monitor.cpp.

void set_done ( const cpswarm_msgs::TargetGoalConstPtr &  goal,
action_server_t as 
)

Callback of the action server which sets the target state to done.

Parameters
goalThe goal message received from the action client.
asThe action server offered by this node.

Definition at line 151 of file target_monitor.cpp.

void tracking_callback ( const cpswarm_msgs::TargetTracking::ConstPtr &  msg)

Callback function for target position.

Parameters
msgID of target and translation between CPS and target as received from the OpenMV camera.

Definition at line 64 of file target_monitor.cpp.

void update_callback ( const cpswarm_msgs::TargetPositionEvent::ConstPtr &  msg)

Callback function to receive updated information about targets from other CPSs.

Parameters
msgID and position of target.

Definition at line 93 of file target_monitor.cpp.

double yaw ( )

Compute the current yaw orientation of the CPS.

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

Definition at line 38 of file target_monitor.cpp.

Variable Documentation

targets* monitor

The targets being monitored.

Definition at line 22 of file target_monitor.cpp.

geometry_msgs::Pose pose

Current position of the CPS.

Definition at line 27 of file target_monitor.cpp.

bool pose_valid

Whether a valid position has been received.

Definition at line 32 of file target_monitor.cpp.



target_monitor
Author(s): Micha Sende
autogenerated on Tue Jan 19 2021 03:30:07