Skip to content

Commit

Permalink
New module 'processing'.
Browse files Browse the repository at this point in the history
  • Loading branch information
Alzathar committed Nov 26, 2016
1 parent cec920a commit b321ac2
Show file tree
Hide file tree
Showing 9 changed files with 360 additions and 0 deletions.
34 changes: 34 additions & 0 deletions modules/processing/CmakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
SET(OPENMA_BODY_SRCS
src/_processing.cpp
)

ADD_LIBRARY(processing ${OPENMA_LIBS_BUILD_TYPE} ${OPENMA_BODY_SRCS})
TARGET_LINK_LIBRARIES(processing base math)
TARGET_INCLUDE_DIRECTORIES(processing PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}/include>
$<INSTALL_INTERFACE:include>
)
GENERATE_EXPORT_HEADER(processing
BASE_NAME OPENMA_PROCESSING
EXPORT_FILE_NAME include/openma/processing_export.h)

SET_TARGET_PROPERTIES(processing PROPERTIES ${OPENMA_LIBRARY_PROPERTIES})
IF (NOT ${OPENMA_BUILD_SHARED_LIBS})
SET_TARGET_PROPERTIES(processing PROPERTIES COMPILE_FLAGS -DOPENMA_PROCESSING_STATIC_DEFINE)
ENDIF()

IF(BUILD_LANGUAGE_BINDINGS)
ADD_SUBDIRECTORY(swig)
ENDIF()

IF(BUILD_UNIT_TESTS)
ADD_SUBDIRECTORY(test)
ENDIF()

INSTALL(TARGETS processing EXPORT OpenMATargets
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION lib
INCLUDES DESTINATION lib
)
10 changes: 10 additions & 0 deletions modules/processing/doc/processing.dox
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
/**
* @defgroup openma_processing ma::processing
* @brief Data processing algorithms.
*
* This module corresponds to the library @c openma_processing. It uses the nested namespace @c processing. As a consequence all the types proposed in this module use the @c ma::processing namespace.
*
* The main goal of this module is to gives high level functions and classes to process data (e.g Butterworth zero lag filter).
*
* @todo Details the goal and usage or ma::processing.
*/
54 changes: 54 additions & 0 deletions modules/processing/include/openma/processing.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
/*
* Open Source Movement Analysis Library
* Copyright (C) 2016, Moveck Solution Inc., all rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above
* copyright notice, this list of conditions and the following
* disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials
* provided with the distribution.
* * Neither the name(s) of the copyright holders nor the names
* of its contributors may be used to endorse or promote products
* derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef __openma_processing_h
#define __openma_processing_h

#include "openma/processing_export.h"
#include "openma/processing/enums.h"

#include <vector>

namespace ma
{
class TimeSequence;

namespace processing
{
OPENMA_PROCESSING_EXPORT bool filter_butterworth_zero_lag(const std::vector<TimeSequence*>& tss, Response type, double fc, int fn);
};

};

#endif // __openma_processing_h
76 changes: 76 additions & 0 deletions modules/processing/include/openma/processing/enums.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
/*
* Open Source Movement Analysis Library
* Copyright (C) 2016, Moveck Solution Inc., all rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above
* copyright notice, this list of conditions and the following
* disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials
* provided with the distribution.
* * Neither the name(s) of the copyright holders nor the names
* of its contributors may be used to endorse or promote products
* derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef __openma_processing_enums_h
#define __openma_processing_enums_h

namespace ma
{
namespace processing
{
enum class Response
{
LowPass = 1,
HighPass,
BandPass,
BandStop
};

/**
* @enum Response
* Enumerator for filter response type
* @sa filter_butterworth_zero_lag
* @ingroup openma_processing
*/
/**
* @var Response Response::LowPass
* To be used when designing a low-pass filter response type
*/
/**
* @var Response Response::HighPass
* To be used when designing a high-pass filter response type
*/
/**
* @var Response Response::BandPass
* To be used when designing a band-pass filter response type
*/
/**
* @var Response Response::BandStop
* To be used when designing a band-stop (or band-rejection) filter response type
*/
};

};

#endif // __openma_processing_h
136 changes: 136 additions & 0 deletions modules/processing/src/_processing.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,136 @@
/*
* Open Source Movement Analysis Library
* Copyright (C) 2016, Moveck Solution Inc., all rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above
* copyright notice, this list of conditions and the following
* disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials
* provided with the distribution.
* * Neither the name(s) of the copyright holders nor the names
* of its contributors may be used to endorse or promote products
* derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "openma/processing.h"
#include "openma/base/timesequence.h"
#include "openma/base/logger.h"
#include "openma/math.h" // ma::math::prepare_window_processing

#include <iostream> // Used by IIRFilterDesign
#include <Eigen_openma/SignalProcessing/IIRFilterDesign.h>
#include <Eigen_openma/SignalProcessing/FiltFilt.h>

void _ma_processing_butterworth_zero_lag_filter(ma::TimeSequence* ts, const Eigen::Matrix<double, Eigen::Dynamic, 1>& b, const Eigen::Matrix<double, Eigen::Dynamic, 1>& a)
{
Eigen::Map<Eigen::Matrix<double,Eigen::Dynamic,Eigen::Dynamic>> data(ts->data(), ts->samples(), ts->components());
data = Eigen::filtfilt(b,a,data);
};

void _ma_processing_butterworth_zero_lag_filter_windowed(ma::TimeSequence* ts, const Eigen::Matrix<double, Eigen::Dynamic, 1>& b, const Eigen::Matrix<double, Eigen::Dynamic, 1>& a)
{
int cpts = ts->components()-1;
Eigen::Map<Eigen::Array<double,Eigen::Dynamic,1>> resin(ts->data()+cpts*ts->samples(), ts->samples(), 1);
Eigen::Array<double,Eigen::Dynamic,1> resout;
unsigned mwlen = 3 * std::max(a.rows(),b.rows()) - 1;
std::vector<std::array<unsigned,2>> windows;
ma::math::prepare_window_processing(resout, windows, resin, mwlen);
Eigen::Map<Eigen::Matrix<double,Eigen::Dynamic,Eigen::Dynamic>> data(ts->data(), ts->samples(), ts->components());
Eigen::Matrix<double,Eigen::Dynamic,1> temp = Eigen::Matrix<double,Eigen::Dynamic,1>::Zero(data.rows(),1);
for (int i = 0 ; i < cpts ; ++i)
{
for (const auto& w : windows)
temp.segment(w[0],w[1]) = Eigen::filtfilt(b,a,data.block(w[0],i,w[1],1));
data.col(i) = temp;
}
resin = resout;
};

namespace ma
{
namespace processing
{
/**
* Convenient function to simplify the data filtering of time sequences with a zero-lag Butterworth filter
* Internally, this function does two filtering passes (one forward followed by one backward). To respect the given final cut-off frequency (@a fc) and the final order (@a fn), these ones are adapted in consequence (see Robertson & Dowling [1] and Winter [2]).
* This function manage each component independently. In case the type of a time sequence is tagged ma::TimeSequence::Reconstructed, the filtering is managed in consequence and realized by window.
*
* @important This is the responsability of the developer to use correctly this function. It is not intended to verify if the passed time sequence(s) is(are) physically adapted to this filter. For example, the filter is adapted for time sequence with the types TimeSequence::Marker and TimeSequence::Analog but might not with the types TimeSequence::Pose and TimeSequence::Wrench.
*
* @par References
* 1. Robertson D.G., Dowling J.J., <em>Design and responses of Butterworth and critically damped digital filters</em>, Journal of Electromyography and Kinesiology, 2003.
* 2. Winter D.A., <em>Biomechanics and Motor Control of Human Movement</em>, John Wiley & Sons, Inc., 2009, paragraph 3.4.4.2.
*
* @ingroup openma_processing
*/
bool filter_butterworth_zero_lag(const std::vector<TimeSequence*>& tss, Response type, double fc, int fn)
{
if (fc <= 0.0)
{
error("Impossible to have a cut-off frequency equal or lower than 0.0.");
return false;
}
if (fn <= 1)
{
error("Impossible to have an order equal or lower than 1.");
return false;
}
Eigen::BandType t = Eigen::LowPass;
switch (type)
{
case Response::LowPass:
break;
case Response::HighPass:
t = Eigen::HighPass;
break;
case Response::BandPass:
t = Eigen::BandPass;
break;
case Response::BandStop:
t = Eigen::BandStop;
break;
default:
error("Unknown band type for the Butterworth filter. Filtering aborted.");
return false;
}
for (const auto& ts : tss)
{
if (ts->sampleRate() == 0.0)
{
error("The time sequence '%s' has a null sample rate.", ts->name().c_str());
continue;
}
double wn = fc / (ts->sampleRate() / 2.0);
int n = fn;
Eigen::adjustZeroLagButterworth(n, wn);
Eigen::Matrix<double, Eigen::Dynamic, 1> a, b;
Eigen::butter(&b, &a, n, wn, t);
if ((ts->type() & TimeSequence::Reconstructed) == TimeSequence::Reconstructed)
_ma_processing_butterworth_zero_lag_filter_windowed(ts,b,a);
else
_ma_processing_butterworth_zero_lag_filter(ts,b,a);
}
return true;
};
};
};
Empty file.
1 change: 1 addition & 0 deletions modules/processing/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
ADD_SUBDIRECTORY("c++")
1 change: 1 addition & 0 deletions modules/processing/test/c++/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
ADD_CXXTEST_TESTDRIVER(openma_processing_butterzerolaglowpass butterzerolaglowpassTest.cpp processing)
48 changes: 48 additions & 0 deletions modules/processing/test/c++/butterzerolaglowpassTest.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
#include <cxxtest/TestDrive.h>

