#include <robot_information.h>
Definition at line 53 of file robot_information.h.
 
◆ Ptr
◆ RobotInformation()
      
        
          | mbf_utility::RobotInformation::RobotInformation  | 
          ( | 
          TF &  | 
          tf_listener,  | 
        
        
           | 
           | 
          const std::string &  | 
          global_frame,  | 
        
        
           | 
           | 
          const std::string &  | 
          robot_frame,  | 
        
        
           | 
           | 
          const ros::Duration &  | 
          tf_timeout  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
 
◆ getGlobalFrame()
      
        
          | const std::string & mbf_utility::RobotInformation::getGlobalFrame  | 
          ( | 
           | ) | 
           const | 
        
      
 
 
◆ getRobotFrame()
      
        
          | const std::string & mbf_utility::RobotInformation::getRobotFrame  | 
          ( | 
           | ) | 
           const | 
        
      
 
 
◆ getRobotPose()
      
        
          | bool mbf_utility::RobotInformation::getRobotPose  | 
          ( | 
          geometry_msgs::PoseStamped &  | 
          robot_pose | ) | 
           const | 
        
      
 
Computes the current robot pose (robot_frame_) in the global frame (global_frame_). 
- Parameters
 - 
  
    | robot_pose | Reference to the robot_pose message object to be filled.  | 
  
   
- Returns
 - true, if the current robot pose could be computed, false otherwise. 
 
Definition at line 55 of file robot_information.cpp.
 
 
◆ getRobotVelocity()
      
        
          | bool mbf_utility::RobotInformation::getRobotVelocity  | 
          ( | 
          geometry_msgs::TwistStamped &  | 
          robot_velocity,  | 
        
        
           | 
           | 
          ros::Duration  | 
          look_back_duration  | 
        
        
           | 
          ) | 
           |  const | 
        
      
 
 
◆ getTfTimeout()
      
        
          | const ros::Duration & mbf_utility::RobotInformation::getTfTimeout  | 
          ( | 
           | ) | 
           const | 
        
      
 
 
◆ getTransformListener()
      
        
          | const TF & mbf_utility::RobotInformation::getTransformListener  | 
          ( | 
           | ) | 
           const | 
        
      
 
 
◆ global_frame_
  
  
      
        
          | const std::string& mbf_utility::RobotInformation::global_frame_ | 
         
       
   | 
  
private   | 
  
 
 
◆ robot_frame_
  
  
      
        
          | const std::string& mbf_utility::RobotInformation::robot_frame_ | 
         
       
   | 
  
private   | 
  
 
 
◆ tf_listener_
  
  
      
        
          | const TF& mbf_utility::RobotInformation::tf_listener_ | 
         
       
   | 
  
private   | 
  
 
 
◆ tf_timeout_
The documentation for this class was generated from the following files: