Public Member Functions | |
void | cameraInfoSubCallback (sensor_msgs::CameraInfo::ConstPtr pc_in) |
void | dynReconfCallback (cob_keyframe_detector::keyframe_detectorConfig &config, uint32_t level) |
KeyframeDetector () | |
void | transformSubCallback (const tf::tfMessageConstPtr &msg) |
bool | triggerKeyFrame () |
~KeyframeDetector () | |
Protected Attributes | |
ros::Subscriber | camera_info_sub_ |
dynamic_reconfigure::Server < cob_keyframe_detector::keyframe_detectorConfig > | config_server_ |
double | distance_limit_ |
bool | first_ |
std::string | frame_id_ |
ros::ServiceClient | keyframe_trigger_client_ |
boost::mutex | m_mutex_pointCloudSubCallback |
ros::NodeHandle | n_ |
double | p_limit_ |
double | r_limit_ |
ros::Time | stamp_ |
TransformListener | tf_listener_ |
StampedTransform | transform_old_ |
ros::Subscriber | transform_sub_ |
bool | trigger_always_ |
double | y_limit_ |
Definition at line 85 of file keyframe_detector.cpp.
KeyframeDetector::KeyframeDetector | ( | ) | [inline] |
Definition at line 90 of file keyframe_detector.cpp.
KeyframeDetector::~KeyframeDetector | ( | ) | [inline] |
void
Definition at line 102 of file keyframe_detector.cpp.
void KeyframeDetector::cameraInfoSubCallback | ( | sensor_msgs::CameraInfo::ConstPtr | pc_in | ) | [inline] |
Definition at line 117 of file keyframe_detector.cpp.
void KeyframeDetector::dynReconfCallback | ( | cob_keyframe_detector::keyframe_detectorConfig & | config, |
uint32_t | level | ||
) | [inline] |
Definition at line 107 of file keyframe_detector.cpp.
void KeyframeDetector::transformSubCallback | ( | const tf::tfMessageConstPtr & | msg | ) | [inline] |
Definition at line 123 of file keyframe_detector.cpp.
bool KeyframeDetector::triggerKeyFrame | ( | ) | [inline] |
Definition at line 158 of file keyframe_detector.cpp.
ros::Subscriber KeyframeDetector::camera_info_sub_ [protected] |
Definition at line 177 of file keyframe_detector.cpp.
dynamic_reconfigure::Server<cob_keyframe_detector::keyframe_detectorConfig> KeyframeDetector::config_server_ [protected] |
Definition at line 180 of file keyframe_detector.cpp.
double KeyframeDetector::distance_limit_ [protected] |
Definition at line 190 of file keyframe_detector.cpp.
bool KeyframeDetector::first_ [protected] |
Definition at line 182 of file keyframe_detector.cpp.
std::string KeyframeDetector::frame_id_ [protected] |
Definition at line 187 of file keyframe_detector.cpp.
Definition at line 179 of file keyframe_detector.cpp.
boost::mutex KeyframeDetector::m_mutex_pointCloudSubCallback [protected] |
Definition at line 194 of file keyframe_detector.cpp.
ros::NodeHandle KeyframeDetector::n_ [protected] |
Definition at line 175 of file keyframe_detector.cpp.
double KeyframeDetector::p_limit_ [protected] |
Definition at line 192 of file keyframe_detector.cpp.
double KeyframeDetector::r_limit_ [protected] |
Definition at line 191 of file keyframe_detector.cpp.
ros::Time KeyframeDetector::stamp_ [protected] |
Definition at line 176 of file keyframe_detector.cpp.
TransformListener KeyframeDetector::tf_listener_ [protected] |
Definition at line 178 of file keyframe_detector.cpp.
StampedTransform KeyframeDetector::transform_old_ [protected] |
Definition at line 185 of file keyframe_detector.cpp.
ros::Subscriber KeyframeDetector::transform_sub_ [protected] |
Definition at line 177 of file keyframe_detector.cpp.
bool KeyframeDetector::trigger_always_ [protected] |
Definition at line 183 of file keyframe_detector.cpp.
double KeyframeDetector::y_limit_ [protected] |
Definition at line 189 of file keyframe_detector.cpp.