Public Member Functions | |
DynamicTrails (ros::NodeHandle &n, ros::NodeHandle &pn) | |
~DynamicTrails () | |
Protected Member Functions | |
float | angleWeight (const Eigen::Vector3f &normal, const Eigen::Vector3f &velocity) |
void | averageWithReference (shared_ptr< DP > reference, shared_ptr< DP > reading, const float dir) |
void | computeVelocity (shared_ptr< DP > reference, shared_ptr< NNS > ref_tree, shared_ptr< DP > reading, shared_ptr< NNS > read_tree, const float maxRadius, const int knn, ros::Publisher debugPub) |
PM::DataPoints | extractDynamicPoints (const PM::DataPoints input, const float minDynamicRatio) |
void | gotCloud (const sensor_msgs::PointCloud2ConstPtr &cloudMsgIn) |
void | gotMap (const sensor_msgs::PointCloud2 &cloudMsgIn) |
void | processCloud (DP cloud, const TP TScannerToMap) |
Private Types | |
typedef PM::Matches | Matches |
typedef Nabo::NearestNeighbourSearch < float > | NNS |
typedef NNS::SearchType | NNSearchType |
typedef PM::TransformationParameters | TP |
Private Attributes | |
ros::Subscriber | cloudSub |
ros::Publisher | dynProjectedPub |
ros::Publisher | dynPub |
const float | eps |
PM::DataPoints | globalMap |
std::shared_ptr< NNS > | globalNNS |
PM::DataPointsFilters | inputFilters |
ros::Time | lastInputTime |
std::shared_ptr< NNS > | lastNNS |
shared_ptr< DP > | lastPointCloud |
ros::Publisher | lastProjectedPub |
ros::Publisher | lastPub |
ros::Subscriber | mapSub |
ros::Publisher | markerPub |
ros::NodeHandle & | n |
const bool | p_accumulateMarkers |
const float | p_inputRate |
const string | p_mapFrame |
const float | p_maxClusterDistance |
const float | p_maxGlobalMapDist |
const float | p_maxVelocity |
const float | p_minDynamicRatio |
const float | p_normalSpaceFactor |
const string | p_trailFilepName |
const int | p_windowSize |
ros::NodeHandle & | pn |
std::deque< shared_ptr< DP > > | priors |
boost::mutex | publishLock |
ros::Subscriber | scanSub |
tf::TransformListener | tfListener |
int | trailCount |
shared_ptr< DP > | trailPointCloud |
unique_ptr< PM::Transformation > | transformation |
boost::mutex | usingGlobalMap |
Definition at line 40 of file dynamic_trails.cpp.
typedef PM::Matches DynamicTrails::Matches [private] |
Definition at line 43 of file dynamic_trails.cpp.
typedef Nabo::NearestNeighbourSearch<float> DynamicTrails::NNS [private] |
Definition at line 45 of file dynamic_trails.cpp.
typedef NNS::SearchType DynamicTrails::NNSearchType [private] |
Definition at line 46 of file dynamic_trails.cpp.
typedef PM::TransformationParameters DynamicTrails::TP [private] |
Definition at line 42 of file dynamic_trails.cpp.
DynamicTrails::DynamicTrails | ( | ros::NodeHandle & | n, |
ros::NodeHandle & | pn | ||
) |
Definition at line 118 of file dynamic_trails.cpp.
Definition at line 180 of file dynamic_trails.cpp.
float DynamicTrails::angleWeight | ( | const Eigen::Vector3f & | normal, |
const Eigen::Vector3f & | velocity | ||
) | [protected] |
Definition at line 839 of file dynamic_trails.cpp.
void DynamicTrails::averageWithReference | ( | shared_ptr< DP > | reference, |
shared_ptr< DP > | reading, | ||
const float | dir | ||
) | [protected] |
Definition at line 857 of file dynamic_trails.cpp.
void DynamicTrails::computeVelocity | ( | shared_ptr< DP > | reference, |
shared_ptr< NNS > | ref_tree, | ||
shared_ptr< DP > | reading, | ||
shared_ptr< NNS > | read_tree, | ||
const float | maxRadius, | ||
const int | knn, | ||
ros::Publisher | debugPub | ||
) | [protected] |
Definition at line 575 of file dynamic_trails.cpp.
PM::DataPoints DynamicTrails::extractDynamicPoints | ( | const PM::DataPoints | input, |
const float | minDynamicRatio | ||
) | [protected] |
Definition at line 516 of file dynamic_trails.cpp.
void DynamicTrails::gotCloud | ( | const sensor_msgs::PointCloud2ConstPtr & | cloudMsgIn | ) | [protected] |
Definition at line 206 of file dynamic_trails.cpp.
void DynamicTrails::gotMap | ( | const sensor_msgs::PointCloud2 & | cloudMsgIn | ) | [protected] |
Definition at line 192 of file dynamic_trails.cpp.
void DynamicTrails::processCloud | ( | DP | cloud, |
const TP | TScannerToMap | ||
) | [protected] |
Definition at line 250 of file dynamic_trails.cpp.
ros::Subscriber DynamicTrails::cloudSub [private] |
Definition at line 58 of file dynamic_trails.cpp.
ros::Publisher DynamicTrails::dynProjectedPub [private] |
Definition at line 63 of file dynamic_trails.cpp.
ros::Publisher DynamicTrails::dynPub [private] |
Definition at line 61 of file dynamic_trails.cpp.
const float DynamicTrails::eps [private] |
Definition at line 84 of file dynamic_trails.cpp.
PM::DataPoints DynamicTrails::globalMap [private] |
Definition at line 70 of file dynamic_trails.cpp.
std::shared_ptr<NNS> DynamicTrails::globalNNS [private] |
Definition at line 72 of file dynamic_trails.cpp.
Definition at line 66 of file dynamic_trails.cpp.
ros::Time DynamicTrails::lastInputTime [private] |
Definition at line 85 of file dynamic_trails.cpp.
std::shared_ptr<NNS> DynamicTrails::lastNNS [private] |
Definition at line 73 of file dynamic_trails.cpp.
shared_ptr<DP> DynamicTrails::lastPointCloud [private] |
Definition at line 68 of file dynamic_trails.cpp.
Definition at line 62 of file dynamic_trails.cpp.
ros::Publisher DynamicTrails::lastPub [private] |
Definition at line 60 of file dynamic_trails.cpp.
ros::Subscriber DynamicTrails::mapSub [private] |
Definition at line 59 of file dynamic_trails.cpp.
ros::Publisher DynamicTrails::markerPub [private] |
Definition at line 64 of file dynamic_trails.cpp.
ros::NodeHandle& DynamicTrails::n [private] |
Definition at line 48 of file dynamic_trails.cpp.
const bool DynamicTrails::p_accumulateMarkers [private] |
Definition at line 95 of file dynamic_trails.cpp.
const float DynamicTrails::p_inputRate [private] |
Definition at line 92 of file dynamic_trails.cpp.
const string DynamicTrails::p_mapFrame [private] |
Definition at line 88 of file dynamic_trails.cpp.
const float DynamicTrails::p_maxClusterDistance [private] |
Definition at line 97 of file dynamic_trails.cpp.
const float DynamicTrails::p_maxGlobalMapDist [private] |
Definition at line 96 of file dynamic_trails.cpp.
const float DynamicTrails::p_maxVelocity [private] |
Definition at line 91 of file dynamic_trails.cpp.
const float DynamicTrails::p_minDynamicRatio [private] |
Definition at line 89 of file dynamic_trails.cpp.
const float DynamicTrails::p_normalSpaceFactor [private] |
Definition at line 90 of file dynamic_trails.cpp.
const string DynamicTrails::p_trailFilepName [private] |
Definition at line 94 of file dynamic_trails.cpp.
const int DynamicTrails::p_windowSize [private] |
Definition at line 93 of file dynamic_trails.cpp.
ros::NodeHandle& DynamicTrails::pn [private] |
Definition at line 49 of file dynamic_trails.cpp.
std::deque<shared_ptr<DP> > DynamicTrails::priors [private] |
Definition at line 77 of file dynamic_trails.cpp.
boost::mutex DynamicTrails::publishLock [private] |
Definition at line 82 of file dynamic_trails.cpp.
ros::Subscriber DynamicTrails::scanSub [private] |
Definition at line 57 of file dynamic_trails.cpp.
Definition at line 80 of file dynamic_trails.cpp.
int DynamicTrails::trailCount [private] |
Definition at line 99 of file dynamic_trails.cpp.
shared_ptr<DP> DynamicTrails::trailPointCloud [private] |
Definition at line 69 of file dynamic_trails.cpp.
unique_ptr<PM::Transformation> DynamicTrails::transformation [private] |
Definition at line 67 of file dynamic_trails.cpp.
boost::mutex DynamicTrails::usingGlobalMap [private] |
Definition at line 75 of file dynamic_trails.cpp.