#include <openma/processing.h>
#include <openma/base.h>

static const double in[81] = {0.269798891254315, 0.548893273936043, 0.859470031283581, 1.083314451319253, 1.181526336501076, 1.257304313666979, 1.276759551809656, 1.068465704696009, 0.685668156305006, 0.372268495814636, 0.157220415283078,-0.104162709960200,-0.411133031729557,-0.666435823989357,-0.821984136929495,-0.833236901328857,-0.709580252798482,-0.542015408017795,-0.372916081515782,-0.174340534581690, 0.072920410968047, 0.380822922154266, 0.767727734946687, 1.120370101251430, 1.245206330432570, 1.175867152632213, 1.092613558545766, 1.006391390249807, 0.809008427785796, 0.500882870473192,0.177427442323182,-0.115265050765107,-0.399394457537441,-0.683974764754652,-0.867972546429597,-0.841912916291380,-0.686986990511049,-0.548614709893092,-0.431855109908579,-0.225316251342442,0.149990554410562, 0.548991274928445, 0.766603662161258, 0.897492808926710, 1.119235616431332, 1.308820691731916, 1.244650590294634, 0.982001470310733, 0.740054381757683, 0.537145589228529,0.241231226499049,-0.153720986008040,-0.506910201501367,-0.663739279012461,-0.656372165803181,-0.667496462570363,-0.676804487342212,-0.520053642587747,-0.227506579633197, 0.073377651136435, 0.334500818135176, 0.537846810887783, 0.716580939359015, 0.908624646571194, 1.038847705160293, 1.081244298319416, 1.110278804941418, 1.053114775703411, 0.816052544461935, 0.519935281836539,0.261179617911776,-0.018178988662816,-0.328756149855888,-0.622570989208225,-0.849673221482816,-0.901019340312481,-0.760265237435191,-0.571478064861968,-0.381544623107748,-0.141512050095412,0.126109968176025};

CXXTEST_SUITE(ButterZeroLagLowPassTest)
{
CXXTEST_TEST(analog)
{
const double out[81] = {0.269798891261088, 0.556750494481059, 0.837639550689753, 1.05170782780124, 1.17579244936994, 1.24302331725988, 1.21944440896103, 1.02456046513212, 0.703051673641974, 0.396977077696546, 0.145614906096657, -0.115606496765273, -0.398129299224639, -0.641279251047927, -0.785621929835143, -0.799257171071498, -0.698479428945550, -0.541589407752543, -0.365486766877003, -0.162065813318965, 0.0882179461850634, 0.400674769026374, 0.759042196814361, 1.06304197155685, 1.19631544487594, 1.17226410846896, 1.09179880471148, 0.978416116685996, 0.781131186310728, 0.496989302330060, 0.185148164030461, -0.113098036515398, -0.399447198063161, -0.658602686951213, -0.815100514647356, -0.809447720033578, -0.691084109578709, -0.554000923058926, -0.409230334874926, -0.182876206066244, 0.155933152396641, 0.503410130450450, 0.744777476665554, 0.920240123033550, 1.11107061457078, 1.24497558881929, 1.19468389896834, 0.987111415426758, 0.749816684110644, 0.513758832420659, 0.216334800195200, -0.143180521473855, -0.457490637970223, -0.622411393766237, -0.660923380016051, -0.666958654861107, -0.635031146928926, -0.485859018803136, -0.225360022547793, 0.0633664990587942, 0.319957468260014, 0.531642114190447, 0.719875140812418, 0.893060311669299, 1.01675288692063, 1.07779281123948, 1.08852755678891, 1.00786217509059, 0.801145064136580, 0.529272614014537, 0.256009544847483, -0.0260199750629534, -0.324527360601293, -0.605713059415040, -0.805397970647959, -0.852659385822292, -0.748097268362033, -0.571135853735994, -0.368948801080136, -0.134556731080026, 0.126109966992686};
ma::Node root("root");
auto tss = ma::make_nodes<ma::TimeSequence*>(2,1,81,100.0,0.0,ma::TimeSequence::Analog,"V",&root);
std::copy_n(in, 81, tss[0]->data());
std::copy_n(in, 81, tss[1]->data());
filter_butterworth_zero_lag(tss,ma::processing::Response::LowPass,20.0,2);
for (int i = 0 ; i < 81 ; ++i)
{
TS_ASSERT_DELTA(tss[0]->data()[i], out[i], 5e-8);
TS_ASSERT_DELTA(tss[1]->data()[i], out[i], 5e-8);
}
};

CXXTEST_TEST(reconstructed)
{
const double out[162] = {0.291660028, 0.565287139, 0.813669574, 1.01067018, 1.134069037, 1.168219095, 1.106033864, 0.952326377, 0.725722533, 0.453995496, 0.165365056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.087430096, 0.416285788, 0.713950497, 0.947799244, 1.092730326, 1.137534335, 1.084573407, 0.944459908, 0.732860592, 0.471230282, 0.187148982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.169508982, 0.457839033, 0.719685682, 0.93137081, 1.07322077, 1.128839422, 1.089750982, 0.961423677, 0.762412683, 0.517633828, 0.253263523, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.078769178, 0.313514513, 0.537081905, 0.735855316, 0.89635526, 1.005037296, 1.049581123, 1.021010974, 0.916547735, 0.743217847, 0.519232652, 0.270749678, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0};
ma::Node root("root");
auto tss = ma::make_nodes<ma::TimeSequence*>(1,4,81,100.0,0.0,ma::TimeSequence::Marker,"mm",&root);
std::copy_n(in, 81, tss[0]->data());
std::copy_n(in, 81, tss[0]->data()+81);
std::copy_n(in, 81, tss[0]->data()+81*2);
std::copy_n(in, 81, tss[0]->data()+81*3);
filter_butterworth_zero_lag(tss,ma::processing::Response::LowPass,6,4);
for (int i = 0 ; i < 81 ; ++i)
{
TS_ASSERT_DELTA(*(tss[0]->data()+i), *(out+i), 1e-9);
TS_ASSERT_DELTA(*(tss[0]->data()+i+81), *(out+i), 1e-9);
TS_ASSERT_DELTA(*(tss[0]->data()+i+81*2), *(out+i), 1e-9);
TS_ASSERT_DELTA(*(tss[0]->data()+i+81*3), *(out+i+81), 1e-15);
}
};
};

CXXTEST_SUITE_REGISTRATION(ButterZeroLagLowPassTest)
CXXTEST_TEST_REGISTRATION(ButterZeroLagLowPassTest, analog)
CXXTEST_TEST_REGISTRATION(ButterZeroLagLowPassTest, reconstructed)

0 comments on commit b321ac2

Please sign in to comment.