Public Member Functions | Protected Member Functions
omip::DisconnectedJointFilter Class Reference

#include <DisconnectedJointFilter.h>

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

List of all members.

Public Member Functions

DisconnectedJointFilterPtr clone () const
 DisconnectedJointFilter ()
 DisconnectedJointFilter (const DisconnectedJointFilter &rigid_joint)
virtual JointFilterType getJointFilterType () const
virtual std::string getJointFilterTypeStr () const
virtual std::vector
< visualization_msgs::Marker > 
getJointMarkersInRRBFrame () const
virtual
geometry_msgs::TwistWithCovariance 
getPredictedSRBDeltaPoseWithCovInSensorFrame ()
 Generate a prediction about the change in pose of the second rigid body (SRB) and its covariance using the frame of sensor (SF) as observation and ref frame based on the predicted measurement and the predicted next pose of the reference rigid body (RRB) in the sensor frame (SF)
virtual
geometry_msgs::TwistWithCovariance 
getPredictedSRBPoseWithCovInSensorFrame ()
 Generate a prediction about the pose-twist of the second rigid body (SRB) and its covariance using the frame of sensor (SF) as observation and ref frame based on the predicted measurement and the predicted next pose of the reference rigid body (RRB) in the sensor frame (SF)
virtual
geometry_msgs::TwistWithCovariance 
getPredictedSRBVelocityWithCovInSensorFrame ()
 Generate a prediction about the velocity of the second rigid body (SRB) and its covariance using the frame of sensor (SF) as observation and ref frame based on the predicted measurement and the predicted next pose of the reference rigid body (RRB) in the sensor frame (SF)
virtual double getProbabilityOfJointFilter () const
 Return the normalized joint filter probability of the Disconnected Joint model, which is a constant value we set at the beginning and use as quality threshold for the other models.
virtual void initialize ()
virtual ~DisconnectedJointFilter ()

Protected Member Functions

virtual DisconnectedJointFilterdoClone () const

Detailed Description

Definition at line 43 of file DisconnectedJointFilter.h.


Constructor & Destructor Documentation

Constructor

Definition at line 7 of file DisconnectedJointFilter.cpp.

Destructor

Definition at line 13 of file DisconnectedJointFilter.cpp.

Copy constructor

Definition at line 18 of file DisconnectedJointFilter.cpp.


Member Function Documentation

DisconnectedJointFilterPtr omip::DisconnectedJointFilter::clone ( ) const [inline]

Creates a new Joint object with the same values as this one and passes its reference

Returns:
- A reference to the clone of this Feature object

Reimplemented from omip::JointFilter.

Definition at line 63 of file DisconnectedJointFilter.h.

virtual DisconnectedJointFilter* omip::DisconnectedJointFilter::doClone ( ) const [inline, protected, virtual]

A Disconnected Joint does not constrain any of the 6 dofs of the relative motion between RBs Disconnected Joints have no motion parameters Disconnected Joints have no latent variables

Implements omip::JointFilter.

Definition at line 133 of file DisconnectedJointFilter.h.

JointFilterType DisconnectedJointFilter::getJointFilterType ( ) const [virtual]

Return the joint type as one of the possible JointFilterTypes

Implements omip::JointFilter.

Definition at line 203 of file DisconnectedJointFilter.cpp.

std::string DisconnectedJointFilter::getJointFilterTypeStr ( ) const [virtual]

Return the joint type as an string

Implements omip::JointFilter.

Definition at line 208 of file DisconnectedJointFilter.cpp.

std::vector< visualization_msgs::Marker > DisconnectedJointFilter::getJointMarkersInRRBFrame ( ) const [virtual]

Return rviz markers that show the type and parameters of the estimated joint

Implements omip::JointFilter.

Definition at line 167 of file DisconnectedJointFilter.cpp.

geometry_msgs::TwistWithCovariance DisconnectedJointFilter::getPredictedSRBDeltaPoseWithCovInSensorFrame ( ) [virtual]

Generate a prediction about the change in pose of the second rigid body (SRB) and its covariance using the frame of sensor (SF) as observation and ref frame based on the predicted measurement and the predicted next pose of the reference rigid body (RRB) in the sensor frame (SF)

Returns:
geometry_msgs::TwistWithCovariance Change in pose of the second rigid body in form of a twist with covariance based on the model uncertainty

Implements omip::JointFilter.

Definition at line 33 of file DisconnectedJointFilter.cpp.

geometry_msgs::TwistWithCovariance DisconnectedJointFilter::getPredictedSRBPoseWithCovInSensorFrame ( ) [virtual]

Generate a prediction about the pose-twist of the second rigid body (SRB) and its covariance using the frame of sensor (SF) as observation and ref frame based on the predicted measurement and the predicted next pose of the reference rigid body (RRB) in the sensor frame (SF)

Implements omip::JointFilter.

Definition at line 103 of file DisconnectedJointFilter.cpp.

geometry_msgs::TwistWithCovariance DisconnectedJointFilter::getPredictedSRBVelocityWithCovInSensorFrame ( ) [virtual]

Generate a prediction about the velocity of the second rigid body (SRB) and its covariance using the frame of sensor (SF) as observation and ref frame based on the predicted measurement and the predicted next pose of the reference rigid body (RRB) in the sensor frame (SF)

Returns:
geometry_msgs::TwistWithCovariance Velocity of the second rigid body in form of a twist with covariance based on the model uncertainty

Implements omip::JointFilter.

Definition at line 68 of file DisconnectedJointFilter.cpp.

Return the normalized joint filter probability of the Disconnected Joint model, which is a constant value we set at the beginning and use as quality threshold for the other models.

Returns:
double Normalized probability of this joint filter

Reimplemented from omip::JointFilter.

Definition at line 28 of file DisconnectedJointFilter.cpp.

Reimplemented from omip::JointFilter.

Definition at line 23 of file DisconnectedJointFilter.cpp.


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


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