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

A target that is monitored by the CPSs. More...

#include <target.h>

Public Member Functions

geometry_msgs::Pose get_pose ()
 Get the position of the target. More...
 
target_state_t get_state ()
 Get the state of the target. More...
 
bool lost ()
 Check whether the target tracked by this CPS has been lost. Switch state from TARGET_TRACKED to TARGET_LOST if the tracking timeout has expired. More...
 
void operator= (const target &t)
 Assignment operator. More...
 
 target ()
 Constructor. More...
 
 target (const target &t)
 Copy constructor. More...
 
 target (unsigned int id, target_state_t state)
 Constructor that initializes some private member variables. More...
 
 target (unsigned int id, target_state_t state, geometry_msgs::Pose pose)
 Constructor that initializes some private member variables. More...
 
 target (unsigned int id, target_state_t state, geometry_msgs::Pose pose, Time stamp)
 Constructor that initializes some private member variables. More...
 
void update (target_state_t state, geometry_msgs::Pose pose, Time stamp)
 Update the information about a target. More...
 
 ~target ()
 Destructor that destroys all objects. More...
 

Private Attributes

int id
 The ID of this target. Negative IDs are invalid. More...
 
NodeHandle nh
 A node handle for the main ROS node. More...
 
geometry_msgs::Pose pose
 Position of the target. More...
 
Raterate
 The loop rate object for running the behavior control loops at a specific frequency. More...
 
Time stamp
 Time stamp of latest update of the target. More...
 
target_state_t state
 State of the target. More...
 
Duration timeout
 The time in seconds after which a target transitions into the state TARGET_LOST when no target update has been received. More...
 

Detailed Description

A target that is monitored by the CPSs.

Definition at line 25 of file target.h.

Constructor & Destructor Documentation

target::target ( )

Constructor.

Definition at line 3 of file target.cpp.

target::target ( const target t)

Copy constructor.

Definition at line 7 of file target.cpp.

target::target ( unsigned int  id,
target_state_t  state 
)

Constructor that initializes some private member variables.

Parameters
idThe target ID.
stateThe target state.

Definition at line 11 of file target.cpp.

target::target ( unsigned int  id,
target_state_t  state,
geometry_msgs::Pose  pose 
)

Constructor that initializes some private member variables.

Parameters
idThe target ID.
stateThe target state.
poseThe position of the target.

Definition at line 15 of file target.cpp.

target::target ( unsigned int  id,
target_state_t  state,
geometry_msgs::Pose  pose,
Time  stamp 
)

Constructor that initializes some private member variables.

Parameters
idThe target ID.
stateThe target state.
poseThe position of the target.
stampThe time stamp of target.

Definition at line 19 of file target.cpp.

target::~target ( )

Destructor that destroys all objects.

Definition at line 36 of file target.cpp.

Member Function Documentation

geometry_msgs::Pose target::get_pose ( )

Get the position of the target.

Returns
A pose containing the target position.

Definition at line 41 of file target.cpp.

target_state_t target::get_state ( )

Get the state of the target.

Returns
The current target state.

Definition at line 46 of file target.cpp.

bool target::lost ( )

Check whether the target tracked by this CPS has been lost. Switch state from TARGET_TRACKED to TARGET_LOST if the tracking timeout has expired.

Returns
Whether the target has been lost.

Definition at line 51 of file target.cpp.

void target::operator= ( const target t)

Assignment operator.

Parameters
tThe object from where to take the assignment values.

Definition at line 74 of file target.cpp.

void target::update ( target_state_t  state,
geometry_msgs::Pose  pose,
Time  stamp 
)

Update the information about a target.

Parameters
stateThe state of the target.
poseThe position of the target.
stampThe time stamp of the update.

Definition at line 80 of file target.cpp.

Member Data Documentation

int target::id
private

The ID of this target. Negative IDs are invalid.

Definition at line 108 of file target.h.

NodeHandle target::nh
private

A node handle for the main ROS node.

Definition at line 103 of file target.h.

geometry_msgs::Pose target::pose
private

Position of the target.

Definition at line 118 of file target.h.

Rate* target::rate
private

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

Definition at line 133 of file target.h.

Time target::stamp
private

Time stamp of latest update of the target.

Definition at line 123 of file target.h.

target_state_t target::state
private

State of the target.

Definition at line 113 of file target.h.

Duration target::timeout
private

The time in seconds after which a target transitions into the state TARGET_LOST when no target update has been received.

Definition at line 128 of file target.h.


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


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