#include <interpolation_1d.h>
Definition at line 39 of file interpolation_1d.h.
 
◆ InterpolationType
◆ Interpolation1D()
      
        
          | swri_math_util::Interpolation1D::Interpolation1D | ( |  | ) |  | 
      
 
 
◆ appendPoint()
      
        
          | bool swri_math_util::Interpolation1D::appendPoint | ( | double | x, | 
        
          |  |  | double | y | 
        
          |  | ) |  |  | 
      
 
 
◆ clear()
      
        
          | void swri_math_util::Interpolation1D::clear | ( |  | ) |  | 
      
 
 
◆ eval()
  
  | 
        
          | double swri_math_util::Interpolation1D::eval | ( | double | x | ) | const |  | inline | 
 
 
◆ getPoint()
      
        
          | std::pair< double, double > swri_math_util::Interpolation1D::getPoint | ( | size_t | index | ) | const | 
      
 
 
◆ interpolationType()
◆ interpolationTypeString()
      
        
          | std::string swri_math_util::Interpolation1D::interpolationTypeString | ( |  | ) | const | 
      
 
 
◆ maxX()
      
        
          | double swri_math_util::Interpolation1D::maxX | ( |  | ) | const | 
      
 
 
◆ minX()
      
        
          | double swri_math_util::Interpolation1D::minX | ( |  | ) | const | 
      
 
 
◆ numPoints()
      
        
          | size_t swri_math_util::Interpolation1D::numPoints | ( |  | ) | const | 
      
 
 
◆ readFromParameter() [1/2]
      
        
          | bool swri_math_util::Interpolation1D::readFromParameter | ( | const ros::NodeHandle & | node_handle, | 
        
          |  |  | const std::string & | param_name, | 
        
          |  |  | bool | error_if_missing | 
        
          |  | ) |  |  | 
      
 
 
◆ readFromParameter() [2/2]
      
        
          | bool swri_math_util::Interpolation1D::readFromParameter | ( | XmlRpc::XmlRpcValue & | curve_param, | 
        
          |  |  | const std::string & | param_name | 
        
          |  | ) |  |  | 
      
 
 
◆ removePoint()
      
        
          | void swri_math_util::Interpolation1D::removePoint | ( | size_t | index | ) |  | 
      
 
 
◆ setInterpolationType()
◆ interp_type_
◆ x_
  
  | 
        
          | std::vector<double> swri_math_util::Interpolation1D::x_ |  | private | 
 
 
◆ y_
  
  | 
        
          | std::vector<double> swri_math_util::Interpolation1D::y_ |  | private | 
 
 
The documentation for this class was generated from the following files: