Public Member Functions | Public Attributes | Private Attributes
lpf Class Reference

Lowpass filter class. More...

#include <lmc_filter_node.h>

List of all members.

Public Member Functions

double filter (const double &new_msrmt, int f_idx, int dim)
 This is used to filter the position values of a bone.
double getFilteredMsrmt (int f_idx, int dim)
 This is used to get a filtered value of a bone.
 lpf ()
 Uses default values for initial setup.
 lpf (double)
 Uses parameter server values for initial setup.
void setCutoff (double)
 Use this to change the cutoff of a lpf object.
void setInitialPos (double initial_msrmt, int b_idx, int dim)
 This is used to set the inital position values of a filter.

Public Attributes

double c_

Private Attributes

double prev_filtered_msrmts_ [6][3][2]
double prev_msrmts_ [6][3][3]

Detailed Description

Lowpass filter class.

This is a 2nd-order Butterworth LPF that is used to filter the hand x, y, z coordinates coming from the Leap Controller via Human.msg Refer to Julius O. Smith III, Intro. to Digital Filters with Audio Applications

Definition at line 10 of file lmc_filter_node.h.


Constructor & Destructor Documentation

lpf::lpf ( )

Uses default values for initial setup.

Called when a Lpf object is created with this constructor.

Definition at line 23 of file lmc_filter_node.cpp.

lpf::lpf ( double  cutoff)

Uses parameter server values for initial setup.

Called when a Lpf object is created with this constructor.

Parameters:
cutoffRelated to the cutoff frequency of the filter.

Definition at line 35 of file lmc_filter_node.cpp.


Member Function Documentation

double lpf::filter ( const double &  new_msrmt,
int  b_idx,
int  dim 
)

This is used to filter the position values of a bone.

See bitbucket.org/AndyZe/pid if you want to get more sophisticated. Larger c --> trust the filtered data more, trust the measurements less.

Parameters:
new_msrmtNew measurement that will be used to calculate the new filtered value.
b_idxUsed to access the values of the bone using that index.
dimEach bone has a coordinate of x, y, z (0, 1, 2).

Definition at line 79 of file lmc_filter_node.cpp.

double lpf::getFilteredMsrmt ( int  b_idx,
int  dim 
)

This is used to get a filtered value of a bone.

Parameters:
b_idxUsed to access the values of the bone using that index.
dimEach bone has a coordinate of x, y, z (0, 1, 2).

Definition at line 103 of file lmc_filter_node.cpp.

void lpf::setCutoff ( double  cutoff)

Use this to change the cutoff of a lpf object.

Use this to change the cutoff of a lpf object.

Parameters:
cutoffRelated to the cutoff frequency of the filter.

Definition at line 47 of file lmc_filter_node.cpp.

void lpf::setInitialPos ( double  initial_msrmt,
int  b_idx,
int  dim 
)

This is used to set the inital position values of a filter.

Parameters:
initial_msrmtMeasurement will be used as the base for further filtering.
b_idxUsed to access the values of the bone using that index.
dimEach bone has a value of x, y, z (0, 1, 2).

Definition at line 59 of file lmc_filter_node.cpp.


Member Data Documentation

double lpf::c_

Definition at line 19 of file lmc_filter_node.h.

double lpf::prev_filtered_msrmts_[6][3][2] [private]

Definition at line 25 of file lmc_filter_node.h.

double lpf::prev_msrmts_[6][3][3] [private]

Definition at line 24 of file lmc_filter_node.h.


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


leap_motion
Author(s): Florian Lier , Mirza Shah , Isaac IY Saito
autogenerated on Sat Jun 8 2019 18:47:25