JeVoisBase  1.22
JeVois Smart Embedded Machine Vision Toolkit Base Modules
Share this page:
Loading...
Searching...
No Matches
Kalman2D Class Reference

Simple component to track a moving 2D point over time using a Kalman filter. More...

#include <jevoisbase/Components/Tracking/Kalman2D.H>

Inheritance diagram for Kalman2D:
Collaboration diagram for Kalman2D:

Public Member Functions

 Kalman2D (std::string const &instance)
 Constructor.
 
virtual ~Kalman2D ()
 Destructor.
 
void set (float x, float y)
 Function to call each time you have a new measurement (output from a vision algorithm)
 
void set (float x, float y, unsigned int imgwidth, unsigned int imgheight)
 Function to call each time you have a new measurement (output from a vision algorithm)
 
void get (float &x, float &y, float const eps=0.01F)
 Function to call each time you want to get the Kalman-filtered coordinates.
 
void get (float &x, float &y, unsigned int imgwidth, unsigned int imgheight, float const eps=0.01F)
 Function to call each time you want to get the Kalman-filtered coordinates.
 
void get (float &rawx, float &rawy, float &imgx, float &imgy, unsigned int imgwidth, unsigned int imgheight, float const raweps=0.01F, float const imgeps=0.01F)
 Function to call each time you want to get the Kalman-filtered coordinates.
 
- Public Member Functions inherited from jevois::Component
 Component (std::string const &instance)
 
virtual ~Component ()
 
std::shared_ptr< Comp > addSubComponent (std::string const &instance, Args &&...args)
 
void removeSubComponent (std::shared_ptr< Comp > &component)
 
void removeSubComponent (std::string const &instance, bool warnIfNotFound=true)
 
std::shared_ptr< Comp > getSubComponent (std::string const &instance) const
 
bool isTopLevel () const
 
bool initialized () const
 
std::string const & className () const
 
std::string const & instanceName () const
 
std::vector< std::string > setParamVal (std::string const &paramdescriptor, T const &val)
 
void setParamValUnique (std::string const &paramdescriptor, T const &val)
 
std::vector< std::pair< std::string, T > > getParamVal (std::string const &paramdescriptor) const
 
getParamValUnique (std::string const &paramdescriptor) const
 
std::vector< std::string > setParamString (std::string const &paramdescriptor, std::string const &val)
 
void setParamStringUnique (std::string const &paramdescriptor, std::string const &val)
 
std::vector< std::pair< std::string, std::string > > getParamString (std::string const &paramdescriptor) const
 
std::string getParamStringUnique (std::string const &paramdescriptor) const
 
void freezeParam (std::string const &paramdescriptor, bool doit)
 
void freezeAllParams (bool doit)
 
std::string descriptor () const
 
void setParamsFromFile (std::string const &filename)
 
std::istream & setParamsFromStream (std::istream &is, std::string const &absfile)
 
virtual void paramInfo (std::shared_ptr< UserInterface > s, std::map< std::string, std::string > &categs, bool skipFrozen, std::string const &cname="", std::string const &pfx="")
 
void foreachParam (std::function< void(std::string const &compname, ParameterBase *p)> func, std::string const &cname="")
 
std::shared_ptr< DynamicParameter< T > > addDynamicParameter (std::string const &name, std::string const &description, T const &defaultValue, ParameterCategory const &category)
 
std::shared_ptr< DynamicParameter< T > > addDynamicParameter (std::string const &name, std::string const &description, T const &defaultValue, ValidValuesSpec< T > const &validValuesSpec, ParameterCategory const &category)
 
void setDynamicParameterCallback (std::string const &name, std::function< void(T const &)> cb, bool callnow=true)
 
void removeDynamicParameter (std::string const &name, bool throw_if_not_found=true)
 
void setPath (std::string const &path)
 
std::filesystem::path absolutePath (std::filesystem::path const &path="")
 
std::shared_ptr< Comp > addSubComponent (std::string const &instance, Args &&...args)
 
void removeSubComponent (std::shared_ptr< Comp > &component)
 
void removeSubComponent (std::string const &instance, bool warnIfNotFound=true)
 
std::shared_ptr< Comp > getSubComponent (std::string const &instance) const
 
bool isTopLevel () const
 
bool initialized () const
 
std::string const & className () const
 
std::string const & instanceName () const
 
std::vector< std::string > setParamVal (std::string const &paramdescriptor, T const &val)
 
void setParamValUnique (std::string const &paramdescriptor, T const &val)
 
std::vector< std::pair< std::string, T > > getParamVal (std::string const &paramdescriptor) const
 
getParamValUnique (std::string const &paramdescriptor) const
 
std::vector< std::string > setParamString (std::string const &paramdescriptor, std::string const &val)
 
void setParamStringUnique (std::string const &paramdescriptor, std::string const &val)
 
std::vector< std::pair< std::string, std::string > > getParamString (std::string const &paramdescriptor) const
 
std::string getParamStringUnique (std::string const &paramdescriptor) const
 
void freezeParam (std::string const &paramdescriptor, bool doit)
 
void freezeAllParams (bool doit)
 
std::string descriptor () const
 
void setParamsFromFile (std::string const &filename)
 
std::istream & setParamsFromStream (std::istream &is, std::string const &absfile)
 
virtual void paramInfo (std::shared_ptr< UserInterface > s, std::map< std::string, std::string > &categs, bool skipFrozen, std::string const &cname="", std::string const &pfx="")
 
void foreachParam (std::function< void(std::string const &compname, ParameterBase *p)> func, std::string const &cname="")
 
std::shared_ptr< DynamicParameter< T > > addDynamicParameter (std::string const &name, std::string const &description, T const &defaultValue, ParameterCategory const &category)
 
std::shared_ptr< DynamicParameter< T > > addDynamicParameter (std::string const &name, std::string const &description, T const &defaultValue, ValidValuesSpec< T > const &validValuesSpec, ParameterCategory const &category)
 
void setDynamicParameterCallback (std::string const &name, std::function< void(T const &)> cb, bool callnow=true)
 
void removeDynamicParameter (std::string const &name, bool throw_if_not_found=true)
 
void setPath (std::string const &path)
 
std::filesystem::path absolutePath (std::filesystem::path const &path="")
 
- Public Member Functions inherited from jevois::ParameterRegistry
virtual ~ParameterRegistry ()
 

Protected Member Functions

void postInit () override
 
void onParamChange (kalman2d::usevel const &param, bool const &newval) override
 
void onParamChange (kalman2d::procnoise const &param, float const &newval) override
 
void onParamChange (kalman2d::measnoise const &param, float const &newval) override
 
void onParamChange (kalman2d::postnoise const &param, float const &newval) override
 
- Protected Member Functions inherited from jevois::Component
virtual void preInit ()
 
virtual void preUninit ()
 
virtual void postUninit ()
 
virtual void preInit ()
 
virtual void preUninit ()
 
virtual void postUninit ()
 
- Protected Member Functions inherited from jevois::ParameterRegistry
void addParameter (ParameterBase *const param)
 
void removeParameter (ParameterBase *const param)
 
void callbackInitCall ()
 

Protected Attributes

cv::KalmanFilter itsKF
 
cv::Mat itsProcessNoise
 
cv::Mat itsMeasurement
 
cv::Mat itsLatest
 
bool itsFresh
 

Related Symbols

(Note that these are not member symbols.)

 JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (usevel, bool, "Use velocity tracking, in addition to position", false, ParamCateg)
 Parameter.
 
 JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (procnoise, float, "Process noise standard deviation", 0.003F, ParamCateg)
 Parameter.
 
 JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (measnoise, float, "Measurement noise standard deviation", 0.05F, ParamCateg)
 Parameter.
 
 JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (postnoise, float, "A posteriori error estimate standard deviation", 0.3F, ParamCateg)
 Parameter.
 

Detailed Description

Simple component to track a moving 2D point over time using a Kalman filter.

A Kalman filter allows one to filter noisy data over time. Here, it is used to filter the possibly noisy results of some machine vision algorith that is trying to detect a particular item in the camera's video stream. On occasion, the detection might abruptly jump to an erroneous location. Such jumps are filtered out by the Kalman filter.

See for example DemoSaliency to see the Kalman2D filtering over time the location of the most salient object in the video stream.

To allow using this component in many different modules and to support various image resolutions, we here internally normalize all measurements and filtered outputs to between [-1000.0 ... 1000.0] horizontally and [-750 ... 750 vertically, where (-1000.0, -750.0) is the top-left of the image, (0.0, 0.0) the center, and (1000.0, 750.0) the bottom-right corner.

Helper functions are used to do this conversion, see Helper functions to convert coordinates from camera resolution to standardized.

The range [-1000.0 ... 1000.0] is fixed and is not exposed as a parameter so that users of the Kalman2D class will not be tempted to use various ranges, in an effort to standardize the interface between vision modules (which may track object locations using Kalman2D) and motor control (e.g., an Arduino controlling servos on a pan/tilt camera head). The writers of motor control code can reliably assume that object coordinates sent to them will be in the [-1000.0 ... 1000.0] horizontal and [-750 ... 750] vertical range with 0,0 at dead center, and control their motors accordingly.

This code loosely inspired by https://github.com/abreheret/kalman-mouse/blob/master/src/main.cpp

Definition at line 69 of file Kalman2D.H.

Constructor & Destructor Documentation

◆ Kalman2D()

Kalman2D::Kalman2D ( std::string const &  instance)

Constructor.

Definition at line 23 of file Kalman2D.C.

References itsKF.

◆ ~Kalman2D()

Kalman2D::~Kalman2D ( )
virtual

Destructor.

Definition at line 31 of file Kalman2D.C.

Member Function Documentation

◆ get() [1/3]

void Kalman2D::get ( float &  rawx,
float &  rawy,
float &  imgx,
float &  imgy,
unsigned int  imgwidth,
unsigned int  imgheight,
float const  raweps = 0.01F,
float const  imgeps = 0.01F 
)

Function to call each time you want to get the Kalman-filtered coordinates.

It is ok to call get() multiple times with no intervening set(), if you have no new measurements but still want to use the filter output. This variant returns both the coordinates in [0 .. 1000] range (typically, so send to an Arduino for servo control, or other motor plant), and the image coordinates in [0 .. imgwidth[ x [0 .. imgheight[ (typically, to draw on a debug/demo image).

Definition at line 123 of file Kalman2D.C.

References get(), and jevois::coords::stdToImg().

◆ get() [2/3]

void Kalman2D::get ( float &  x,
float &  y,
float const  eps = 0.01F 
)

Function to call each time you want to get the Kalman-filtered coordinates.

It is ok to call get() multiple times with no intervening set(), if you have no new measurements but still want to use the filter output. This variant does not normalize the coordinates, they should typically be in [-1000.0 .. 1000.0] range.

eps is used for rounding of returned coordinates, which is convenient to avoid sending very long floating point values over serial port.

Definition at line 91 of file Kalman2D.C.

References itsFresh, itsKF, and itsLatest.

Referenced by get(), and get().

◆ get() [3/3]

void Kalman2D::get ( float &  x,
float &  y,
unsigned int  imgwidth,
unsigned int  imgheight,
float const  eps = 0.01F 
)

Function to call each time you want to get the Kalman-filtered coordinates.

It is ok to call get() multiple times with no intervening set(), if you have no new measurements but still want to use the filter output. This variant normalizes the coordinates back to image coordinates in [0 .. imgwidth[ x [0 .. imgheight[

Definition at line 116 of file Kalman2D.C.

References get(), and jevois::coords::stdToImg().

◆ onParamChange() [1/4]

void Kalman2D::onParamChange ( kalman2d::measnoise const &  param,
float const &  newval 
)
overrideprotected

◆ onParamChange() [2/4]

void Kalman2D::onParamChange ( kalman2d::postnoise const &  param,
float const &  newval 
)
overrideprotected

◆ onParamChange() [3/4]

void Kalman2D::onParamChange ( kalman2d::procnoise const &  param,
float const &  newval 
)
overrideprotected

◆ onParamChange() [4/4]

void Kalman2D::onParamChange ( kalman2d::usevel const &  param,
bool const &  newval 
)
overrideprotected

◆ postInit()

void Kalman2D::postInit ( )
overrideprotectedvirtual

Reimplemented from jevois::Component.

Definition at line 35 of file Kalman2D.C.

References itsKF.

◆ set() [1/2]

void Kalman2D::set ( float  x,
float  y 
)

Function to call each time you have a new measurement (output from a vision algorithm)

This variant does not normalize the coordinates, they should typically be in [-1000.0 .. 1000.0]

Definition at line 76 of file Kalman2D.C.

References itsFresh, itsKF, itsLatest, and itsMeasurement.

◆ set() [2/2]

void Kalman2D::set ( float  x,
float  y,
unsigned int  imgwidth,
unsigned int  imgheight 
)

Function to call each time you have a new measurement (output from a vision algorithm)

This variant normalizes the image coordinates to the range [-1000.0 .. 1000.0] horizontal and [-750 ... 750] vertical.

Definition at line 84 of file Kalman2D.C.

References jevois::coords::imgToStd(), and set().

Referenced by set().

Friends And Related Symbol Documentation

◆ JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK() [1/4]

JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK ( measnoise  ,
float  ,
"Measurement noise standard deviation"  ,
0.  05F,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK() [2/4]

JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK ( postnoise  ,
float  ,
"A posteriori error estimate standard deviation"  ,
0.  3F,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK() [3/4]

JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK ( procnoise  ,
float  ,
"Process noise standard deviation"  ,
0.  003F,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK() [4/4]

JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK ( usevel  ,
bool  ,
"Use velocity  tracking,
in addition to position"  ,
false  ,
ParamCateg   
)
related

Parameter.

Member Data Documentation

◆ itsFresh

bool Kalman2D::itsFresh
protected

Definition at line 124 of file Kalman2D.H.

Referenced by get(), and set().

◆ itsKF

cv::KalmanFilter Kalman2D::itsKF
protected

Definition at line 120 of file Kalman2D.H.

Referenced by get(), Kalman2D(), postInit(), and set().

◆ itsLatest

cv::Mat Kalman2D::itsLatest
protected

Definition at line 123 of file Kalman2D.H.

Referenced by get(), and set().

◆ itsMeasurement

cv::Mat Kalman2D::itsMeasurement
protected

Definition at line 122 of file Kalman2D.H.

Referenced by set().

◆ itsProcessNoise

cv::Mat Kalman2D::itsProcessNoise
protected

Definition at line 121 of file Kalman2D.H.


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