Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 7 additions & 2 deletions apriltag_ros/include/apriltag_ros/continuous_detector.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,28 +48,33 @@
#include <memory>

#include <nodelet/nodelet.h>
#include <std_srvs/Trigger.h>

namespace apriltag_ros
{

class ContinuousDetector: public nodelet::Nodelet
{
public:
ContinuousDetector();
ContinuousDetector();
void onInit();

void imageCallback(const sensor_msgs::ImageConstPtr& image_rect,
const sensor_msgs::CameraInfoConstPtr& camera_info);


bool singleShotService (std_srvs::Trigger::Request& request,
std_srvs::Trigger::Response& response);
private:
std::shared_ptr<TagDetector> tag_detector_;
bool draw_tag_detections_image_;
bool single_shot_detection_;
cv_bridge::CvImagePtr cv_image_;

std::shared_ptr<image_transport::ImageTransport> it_;
image_transport::CameraSubscriber camera_image_subscriber_;
image_transport::Publisher tag_detections_image_publisher_;
ros::Publisher tag_detections_publisher_;
ros::ServiceServer single_shot_service_;
};

} // namespace apriltag_ros
Expand Down
49 changes: 45 additions & 4 deletions apriltag_ros/src/continuous_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,16 +52,29 @@ void ContinuousDetector::onInit ()
"publish_tag_detections_image", false);
it_ = std::shared_ptr<image_transport::ImageTransport>(
new image_transport::ImageTransport(nh));

camera_image_subscriber_ =
it_->subscribeCamera("image_rect", 1,
&ContinuousDetector::imageCallback, this);

single_shot_detection_ = getAprilTagOption<bool>(pnh,
"single_shot_detection", false);

if (!single_shot_detection_)
{
camera_image_subscriber_ =
it_->subscribeCamera("image_rect", 1,
&ContinuousDetector::imageCallback, this);
ROS_INFO("Running in continous mode.");
}
else {
ROS_INFO("Running in single shot detection mode.");
}

tag_detections_publisher_ =
nh.advertise<AprilTagDetectionArray>("tag_detections", 1);
if (draw_tag_detections_image_)
{
tag_detections_image_publisher_ = it_->advertise("tag_detections_image", 1);
}

single_shot_service_ = nh.advertiseService("single_shot_detect_tags", &ContinuousDetector::singleShotService, this);
}

void ContinuousDetector::imageCallback (
Expand Down Expand Up @@ -91,6 +104,34 @@ void ContinuousDetector::imageCallback (
tag_detector_->drawDetections(cv_image_);
tag_detections_image_publisher_.publish(cv_image_->toImageMsg());
}

if (single_shot_detection_)
{
camera_image_subscriber_.shutdown();
}
}

bool ContinuousDetector::singleShotService (
std_srvs::Trigger::Request& request,
std_srvs::Trigger::Response& response)
{
if (!camera_image_subscriber_) {
camera_image_subscriber_ =
it_->subscribeCamera("image_rect", 1,
&ContinuousDetector::imageCallback, this);
response.success = true;
response.message = "Single shot tag detection activated.";
}
else
{
response.success = false;
if (!single_shot_detection_)
response.message = "Not in single shot detection mode.";
else
response.message = "Already waiting for single shot detection.";

}
return true;
}

} // namespace apriltag_ros