#include <MultiRBTrackerNode.h>
Public Member Functions | |
| void | DynamicReconfigureCallback (rb_tracker::RBTrackerDynReconfConfig &config, uint32_t level) |
| Callback for the Dynamic Reconfigure parameters. | |
| 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) | |
| 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. | |
| virtual | ~MultiRBTrackerNode () |
Protected Member Functions | |
| virtual void | _PrintResults () const |
| Print the results of the RB tracker on the terminal. | |
| virtual void | _PublishClusteredFeatures () |
| Publish the tracked features clustered in RBs (the cluster id is written in the "label" field of the published PointCloud<PointXYZL> | |
| virtual void | _PublishPosesWithCovariance () |
| virtual void | _publishPredictedMeasurement () const |
| Publish the prediction about the next measurement by this RE level. | |
| virtual void | _publishState () const |
| Publish the current state of this RE level. | |
| virtual void | _PublishTF () |
Protected Attributes | |
| ros::Publisher | _atbirthfeats_pc_publisher |
| ros::Publisher | _clustered_pc_publisher |
| dynamic_reconfigure::Server < rb_tracker::RBTrackerDynReconfConfig > ::CallbackType | _dr_callback |
| dynamic_reconfigure::Server < rb_tracker::RBTrackerDynReconfConfig > | _dr_srv |
| std::map< RB_id_t, ros::Publisher * > | _est_body_publishers |
| double | _estimation_error_threshold |
| ros::Publisher | _freefeats_pc_publisher |
| rbt_state_t | _last_predictions_kh |
| double | _loop_period_ns |
| ros::Subscriber | _matthias_refinements_subscriber |
| double | _max_error_to_reassign_feats |
| ros::Subscriber | _meas_from_st_subscriber |
| int | _min_num_feats_for_new_rb |
| int | _min_num_frames_for_new_rb |
| double | _new_rbm_error_threshold |
| int | _num_tracked_feats |
| ros::Publisher | _predictedfeats_pc_publisher |
| Eigen::Twistd | _previous_twist |
| bool | _printing_rb_poses |
| int | _processing_factor |
| bool | _publishing_clustered_pc |
| bool | _publishing_rbposes_with_cov |
| bool | _publishing_tf |
| int | _ransac_iterations |
| ros::Publisher | _rbposes_publisher |
| double | _sensor_fps |
| omip_msgs::ShapeTrackerStates | _shape_tracker_meas |
| bool | _shape_tracker_received |
| ros::Publisher | _state_publisher2 |
| static_environment_tracker_t | _static_environment_tracker_type |
| double | _static_motion_threshold |
| int | _supporting_features_threshold |
Definition at line 78 of file MultiRBTrackerNode.h.
Constructor
Definition at line 28 of file MultiRBTrackerNode.cpp.
| MultiRBTrackerNode::~MultiRBTrackerNode | ( | ) | [virtual] |
Destructor
Definition at line 194 of file MultiRBTrackerNode.cpp.
| void MultiRBTrackerNode::_PrintResults | ( | ) | const [protected, virtual] |
Print the results of the RB tracker on the terminal.
Definition at line 400 of file MultiRBTrackerNode.cpp.
| void MultiRBTrackerNode::_PublishClusteredFeatures | ( | ) | [protected, virtual] |
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.
| void MultiRBTrackerNode::_PublishPosesWithCovariance | ( | ) | [protected, virtual] |
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.
| void MultiRBTrackerNode::_publishPredictedMeasurement | ( | ) | const [protected, virtual] |
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.
| void MultiRBTrackerNode::_publishState | ( | ) | const [protected, virtual] |
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.
| void MultiRBTrackerNode::_PublishTF | ( | ) | [protected, virtual] |
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 | ) |
| void MultiRBTrackerNode::measurementCallback | ( | const boost::shared_ptr< rbt_measurement_ros_t const > & | features_pc | ) | [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 | ) |
| void MultiRBTrackerNode::statePredictionCallback | ( | const boost::shared_ptr< rbt_state_t const > & | predicted_next_state | ) | [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.
Definition at line 170 of file MultiRBTrackerNode.h.
Definition at line 166 of file MultiRBTrackerNode.h.
dynamic_reconfigure::Server<rb_tracker::RBTrackerDynReconfConfig>::CallbackType omip::MultiRBTrackerNode::_dr_callback [protected] |
Definition at line 221 of file MultiRBTrackerNode.h.
dynamic_reconfigure::Server<rb_tracker::RBTrackerDynReconfConfig> omip::MultiRBTrackerNode::_dr_srv [protected] |
Definition at line 220 of file MultiRBTrackerNode.h.
std::map<RB_id_t, ros::Publisher*> omip::MultiRBTrackerNode::_est_body_publishers [protected] |
Definition at line 164 of file MultiRBTrackerNode.h.
double omip::MultiRBTrackerNode::_estimation_error_threshold [protected] |
Definition at line 180 of file MultiRBTrackerNode.h.
Definition at line 168 of file MultiRBTrackerNode.h.
Definition at line 225 of file MultiRBTrackerNode.h.
double omip::MultiRBTrackerNode::_loop_period_ns [protected] |
Reimplemented from omip::RecursiveEstimatorNodeInterface< rbt_measurement_ros_t, rbt_state_ros_t, MultiRBTracker >.
Definition at line 193 of file MultiRBTrackerNode.h.
Definition at line 173 of file MultiRBTrackerNode.h.
double omip::MultiRBTrackerNode::_max_error_to_reassign_feats [protected] |
Definition at line 189 of file MultiRBTrackerNode.h.
Definition at line 172 of file MultiRBTrackerNode.h.
int omip::MultiRBTrackerNode::_min_num_feats_for_new_rb [protected] |
Definition at line 202 of file MultiRBTrackerNode.h.
int omip::MultiRBTrackerNode::_min_num_frames_for_new_rb [protected] |
Definition at line 205 of file MultiRBTrackerNode.h.
double omip::MultiRBTrackerNode::_new_rbm_error_threshold [protected] |
Definition at line 186 of file MultiRBTrackerNode.h.
int omip::MultiRBTrackerNode::_num_tracked_feats [protected] |
Definition at line 199 of file MultiRBTrackerNode.h.
Definition at line 169 of file MultiRBTrackerNode.h.
Definition at line 224 of file MultiRBTrackerNode.h.
bool omip::MultiRBTrackerNode::_printing_rb_poses [protected] |
Definition at line 211 of file MultiRBTrackerNode.h.
int omip::MultiRBTrackerNode::_processing_factor [protected] |
Definition at line 192 of file MultiRBTrackerNode.h.
bool omip::MultiRBTrackerNode::_publishing_clustered_pc [protected] |
Definition at line 210 of file MultiRBTrackerNode.h.
bool omip::MultiRBTrackerNode::_publishing_rbposes_with_cov [protected] |
Definition at line 208 of file MultiRBTrackerNode.h.
bool omip::MultiRBTrackerNode::_publishing_tf [protected] |
Definition at line 209 of file MultiRBTrackerNode.h.
int omip::MultiRBTrackerNode::_ransac_iterations [protected] |
Definition at line 176 of file MultiRBTrackerNode.h.
Definition at line 165 of file MultiRBTrackerNode.h.
double omip::MultiRBTrackerNode::_sensor_fps [protected] |
Definition at line 191 of file MultiRBTrackerNode.h.
omip_msgs::ShapeTrackerStates omip::MultiRBTrackerNode::_shape_tracker_meas [protected] |
Definition at line 216 of file MultiRBTrackerNode.h.
bool omip::MultiRBTrackerNode::_shape_tracker_received [mutable, protected] |
Definition at line 215 of file MultiRBTrackerNode.h.
Definition at line 223 of file MultiRBTrackerNode.h.
Definition at line 213 of file MultiRBTrackerNode.h.
double omip::MultiRBTrackerNode::_static_motion_threshold [protected] |
Definition at line 183 of file MultiRBTrackerNode.h.
int omip::MultiRBTrackerNode::_supporting_features_threshold [protected] |
Definition at line 196 of file MultiRBTrackerNode.h.