#include <detector_node.h>
Public Member Functions | |
void | cam_info_callback (const sensor_msgs::CameraInfo &msg) |
DetectorNode (std::string root=".") | |
void | reconf_callback (blort_ros::DetectorConfig &config, uint32_t level) |
bool | recovery (blort_msgs::RecoveryCall::Request &req, blort_msgs::RecoveryCall::Response &resp) |
bool | setCameraInfoCb (blort_msgs::SetCameraInfo::Request &req, blort_msgs::SetCameraInfo::Response &resp) |
~DetectorNode () | |
Private Attributes | |
ros::ServiceServer | cam_info_service |
ros::Subscriber | cam_info_sub |
unsigned int | counter |
blort_ros::GLDetector * | detector |
dynamic_reconfigure::Server < blort_ros::DetectorConfig > ::CallbackType | f_ |
image_transport::Publisher | image_pub |
image_transport::ImageTransport | it_ |
ros::NodeHandle | nh_ |
double | nn_match_threshold |
ros::ServiceServer | pose_service |
int | ransac_n_points_to_match |
const std::string | root_ |
std::auto_ptr < dynamic_reconfigure::Server < blort_ros::DetectorConfig > > | server_ |
Definition at line 51 of file detector_node.h.
DetectorNode::DetectorNode | ( | std::string | root = "." | ) |
Definition at line 3 of file detector_node.cpp.
Definition at line 17 of file detector_node.cpp.
void DetectorNode::cam_info_callback | ( | const sensor_msgs::CameraInfo & | msg | ) |
Definition at line 88 of file detector_node.cpp.
void DetectorNode::reconf_callback | ( | blort_ros::DetectorConfig & | config, |
uint32_t | level | ||
) |
Definition at line 77 of file detector_node.cpp.
bool DetectorNode::recovery | ( | blort_msgs::RecoveryCall::Request & | req, |
blort_msgs::RecoveryCall::Response & | resp | ||
) |
Definition at line 23 of file detector_node.cpp.
bool DetectorNode::setCameraInfoCb | ( | blort_msgs::SetCameraInfo::Request & | req, |
blort_msgs::SetCameraInfo::Response & | resp | ||
) |
Definition at line 69 of file detector_node.cpp.
Definition at line 60 of file detector_node.h.
ros::Subscriber DetectorNode::cam_info_sub [private] |
Definition at line 57 of file detector_node.h.
unsigned int DetectorNode::counter [private] |
Definition at line 64 of file detector_node.h.
blort_ros::GLDetector* DetectorNode::detector [private] |
Definition at line 63 of file detector_node.h.
dynamic_reconfigure::Server<blort_ros::DetectorConfig>::CallbackType DetectorNode::f_ [private] |
Definition at line 62 of file detector_node.h.
Definition at line 56 of file detector_node.h.
Definition at line 55 of file detector_node.h.
ros::NodeHandle DetectorNode::nh_ [private] |
Definition at line 54 of file detector_node.h.
double DetectorNode::nn_match_threshold [private] |
Definition at line 66 of file detector_node.h.
ros::ServiceServer DetectorNode::pose_service [private] |
Definition at line 59 of file detector_node.h.
int DetectorNode::ransac_n_points_to_match [private] |
Definition at line 67 of file detector_node.h.
const std::string DetectorNode::root_ [private] |
Definition at line 58 of file detector_node.h.
std::auto_ptr<dynamic_reconfigure::Server<blort_ros::DetectorConfig> > DetectorNode::server_ [private] |
Definition at line 61 of file detector_node.h.