32 #ifndef DISCONNECTEDJOINTFILTER_H_ 33 #define DISCONNECTEDJOINTFILTER_H_ 63 DisconnectedJointFilterPtr
clone()
const
DisconnectedJointFilterPtr clone() const
virtual geometry_msgs::TwistWithCovariance getPredictedSRBVelocityWithCovInSensorFrame()
Generate a prediction about the velocity of the second rigid body (SRB) and its covariance using the ...
virtual geometry_msgs::TwistWithCovariance getPredictedSRBDeltaPoseWithCovInSensorFrame()
Generate a prediction about the change in pose of the second rigid body (SRB) and its covariance usin...
boost::shared_ptr< DisconnectedJointFilter > DisconnectedJointFilterPtr
virtual double getProbabilityOfJointFilter() const
Return the normalized joint filter probability of the Disconnected Joint model, which is a constant v...
virtual JointFilterType getJointFilterType() const
virtual std::string getJointFilterTypeStr() const
virtual DisconnectedJointFilter * doClone() const
DisconnectedJointFilter()
virtual ~DisconnectedJointFilter()
virtual geometry_msgs::TwistWithCovariance getPredictedSRBPoseWithCovInSensorFrame()
Generate a prediction about the pose-twist of the second rigid body (SRB) and its covariance using th...
virtual std::vector< visualization_msgs::Marker > getJointMarkersInRRBFrame() const
virtual void initialize()