Public Member Functions | Public Attributes | Private Attributes
PositionSubscriber Class Reference

Subscripes to the position of the stage simulation. More...

#include <PositionSubscriber.h>

List of all members.

Public Member Functions

double calcDistance (PositionSubscriber *other)
double getXPos ()
double getYPos ()
 PositionSubscriber ()
void Subscribe (const nav_msgs::Odometry::ConstPtr &position)
virtual ~PositionSubscriber ()

Public Attributes

bool initialized
 Defines if the robot position has been initialized.
nav_msgs::Odometry position
 Latest position of the specific robot.
std::string robot_name_
 Name of the robot in stage. e.g: "robot_0".
uint32_t robot_number_
 Number of the robot in stage. e.g: number of "robot_0" would be "0".

Private Attributes

uint16_t callback_count
uint16_t callback_refresh
double x_pos_
double y_pos_

Detailed Description

Subscripes to the position of the stage simulation.

The PositionSubscripe class implements all function to build up a channel model in the stage simulation

Definition at line 18 of file PositionSubscriber.h.


Constructor & Destructor Documentation

Packet constructor. Constructor without parametes.

Definition at line 12 of file PositionSubscriber.cpp.

Definition at line 22 of file PositionSubscriber.cpp.


Member Function Documentation

Calculates the distance between a other robot and this instance in stage

Parameters:
otherPositionSubscribe of the other robot
Returns:
the calculated distance

Definition at line 41 of file PositionSubscriber.cpp.

Returns:
the X coordinate of the specific robot in stage
Returns:
the Y coordinate of the specific robot in stage
void PositionSubscriber::Subscribe ( const nav_msgs::Odometry::ConstPtr &  position)

callback method of the subscribed topic. Refreshes the robot position of the instance.

Parameters:
positionCurrent robot position

Definition at line 27 of file PositionSubscriber.cpp.


Member Data Documentation

Definition at line 59 of file PositionSubscriber.h.

Definition at line 59 of file PositionSubscriber.h.

Defines if the robot position has been initialized.

Definition at line 51 of file PositionSubscriber.h.

nav_msgs::Odometry PositionSubscriber::position

Latest position of the specific robot.

Definition at line 55 of file PositionSubscriber.h.

Name of the robot in stage. e.g: "robot_0".

Definition at line 52 of file PositionSubscriber.h.

Number of the robot in stage. e.g: number of "robot_0" would be "0".

Definition at line 53 of file PositionSubscriber.h.

double PositionSubscriber::x_pos_ [private]

Definition at line 58 of file PositionSubscriber.h.

double PositionSubscriber::y_pos_ [private]

Definition at line 58 of file PositionSubscriber.h.


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


adhoc_communication
Author(s): Guenter Cwioro , Torsten Andre
autogenerated on Thu Aug 27 2015 11:56:40