Public Types | Public Member Functions | Private Member Functions | Private Attributes
interpolator Class Reference

#include <interpolator.h>

List of all members.

Public Types

enum  interpolation_mode { LINEAR, HOFFARBIB, QUINTICSPLINE, CUBICSPLINE }

Public Member Functions

double calc_interpolation_time (const double *g)
void clear ()
double deltaT () const
int dimension () const
double * front ()
void get (double *x_, bool popp=true)
void get (double *x_, double *v_, bool popp=true)
void get (double *x_, double *v_, double *a_, bool popp=true)
void go (const double *gx, const double *gv, double time, bool immediate=true)
void go (const double *gx, double time, bool immediate=true)
void interpolate (double &remain_t_)
 interpolator (int dim_, double dt_, interpolation_mode imode_=HOFFARBIB, double default_avg_vel_=0.5)
bool isEmpty ()
void load (string fname, double time_to_start=1.0, double scale=1.0, bool immediate=true, size_t offset1=0, size_t offset2=0)
void load (const char *fname, double time_to_start=1.0, double scale=1.0, bool immediate=true, size_t offset1=0, size_t offset2=0)
void pop ()
void pop_back ()
void push (const double *x_, const double *v_, const double *a_, bool immediate=true)
double remain_time ()
void set (const double *x, const double *v=NULL)
void setGoal (const double *gx, const double *gv, double time, bool online=true)
void setGoal (const double *gx, double time, bool online=true)
bool setInterpolationMode (interpolation_mode i_mode_)
void setName (const std::string &_name)
void sync ()
 ~interpolator ()

Private Member Functions

void hoffarbib (double &remain_t_, double a0, double a1, double a2, double a3, double a4, double a5, double &xx, double &vv, double &aa)
void linear_interpolation (double &remain_t_, double gx, double &xx, double &vv, double &aa)

Private Attributes

double * a
double * a0
double * a1
double * a2
double * a3
double * a4
double * a5
deque< double * > ddq
double default_avg_vel
int dim
deque< double * > dq
double dt
double * ga
double * gv
double * gx
interpolation_mode imode
int length
std::string name
coil::Mutex pop_mutex_
deque< double * > q
double remain_t
double target_t
double * v
double * x

Detailed Description

Definition at line 10 of file interpolator.h.


Member Enumeration Documentation

Enumerator:
LINEAR 
HOFFARBIB 
QUINTICSPLINE 
CUBICSPLINE 

Definition at line 23 of file interpolator.h.


Constructor & Destructor Documentation

interpolator::interpolator ( int  dim_,
double  dt_,
interpolation_mode  imode_ = HOFFARBIB,
double  default_avg_vel_ = 0.5 
)

Definition at line 9 of file interpolator.cpp.

Definition at line 35 of file interpolator.cpp.


Member Function Documentation

Definition at line 99 of file interpolator.cpp.

Definition at line 52 of file interpolator.cpp.

double interpolator::deltaT ( ) const [inline]

Definition at line 61 of file interpolator.h.

int interpolator::dimension ( ) const [inline]

Definition at line 62 of file interpolator.h.

double * interpolator::front ( )

Definition at line 337 of file interpolator.cpp.

void interpolator::get ( double *  x_,
bool  popp = true 
)

Definition at line 346 of file interpolator.cpp.

void interpolator::get ( double *  x_,
double *  v_,
bool  popp = true 
)

Definition at line 351 of file interpolator.cpp.

void interpolator::get ( double *  x_,
double *  v_,
double *  a_,
bool  popp = true 
)

Definition at line 356 of file interpolator.cpp.

void interpolator::go ( const double *  gx,
const double *  gv,
double  time,
bool  immediate = true 
)

Definition at line 208 of file interpolator.cpp.

void interpolator::go ( const double *  gx,
double  time,
bool  immediate = true 
)

Definition at line 203 of file interpolator.cpp.

void interpolator::hoffarbib ( double &  remain_t_,
double  a0,
double  a1,
double  a2,
double  a3,
double  a4,
double  a5,
double &  xx,
double &  vv,
double &  aa 
) [private]

Definition at line 60 of file interpolator.cpp.

void interpolator::interpolate ( double &  remain_t_)

Definition at line 177 of file interpolator.cpp.

Definition at line 387 of file interpolator.cpp.

void interpolator::linear_interpolation ( double &  remain_t_,
double  gx,
double &  xx,
double &  vv,
double &  aa 
) [private]

Definition at line 77 of file interpolator.cpp.

void interpolator::load ( string  fname,
double  time_to_start = 1.0,
double  scale = 1.0,
bool  immediate = true,
size_t  offset1 = 0,
size_t  offset2 = 0 
)

Definition at line 253 of file interpolator.cpp.

void interpolator::load ( const char *  fname,
double  time_to_start = 1.0,
double  scale = 1.0,
bool  immediate = true,
size_t  offset1 = 0,
size_t  offset2 = 0 
)

Definition at line 219 of file interpolator.cpp.

Definition at line 273 of file interpolator.cpp.

Definition at line 290 of file interpolator.cpp.

void interpolator::push ( const double *  x_,
const double *  v_,
const double *  a_,
bool  immediate = true 
)

Definition at line 259 of file interpolator.cpp.

Definition at line 392 of file interpolator.cpp.

void interpolator::set ( const double *  x,
const double *  v = NULL 
)

Definition at line 324 of file interpolator.cpp.

void interpolator::setGoal ( const double *  gx,
const double *  gv,
double  time,
bool  online = true 
)

Definition at line 131 of file interpolator.cpp.

void interpolator::setGoal ( const double *  gx,
double  time,
bool  online = true 
)

Definition at line 125 of file interpolator.cpp.

Definition at line 117 of file interpolator.cpp.

void interpolator::setName ( const std::string &  _name) [inline]

Definition at line 63 of file interpolator.h.

Definition at line 93 of file interpolator.cpp.


Member Data Documentation

double * interpolator::a [private]

Definition at line 76 of file interpolator.h.

double* interpolator::a0 [private]

Definition at line 83 of file interpolator.h.

double * interpolator::a1 [private]

Definition at line 83 of file interpolator.h.

double * interpolator::a2 [private]

Definition at line 83 of file interpolator.h.

double * interpolator::a3 [private]

Definition at line 83 of file interpolator.h.

double * interpolator::a4 [private]

Definition at line 83 of file interpolator.h.

double * interpolator::a5 [private]

Definition at line 83 of file interpolator.h.

deque<double *> interpolator::ddq [private]

Definition at line 68 of file interpolator.h.

Definition at line 85 of file interpolator.h.

Definition at line 72 of file interpolator.h.

deque<double *> interpolator::dq [private]

Definition at line 68 of file interpolator.h.

double interpolator::dt [private]

Definition at line 74 of file interpolator.h.

double * interpolator::ga [private]

Definition at line 78 of file interpolator.h.

double * interpolator::gv [private]

Definition at line 78 of file interpolator.h.

double* interpolator::gx [private]

Definition at line 78 of file interpolator.h.

Definition at line 63 of file interpolator.h.

Definition at line 70 of file interpolator.h.

std::string interpolator::name [private]

Definition at line 87 of file interpolator.h.

Definition at line 97 of file interpolator.h.

deque<double *> interpolator::q [private]

Definition at line 68 of file interpolator.h.

double interpolator::remain_t [private]

Definition at line 81 of file interpolator.h.

double interpolator::target_t [private]

Definition at line 81 of file interpolator.h.

double * interpolator::v [private]

Definition at line 76 of file interpolator.h.

double* interpolator::x [private]

Definition at line 76 of file interpolator.h.


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


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:20