#include <robot_info.h>
|
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) |
|
Definition at line 53 of file robot_info.h.
◆ Online
Enumerator |
---|
inactive | |
active | |
fixed | |
Definition at line 75 of file robot_info.h.
◆ RobotInfo() [1/3]
multi_robot_router::RobotInfo::RobotInfo |
( |
| ) |
|
|
inline |
◆ RobotInfo() [2/3]
multi_robot_router::RobotInfo::RobotInfo |
( |
const tuw_multi_robot_msgs::RobotInfo & |
o | ) |
|
|
inline |
◆ RobotInfo() [3/3]
multi_robot_router::RobotInfo::RobotInfo |
( |
const std::string & |
name | ) |
|
|
inline |
◆ callback_odom()
void multi_robot_router::RobotInfo::callback_odom |
( |
const nav_msgs::Odometry & |
msg | ) |
|
◆ compareName()
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.
◆ findIdx()
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 81 of file robot_info.cpp.
◆ findObj()
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 88 of file robot_info.cpp.
◆ getOnlineStatus()
◆ getPose()
Eigen::Vector3d multi_robot_router::RobotInfo::getPose |
( |
| ) |
const |
◆ initTopics()
void multi_robot_router::RobotInfo::initTopics |
( |
ros::NodeHandle & |
n, |
|
|
bool |
robot_name_as_namespace |
|
) |
| |
crates subsribers and publisher using a given namespace
- Parameters
-
n | node handler |
robot_name_as_namespace | on true it will use the robots name as namespace prefix |
Definition at line 55 of file robot_info.cpp.
◆ radius()
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 102 of file robot_info.cpp.
◆ updateInfo()
void multi_robot_router::RobotInfo::updateInfo |
( |
const tuw_multi_robot_msgs::RobotInfo & |
info | ) |
|
◆ updateOnlineStatus()
void multi_robot_router::RobotInfo::updateOnlineStatus |
( |
const float |
updateTime | ) |
|
◆ activeTime_
float multi_robot_router::RobotInfo::activeTime_ |
|
private |
◆ online_
Online multi_robot_router::RobotInfo::online_ |
|
private |
◆ pubPaths_
◆ pubRoute_
◆ subOdom_
The documentation for this class was generated from the following files: