#include <vive_solver.h>
|  | 
|  | Solver (ros::NodeHandle nh) | 
|  | 
| void | Add (ff_hw_msgs::ViveTrackers::ConstPtr msg, ros::Time const &t) | 
|  | 
| void | Add (ff_hw_msgs::ViveLighthouses::ConstPtr msg, ros::Time const &t) | 
|  | 
| void | Add (ff_hw_msgs::ViveLight::ConstPtr msg, ros::Time const &t) | 
|  | 
| void | Add (geometry_msgs::PoseStamped::ConstPtr msg, ros::Time const &t) | 
|  | 
| bool | Calibrate () | 
|  | 
| bool | Refine () | 
|  | 
| bool | Register () | 
|  | 
| bool | Solve () | 
|  | 
| void | Publish (ros::Publisher &pub, std::string const &frame, std::map< ros::Time, double[6]> const &x) | 
|  | 
| void | PrintTransform (const double transform[6]) | 
|  | 
| void | GetTruth (nav_msgs::Path &path) | 
|  | 
| void | GetVive (nav_msgs::Path &path) | 
|  | 
◆ Solver()
  
  | 
        
          | vive_localization::Solver::Solver | ( | ros::NodeHandle | nh | ) |  |  | explicit | 
 
 
◆ Add() [1/4]
      
        
          | void vive_localization::Solver::Add | ( | ff_hw_msgs::ViveLight::ConstPtr | msg, | 
        
          |  |  | ros::Time const & | t | 
        
          |  | ) |  |  | 
      
 
 
◆ Add() [2/4]
      
        
          | void vive_localization::Solver::Add | ( | ff_hw_msgs::ViveLighthouses::ConstPtr | msg, | 
        
          |  |  | ros::Time const & | t | 
        
          |  | ) |  |  | 
      
 
 
◆ Add() [3/4]
      
        
          | void vive_localization::Solver::Add | ( | ff_hw_msgs::ViveTrackers::ConstPtr | msg, | 
        
          |  |  | ros::Time const & | t | 
        
          |  | ) |  |  | 
      
 
 
◆ Add() [4/4]
      
        
          | void vive_localization::Solver::Add | ( | geometry_msgs::PoseStamped::ConstPtr | msg, | 
        
          |  |  | ros::Time const & | t | 
        
          |  | ) |  |  | 
      
 
 
◆ Calibrate()
      
        
          | bool vive_localization::Solver::Calibrate | ( |  | ) |  | 
      
 
 
◆ GetTruth()
      
        
          | void vive_localization::Solver::GetTruth | ( | nav_msgs::Path & | path | ) |  | 
      
 
 
◆ GetVive()
      
        
          | void vive_localization::Solver::GetVive | ( | nav_msgs::Path & | path | ) |  | 
      
 
 
◆ PrintTransform()
      
        
          | void vive_localization::Solver::PrintTransform | ( | const double | transform[6] | ) |  | 
      
 
 
◆ Publish()
      
        
          | void vive_localization::Solver::Publish | ( | ros::Publisher & | pub, | 
        
          |  |  | std::string const & | frame, | 
        
          |  |  | std::map< ros::Time, double[6]> const & | x | 
        
          |  | ) |  |  | 
      
 
 
◆ Refine()
      
        
          | bool vive_localization::Solver::Refine | ( |  | ) |  | 
      
 
 
◆ Register()
      
        
          | bool vive_localization::Solver::Register | ( |  | ) |  | 
      
 
 
◆ Solve()
      
        
          | bool vive_localization::Solver::Solve | ( |  | ) |  | 
      
 
 
The documentation for this class was generated from the following files: