#include <MultiRBTrackerNode.h>
Public Member Functions | |
| void | DynamicReconfigureCallback (rb_tracker::RBTrackerDynReconfConfig &config, uint32_t level) |
| Callback for the Dynamic Reconfigure parameters. More... | |
| void | MatthiasRefinementsCallback (const boost::shared_ptr< rbt_state_t const > &matthias_refinements) |
| virtual void | measurementCallback (const boost::shared_ptr< rbt_measurement_ros_t const > &features_pc) |
| Callback for the measurements for this RE level (3D features from the lower level, FT) More... | |
| void | MeasurementFromShapeTrackerCallback (const boost::shared_ptr< omip_msgs::ShapeTrackerStates const > &shape_tracker_states) |
| MultiRBTrackerNode () | |
| void | ReadParameters () |
| void | RGBDPCCallback (const sensor_msgs::PointCloud2ConstPtr &full_pc_msg) |
| virtual void | statePredictionCallback (const boost::shared_ptr< rbt_state_t const > &predicted_next_state) |
| Callback for the predictions about the state of this RE level coming from the higher level of the hierarchy. More... | |
| virtual | ~MultiRBTrackerNode () |
Public Member Functions inherited from omip::RecursiveEstimatorNodeInterface< rbt_measurement_ros_t, rbt_state_ros_t, MultiRBTracker > | |
| bool | getROSParameter (std::string param_name, T ¶m_container) |
| bool | getROSParameter (std::string param_name, T ¶m_container, const T &default_value) |
| virtual void | measurementCallback (const boost::shared_ptr< MeasurementTypeROS const > &measurement)=0 |
| virtual void | quitCallback (const std_msgs::EmptyConstPtr &msg) |
| RecursiveEstimatorNodeInterface (int num_external_state_predictors) | |
| virtual void | run () |
| virtual void | spinStatePredictorQueue (int state_prediction_queue_idx) |
| virtual void | statePredictionCallback (const boost::shared_ptr< StateTypeROS const > &predicted_next_state)=0 |
| virtual | ~RecursiveEstimatorNodeInterface () |
Protected Member Functions | |
| virtual void | _PrintResults () const |
| Print the results of the RB tracker on the terminal. More... | |
| virtual void | _PublishClusteredFeatures () |
| Publish the tracked features clustered in RBs (the cluster id is written in the "label" field of the published PointCloud<PointXYZL> More... | |
| virtual void | _PublishPosesWithCovariance () |
| virtual void | _publishPredictedMeasurement () const |
| Publish the prediction about the next measurement by this RE level. More... | |
| virtual void | _publishState () const |
| Publish the current state of this RE level. More... | |
| virtual void | _PublishTF () |
Definition at line 78 of file MultiRBTrackerNode.h.
| MultiRBTrackerNode::MultiRBTrackerNode | ( | ) |
Constructor
Definition at line 28 of file MultiRBTrackerNode.cpp.
|
virtual |
Destructor
Definition at line 194 of file MultiRBTrackerNode.cpp.
|
protectedvirtual |
Print the results of the RB tracker on the terminal.
Definition at line 400 of file MultiRBTrackerNode.cpp.
|
protectedvirtual |
Publish the tracked features clustered in RBs (the cluster id is written in the "label" field of the published PointCloud<PointXYZL>
Definition at line 488 of file MultiRBTrackerNode.cpp.
|
protectedvirtual |
Write the results of the tracking in the terminal and publish the poses and covariances to ROS
Definition at line 430 of file MultiRBTrackerNode.cpp.
|
protectedvirtual |
Publish the prediction about the next measurement by this RE level.
Implements omip::RecursiveEstimatorNodeInterface< rbt_measurement_ros_t, rbt_state_ros_t, MultiRBTracker >.
Definition at line 389 of file MultiRBTrackerNode.cpp.
|
protectedvirtual |
Publish the current state of this RE level.
Implements omip::RecursiveEstimatorNodeInterface< rbt_measurement_ros_t, rbt_state_ros_t, MultiRBTracker >.
Definition at line 371 of file MultiRBTrackerNode.cpp.
|
protectedvirtual |
Publish the results of the tracking into the TF system of ROS We publish the tracked RBs as frames relative to the camera
Definition at line 460 of file MultiRBTrackerNode.cpp.
| void MultiRBTrackerNode::DynamicReconfigureCallback | ( | rb_tracker::RBTrackerDynReconfConfig & | config, |
| uint32_t | level | ||
| ) |
Callback for the Dynamic Reconfigure parameters.
| config | Values from the Dynamic Reconfigure server |
| level |
Definition at line 198 of file MultiRBTrackerNode.cpp.
| void omip::MultiRBTrackerNode::MatthiasRefinementsCallback | ( | const boost::shared_ptr< rbt_state_t const > & | matthias_refinements | ) |
|
virtual |
Callback for the measurements for this RE level (3D features from the lower level, FT)
| features_pc | Input point cloud of the 3D tracked features |
Definition at line 267 of file MultiRBTrackerNode.cpp.
| void MultiRBTrackerNode::MeasurementFromShapeTrackerCallback | ( | const boost::shared_ptr< omip_msgs::ShapeTrackerStates const > & | shape_tracker_states | ) |
Definition at line 248 of file MultiRBTrackerNode.cpp.
| void MultiRBTrackerNode::ReadParameters | ( | ) |
Read parameters to create the RBMEKFTracker
Definition at line 211 of file MultiRBTrackerNode.cpp.
| void omip::MultiRBTrackerNode::RGBDPCCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | full_pc_msg | ) |
|
virtual |
Callback for the predictions about the state of this RE level coming from the higher level of the hierarchy.
| predicted_next_state | Predictions about the next state (next feature 3D locations) from the RBT |
Definition at line 366 of file MultiRBTrackerNode.cpp.
|
protected |
Definition at line 170 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 166 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 221 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 220 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 164 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 180 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 168 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 225 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 193 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 173 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 189 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 172 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 202 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 205 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 186 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 199 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 169 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 224 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 211 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 192 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 210 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 208 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 209 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 176 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 165 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 191 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 216 of file MultiRBTrackerNode.h.
|
mutableprotected |
Definition at line 215 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 223 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 213 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 183 of file MultiRBTrackerNode.h.
|
protected |
Definition at line 196 of file MultiRBTrackerNode.h.