Public Types | Public Member Functions | Private Attributes | List of all members
swri_math_util::Interpolation1D Class Reference

#include <interpolation_1d.h>

Public Types

enum  InterpolationType { ZERO_ORDER_HOLD, LINEAR }
 

Public Member Functions

bool appendPoint (double x, double y)
 
void clear ()
 
double eval (double x) const
 
std::pair< double, double > getPoint (size_t index) const
 
 Interpolation1D ()
 
InterpolationType interpolationType ()
 
std::string interpolationTypeString () const
 
double maxX () const
 
double minX () const
 
size_t numPoints () const
 
bool readFromParameter (const ros::NodeHandle &node_handle, const std::string &param_name, bool error_if_missing)
 
bool readFromParameter (XmlRpc::XmlRpcValue &curve_param, const std::string &param_name)
 
void removePoint (size_t index)
 
void setInterpolationType (InterpolationType type)
 

Private Attributes

InterpolationType interp_type_
 
std::vector< double > x_
 
std::vector< double > y_
 

Detailed Description

Definition at line 39 of file interpolation_1d.h.

Member Enumeration Documentation

Enumerator
ZERO_ORDER_HOLD 
LINEAR 

Definition at line 42 of file interpolation_1d.h.

Constructor & Destructor Documentation

swri_math_util::Interpolation1D::Interpolation1D ( )

Definition at line 33 of file interpolation_1d.cpp.

Member Function Documentation

bool swri_math_util::Interpolation1D::appendPoint ( double  x,
double  y 
)

Definition at line 39 of file interpolation_1d.cpp.

void swri_math_util::Interpolation1D::clear ( )

Definition at line 82 of file interpolation_1d.cpp.

double swri_math_util::Interpolation1D::eval ( double  x) const
inline

Definition at line 81 of file interpolation_1d.h.

std::pair< double, double > swri_math_util::Interpolation1D::getPoint ( size_t  index) const

Definition at line 60 of file interpolation_1d.cpp.

Interpolation1D::InterpolationType swri_math_util::Interpolation1D::interpolationType ( )

Definition at line 88 of file interpolation_1d.cpp.

std::string swri_math_util::Interpolation1D::interpolationTypeString ( ) const

Definition at line 93 of file interpolation_1d.cpp.

double swri_math_util::Interpolation1D::maxX ( ) const

Definition at line 242 of file interpolation_1d.cpp.

double swri_math_util::Interpolation1D::minX ( ) const

Definition at line 233 of file interpolation_1d.cpp.

size_t swri_math_util::Interpolation1D::numPoints ( ) const

Definition at line 55 of file interpolation_1d.cpp.

bool swri_math_util::Interpolation1D::readFromParameter ( const ros::NodeHandle node_handle,
const std::string &  param_name,
bool  error_if_missing 
)

Definition at line 109 of file interpolation_1d.cpp.

bool swri_math_util::Interpolation1D::readFromParameter ( XmlRpc::XmlRpcValue curve_param,
const std::string &  param_name 
)

Definition at line 129 of file interpolation_1d.cpp.

void swri_math_util::Interpolation1D::removePoint ( size_t  index)

Definition at line 71 of file interpolation_1d.cpp.

void swri_math_util::Interpolation1D::setInterpolationType ( InterpolationType  type)

Definition at line 104 of file interpolation_1d.cpp.

Member Data Documentation

InterpolationType swri_math_util::Interpolation1D::interp_type_
private

Definition at line 75 of file interpolation_1d.h.

std::vector<double> swri_math_util::Interpolation1D::x_
private

Definition at line 76 of file interpolation_1d.h.

std::vector<double> swri_math_util::Interpolation1D::y_
private

Definition at line 77 of file interpolation_1d.h.


The documentation for this class was generated from the following files:


swri_math_util
Author(s): Marc Alban
autogenerated on Tue Apr 6 2021 02:50:30