Go to the documentation of this file.
   29 #ifndef MATH_UTIL_INTERPOLATION_1D_H_ 
   30 #define MATH_UTIL_INTERPOLATION_1D_H_ 
   51   std::pair<double, double> 
getPoint(
size_t index) 
const;
 
   62     const std::string ¶m_name,
 
   63     bool error_if_missing);
 
   67     const std::string ¶m_name);
 
   72   double eval(
double x) 
const;
 
   76   std::vector<double> 
x_;
 
   77   std::vector<double> 
y_;
 
   86   } 
else if (
x_.size() == 1) {
 
   90   } 
else if (x <= 
x_.front()) {
 
   94   } 
else if (x >= 
x_.back()) {
 
  107   size_t i_max = 
x_.size()-2;
 
  110   while (i_min <= i_max) {
 
  111     i_mid = i_min + (i_max-i_min)/2;
 
  113     if (
x_[i_mid] <= x && 
x_[i_mid+1] >= x) {
 
  116     } 
else if (x < 
x_[i_mid]) {
 
  130    double s = (x - 
x_[i0]) / (
x_[i1] - 
x_[i0]);
 
  131    return (1.0-
s)*
y_[i0] + 
s*
y_[i1];   
 
  140 #endif  // MATH_UTIL_INTERPOLATION_1D_H_ 
  
InterpolationType interp_type_
bool appendPoint(double x, double y)
InterpolationType interpolationType()
double eval(double x) const
std::pair< double, double > getPoint(size_t index) const
std::string interpolationTypeString() const
void removePoint(size_t index)
void setInterpolationType(InterpolationType type)
bool readFromParameter(const ros::NodeHandle &node_handle, const std::string ¶m_name, bool error_if_missing)
swri_math_util
Author(s): Marc Alban
autogenerated on Thu Feb 27 2025 03:33:58