Public Member Functions | |
| bool | Detect (posedetection_msgs::Feature0D &features, const sensor_msgs::Image &imagemsg) |
| bool | detect_cb (posedetection_msgs::Feature0DDetect::Request &req, posedetection_msgs::Feature0DDetect::Response &res) |
| void | image_cb (const sensor_msgs::ImageConstPtr &msg_ptr) |
| void | info_cb (const sensor_msgs::CameraInfoConstPtr &msg_ptr) |
| StarNode () | |
| virtual | ~StarNode () |
Public Attributes | |
| ros::Time | lasttime |
Private Attributes | |
| bool | _bInfoInitialized |
| image_transport::ImageTransport | _it |
| boost::mutex | _mutex |
| ros::NodeHandle | _node |
| Publisher | _pubStar |
| ros::ServiceServer | _srvDetect |
| image_transport::Subscriber | _subImage |
| Subscriber | _subInfo |
| cv::StarDetector | calc_star |
| posedetection_msgs::ImageFeature0D | star_msg |
Definition at line 42 of file imagestar.cpp.
| StarNode::StarNode | ( | ) | [inline] |
Definition at line 59 of file imagestar.cpp.
| virtual StarNode::~StarNode | ( | ) | [inline, virtual] |
Definition at line 72 of file imagestar.cpp.
| bool StarNode::Detect | ( | posedetection_msgs::Feature0D & | features, |
| const sensor_msgs::Image & | imagemsg | ||
| ) | [inline] |
Definition at line 91 of file imagestar.cpp.
| bool StarNode::detect_cb | ( | posedetection_msgs::Feature0DDetect::Request & | req, |
| posedetection_msgs::Feature0DDetect::Response & | res | ||
| ) | [inline] |
Definition at line 86 of file imagestar.cpp.
| void StarNode::image_cb | ( | const sensor_msgs::ImageConstPtr & | msg_ptr | ) | [inline] |
Definition at line 154 of file imagestar.cpp.
| void StarNode::info_cb | ( | const sensor_msgs::CameraInfoConstPtr & | msg_ptr | ) | [inline] |
Definition at line 79 of file imagestar.cpp.
bool StarNode::_bInfoInitialized [private] |
Definition at line 52 of file imagestar.cpp.
image_transport::ImageTransport StarNode::_it [private] |
Definition at line 46 of file imagestar.cpp.
boost::mutex StarNode::_mutex [private] |
Definition at line 44 of file imagestar.cpp.
ros::NodeHandle StarNode::_node [private] |
Definition at line 45 of file imagestar.cpp.
Publisher StarNode::_pubStar [private] |
Definition at line 50 of file imagestar.cpp.
ros::ServiceServer StarNode::_srvDetect [private] |
Definition at line 48 of file imagestar.cpp.
Definition at line 47 of file imagestar.cpp.
Subscriber StarNode::_subInfo [private] |
Definition at line 49 of file imagestar.cpp.
cv::StarDetector StarNode::calc_star [private] |
Definition at line 54 of file imagestar.cpp.
Definition at line 57 of file imagestar.cpp.
Definition at line 51 of file imagestar.cpp.