#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.
 
| Enumerator | 
|---|
| inactive  | 
 | 
| active  | 
 | 
| fixed  | 
 | 
Definition at line 75 of file robot_info.h.
 
 
  
  
      
        
          | multi_robot_router::RobotInfo::RobotInfo  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
inline   | 
  
 
 
  
  
      
        
          | multi_robot_router::RobotInfo::RobotInfo  | 
          ( | 
          const tuw_multi_robot_msgs::RobotInfo &  | 
          o | ) | 
           | 
         
       
   | 
  
inline   | 
  
 
 
  
  
      
        
          | multi_robot_router::RobotInfo::RobotInfo  | 
          ( | 
          const std::string &  | 
          name | ) | 
           | 
         
       
   | 
  
inline   | 
  
 
 
      
        
          | void multi_robot_router::RobotInfo::callback_odom  | 
          ( | 
          const nav_msgs::Odometry &  | 
          msg | ) | 
           | 
        
      
 
 
      
        
          | 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.
 
 
      
        
          | Eigen::Vector3d multi_robot_router::RobotInfo::getPose  | 
          ( | 
           | ) | 
           const | 
        
      
 
 
crates subsribers and publisher based on the robot name 
- Parameters
 - 
  
  
 
- 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 | ) | 
           | 
        
      
 
 
      
        
          | void multi_robot_router::RobotInfo::updateOnlineStatus  | 
          ( | 
          const float  | 
          updateTime | ) | 
           | 
        
      
 
 
  
  
      
        
          | float multi_robot_router::RobotInfo::activeTime_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | Online multi_robot_router::RobotInfo::online_ | 
         
       
   | 
  
private   | 
  
 
 
The documentation for this class was generated from the following files: