Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes | List of all members
multi_robot_router::RobotInfo Class Reference

#include <robot_info.h>

Inheritance diagram for multi_robot_router::RobotInfo:
Inheritance graph
[legend]

Public Types

enum  Online { Online::inactive, Online::active, Online::fixed }
 

Public Member Functions

void callback_odom (const nav_msgs::Odometry &msg)
 
bool compareName (const std::shared_ptr< RobotInfo > data) const
 
Online getOnlineStatus () const
 
Eigen::Vector3d getPose () const
 
void initTopics (ros::NodeHandle &n)
 
float radius () const
 
 RobotInfo ()
 
 RobotInfo (const tuw_multi_robot_msgs::RobotInfo &o)
 
 RobotInfo (const std::string &name)
 
void updateInfo (const tuw_multi_robot_msgs::RobotInfo &info)
 
void updateOnlineStatus (const float updateTime)
 

Static Public Member Functions

static size_t findIdx (const std::vector< std::shared_ptr< RobotInfo > > &data, const std::string &name)
 
static std::vector< std::shared_ptr< RobotInfo > >::iterator findObj (std::vector< std::shared_ptr< RobotInfo > > &data, const std::string &name)
 

Public Attributes

ros::Publisher pubPaths_
 
ros::Publisher pubRoute_
 
ros::Subscriber subOdom_
 

Private Attributes

float activeTime_
 
Online online_
 

Detailed Description

Definition at line 53 of file robot_info.h.

Member Enumeration Documentation

Enumerator
inactive 
active 
fixed 

Definition at line 75 of file robot_info.h.

Constructor & Destructor Documentation

multi_robot_router::RobotInfo::RobotInfo ( )
inline

Definition at line 56 of file robot_info.h.

multi_robot_router::RobotInfo::RobotInfo ( const tuw_multi_robot_msgs::RobotInfo &  o)
inline

Definition at line 62 of file robot_info.h.

multi_robot_router::RobotInfo::RobotInfo ( const std::string &  name)
inline

Definition at line 68 of file robot_info.h.

Member Function Documentation

void multi_robot_router::RobotInfo::callback_odom ( const nav_msgs::Odometry &  msg)

Definition at line 45 of file robot_info.cpp.

bool multi_robot_router::RobotInfo::compareName ( const std::shared_ptr< RobotInfo data) const

check if it crashes if the robot name holds no number

Definition at line 49 of file robot_info.cpp.

size_t multi_robot_router::RobotInfo::findIdx ( const std::vector< std::shared_ptr< RobotInfo > > &  data,
const std::string &  name 
)
static

returns the indes of the robot with a name

Returns
index or data.size() if no matching element was found

Definition at line 77 of file robot_info.cpp.

std::vector< std::shared_ptr< RobotInfo > >::iterator multi_robot_router::RobotInfo::findObj ( std::vector< std::shared_ptr< RobotInfo > > &  data,
const std::string &  name 
)
static

returns a reference to the robot with a name

Returns
ref or data.end() if no matching element was found

Definition at line 84 of file robot_info.cpp.

RobotInfo::Online multi_robot_router::RobotInfo::getOnlineStatus ( ) const

Definition at line 106 of file robot_info.cpp.

Eigen::Vector3d multi_robot_router::RobotInfo::getPose ( ) const

Definition at line 90 of file robot_info.cpp.

void multi_robot_router::RobotInfo::initTopics ( ros::NodeHandle n)

crates subsribers and publisher based on the robot name

Parameters
nnode handler
Returns
index or data.size() if no matching element was found

Definition at line 55 of file robot_info.cpp.

float multi_robot_router::RobotInfo::radius ( ) const

returns vehilce radius based on the robots shape a caching must be implemented for non circular shapes

Returns
radius

Definition at line 98 of file robot_info.cpp.

void multi_robot_router::RobotInfo::updateInfo ( const tuw_multi_robot_msgs::RobotInfo &  info)

Definition at line 72 of file robot_info.cpp.

void multi_robot_router::RobotInfo::updateOnlineStatus ( const float  updateTime)

Definition at line 110 of file robot_info.cpp.

Member Data Documentation

float multi_robot_router::RobotInfo::activeTime_
private

Definition at line 121 of file robot_info.h.

Online multi_robot_router::RobotInfo::online_
private

Definition at line 120 of file robot_info.h.

ros::Publisher multi_robot_router::RobotInfo::pubPaths_

Definition at line 116 of file robot_info.h.

ros::Publisher multi_robot_router::RobotInfo::pubRoute_

Definition at line 117 of file robot_info.h.

ros::Subscriber multi_robot_router::RobotInfo::subOdom_

Definition at line 115 of file robot_info.h.


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


tuw_multi_robot_router
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:49