47 "publish_tag_detections_image",
false);
48 it_ = std::shared_ptr<image_transport::ImageTransport>(
52 it_->subscribeCamera(
"image_rect", 1,
55 nh.
advertise<AprilTagDetectionArray>(
"tag_detections", 1);
56 if (draw_tag_detections_image_)
63 const sensor_msgs::ImageConstPtr& image_rect,
64 const sensor_msgs::CameraInfoConstPtr& camera_info)
85 ROS_ERROR(
"cv_bridge exception: %s", e.what());
cv_bridge::CvImagePtr cv_image_
void publish(const boost::shared_ptr< M > &message) const
image_transport::CameraSubscriber camera_image_subscriber_
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
std::shared_ptr< TagDetector > tag_detector_
void publish(const sensor_msgs::Image &message) const
bool draw_tag_detections_image_
image_transport::Publisher tag_detections_image_publisher_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::shared_ptr< image_transport::ImageTransport > it_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
uint32_t getNumSubscribers() const
void imageCallback(const sensor_msgs::ImageConstPtr &image_rect, const sensor_msgs::CameraInfoConstPtr &camera_info)
ros::Publisher tag_detections_publisher_
PLUGINLIB_EXPORT_CLASS(apriltag_ros::ContinuousDetector, nodelet::Nodelet)