Public Types | Public Member Functions | Private Attributes
omip::StaticEnvironmentFilter Class Reference

#include <StaticEnvironmentFilter.h>

Inheritance diagram for omip::StaticEnvironmentFilter:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< StaticEnvironmentFilter
Ptr

Public Member Functions

virtual void addSupportingFeature (Feature::Id supporting_feat_id)
virtual void constrainMotion ()
 Function that constrains the last estimated pose of the static environment to the camera according to the motion constraint.
virtual void correctState ()
virtual void estimateDeltaMotion (std::vector< Feature::Id > &supporting_features_ids, tf::Transform &previous_current_Tf)
 Estimate the motion between the last 2 frames of the set of supporting features, assuming they are all on the static environment.
virtual void Init ()
virtual void iterativeICP (pcl::PointCloud< pcl::PointXYZ > &previous_locations, pcl::PointCloud< pcl::PointXYZ > &current_locations, tf::Transform &previous_current_Tf)
 Estimate the transformation between 2 sets of feature locations by iteratively estimating ICP until either the maximum number of iterations is reached or the iterations do not change the transformation (convergence)
virtual void predictState (double time_interval_ns)
virtual void setComputationType (static_environment_tracker_t computation_type)
 Set the computation type for the static environment Options: ICP based (t-1 to t) or EKF based (similar to any other RB)
virtual void setMotionConstraint (int motion_constraint)
 Set a constraint for the motion of the RB Right now this is only used by the StaticEnvironmentFilter.
 StaticEnvironmentFilter (double loop_period_ns, FeaturesDataBase::Ptr feats_database, double environment_motion_threshold)
virtual ~StaticEnvironmentFilter ()

Private Attributes

static_environment_tracker_t _computation_type
double _environment_motion_threshold
int _max_iterations
int _motion_constraint
ros::NodeHandle _nh
pcl::registration::TransformationEstimationSVD
< pcl::PointXYZ, pcl::PointXYZ > 
_svdecomposer
double _tf_epsilon_angular
double _tf_epsilon_linear
tf::TransformListener _tf_listener

Detailed Description

Class StaticEnvironmentICPFilter Represents an special type of RBFilter that tracks the motion of the static environment wrt to the camera Features of the environment that are not moving in the environment support this filter and should be used to estimate the motion of the environment wrt to the camera

Definition at line 63 of file StaticEnvironmentFilter.h.


Member Typedef Documentation

Reimplemented from omip::RBFilter.

Definition at line 68 of file StaticEnvironmentFilter.h.


Constructor & Destructor Documentation

StaticEnvironmentFilter::StaticEnvironmentFilter ( double  loop_period_ns,
FeaturesDataBase::Ptr  feats_database,
double  environment_motion_threshold 
)

Constructor

Parameters:
static_motion_threshold- Threshold to detect Features that move (do not support the static rigid body any longer)

Definition at line 35 of file StaticEnvironmentFilter.cpp.

Destructor

Definition at line 79 of file StaticEnvironmentFilter.h.


Member Function Documentation

void StaticEnvironmentFilter::addSupportingFeature ( Feature::Id  supporting_feat_id) [virtual]

Add the ID of a feature to the list of supporting features of this RB This function is called when a new feature is added to the list of tracked features We create a prediction about its next position (the same it has now) to be used in the support

Parameters:
supporting_feat_id- ID of the Feature that now supports this RB

Reimplemented from omip::RBFilter.

Definition at line 172 of file StaticEnvironmentFilter.cpp.

Function that constrains the last estimated pose of the static environment to the camera according to the motion constraint.

Definition at line 260 of file StaticEnvironmentFilter.cpp.

Correct Correct the predicted next state based on the supporting Features For the StaticRB the state (pose and velocity) is always zero

Reimplemented from omip::RBFilter.

Definition at line 100 of file StaticEnvironmentFilter.cpp.

void StaticEnvironmentFilter::estimateDeltaMotion ( std::vector< Feature::Id > &  supporting_features_ids,
tf::Transform previous_current_Tf 
) [virtual]

Estimate the motion between the last 2 frames of the set of supporting features, assuming they are all on the static environment.

Parameters:
supporting_features_idsIDs of the features that support the static environment
previous_current_TfResulting transformation as a tf transform. It is the transformation of the static environment from the previous to the current frame

Definition at line 193 of file StaticEnvironmentFilter.cpp.

void StaticEnvironmentFilter::Init ( ) [virtual]

Reimplemented from omip::RBFilter.

Definition at line 62 of file StaticEnvironmentFilter.cpp.

void StaticEnvironmentFilter::iterativeICP ( pcl::PointCloud< pcl::PointXYZ > &  previous_locations,
pcl::PointCloud< pcl::PointXYZ > &  current_locations,
tf::Transform previous_current_Tf 
) [virtual]

Estimate the transformation between 2 sets of feature locations by iteratively estimating ICP until either the maximum number of iterations is reached or the iterations do not change the transformation (convergence)

Parameters:
previous_locationsPoint cloud with the previous locations of the features
current_locationsPoint cloud with the current locations of the features
previous_current_TfResulting transformation as a tf transform. It is the transformation of the static environment from the previous to the current frame

Definition at line 217 of file StaticEnvironmentFilter.cpp.

void StaticEnvironmentFilter::predictState ( double  time_interval_ns) [virtual]

Predict Generate a prediction of the next state based on the previous state For the StaticRB the state (pose and velocity) is always zero

Reimplemented from omip::RBFilter.

Definition at line 69 of file StaticEnvironmentFilter.cpp.

Set the computation type for the static environment Options: ICP based (t-1 to t) or EKF based (similar to any other RB)

Parameters:
computation_typeValue of the type of computation (defined in omip_common/OMIPTypeDefs.h)

Definition at line 167 of file StaticEnvironmentFilter.cpp.

void StaticEnvironmentFilter::setMotionConstraint ( int  motion_constraint) [virtual]

Set a constraint for the motion of the RB Right now this is only used by the StaticEnvironmentFilter.

Parameters:
motion_constraintValue of the motion constraint. The meaning of each value is in motion_estimation.h

Reimplemented from omip::RBFilter.

Definition at line 162 of file StaticEnvironmentFilter.cpp.


Member Data Documentation

Definition at line 161 of file StaticEnvironmentFilter.h.

Definition at line 151 of file StaticEnvironmentFilter.h.

Definition at line 154 of file StaticEnvironmentFilter.h.

Definition at line 152 of file StaticEnvironmentFilter.h.

Definition at line 158 of file StaticEnvironmentFilter.h.

pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ> omip::StaticEnvironmentFilter::_svdecomposer [private]

Definition at line 163 of file StaticEnvironmentFilter.h.

Definition at line 156 of file StaticEnvironmentFilter.h.

Definition at line 155 of file StaticEnvironmentFilter.h.

Definition at line 159 of file StaticEnvironmentFilter.h.


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


rb_tracker
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:26:42