diff --git a/mil_common/utils/mil_tools/include/mil_tools/image_publisher.hpp b/mil_common/utils/mil_tools/include/mil_tools/image_publisher.hpp index e6115cfd6..1217dde9e 100644 --- a/mil_common/utils/mil_tools/include/mil_tools/image_publisher.hpp +++ b/mil_common/utils/mil_tools/include/mil_tools/image_publisher.hpp @@ -1,14 +1,15 @@ -#include +#include #include +#include #include -#include class ImagePublisher { - public: - ImagePublisher(const std::string & topic, const std::string &encoding = "bgr8",int queue_size = 1); +public: + ImagePublisher(const std::string& topic, const std::string& encoding = "bgr8", int queue_size = 1); void publish(cv::Mat& image_arg); - private: + +private: std::string encoding_; image_transport::Publisher pub_; ros::NodeHandle nh_; diff --git a/mil_common/utils/mil_tools/include/mil_tools/image_subscriber.hpp b/mil_common/utils/mil_tools/include/mil_tools/image_subscriber.hpp index 363fdecf3..3575cb8a6 100644 --- a/mil_common/utils/mil_tools/include/mil_tools/image_subscriber.hpp +++ b/mil_common/utils/mil_tools/include/mil_tools/image_subscriber.hpp @@ -1,38 +1,34 @@ #ifndef IMAGE_SUBSCRIBER_H_ #define IMAGE_SUBSCRIBER_H_ -#include -#include -#include #include -#include -#include +#include +#include +#include #include +#include #include -#include -#include -#include +#include +#include +#include +#include -template class ImageSubscriber { - public: - template ::value == false>> - ImageSubscriber(const std::string& topic, std::function& func, T* a, - const std::string& encoding = "bgr8", int queue_size = 1) : encoding_(encoding), - queue_size_(queue_size), - it_(nh_) +public: + template + ImageSubscriber(const std::string& topic, void (T::*func)(cv::Mat&), T* a, const std::string& encoding = "bgr8", + int queue_size = 1) + : encoding_(encoding), queue_size_(queue_size), it_(nh_) { image_subscriber_ = it_.subscribe(topic, queue_size, &ImageSubscriber::imageCallback, this); function_ = std::bind(func, a, std::placeholders::_1); camera_info_sub_ = nh_.subscribe(getInfoTopic(topic), queue_size, &ImageSubscriber::infoCallback, this); } - template ::value>> - ImageSubscriber(const std::string& topic, std::function& func, - const std::string& encoding = "bgr8", int queue_size = 1) : encoding_(encoding), - queue_size_(queue_size), - it_(nh_) + ImageSubscriber(const std::string& topic, void (*func)(cv::Mat&), const std::string& encoding = "bgr8", + int queue_size = 1) + : encoding_(encoding), queue_size_(queue_size), it_(nh_) { image_subscriber_ = it_.subscribe(topic, queue_size, &ImageSubscriber::imageCallback, this); function_ = func; @@ -42,7 +38,7 @@ class ImageSubscriber std::string getInfoTopic(const std::string& input) { int location = input.rfind('/'); - if(location == input.length() - 1) + if (location == input.length() - 1) location = input.rfind('/', input.length() - 2); return input.substr(0, location - 1) + "/camera_info"; } @@ -55,9 +51,9 @@ class ImageSubscriber time.sleep(); auto start_time = ros::Time::now(); - while(ros::Time::now() - start_time < time && ros::ok()) + while (ros::Time::now() - start_time < time && ros::ok()) { - if(camera_info_.has_value()) + if (camera_info_.has_value()) { ROS_INFO("Camera info found!"); return camera_info_.get(); @@ -72,7 +68,7 @@ class ImageSubscriber bool waitForCameraModel(image_geometry::PinholeCameraModel& pinhole_camera, unsigned int timeout = 10) { auto msg = waitForCameraInfo(timeout); - if(!msg) + if (!msg) return false; pinhole_camera.fromCameraInfo(msg); return true; @@ -91,7 +87,7 @@ class ImageSubscriber last_image_time_ = image.header.stamp; function_(cv_bridge::toCvCopy(image, encoding_)->image); } - catch(cv_bridge::Exception& e) + catch (cv_bridge::Exception& e) { ROS_ERROR("Could not convert from '%s' to '%s'.", image->encoding, encoding_); } @@ -101,7 +97,8 @@ class ImageSubscriber { return camera_info_; } - private: + +private: std::string encoding_; int queue_size_; @@ -115,4 +112,4 @@ class ImageSubscriber boost::optional camera_info_; boost::optional last_image_time_; }; -#endif // IMAGE_SUBSCRIBER_H_ +#endif // IMAGE_SUBSCRIBER_H_ diff --git a/mil_common/utils/mil_tools/src/mil_tools/image_publisher.cpp b/mil_common/utils/mil_tools/src/mil_tools/image_publisher.cpp index dc5a28bdd..c8524a30b 100644 --- a/mil_common/utils/mil_tools/src/mil_tools/image_publisher.cpp +++ b/mil_common/utils/mil_tools/src/mil_tools/image_publisher.cpp @@ -1,7 +1,6 @@ #include -ImagePublisher::ImagePublisher(const std::string & topic, const std::string &encoding,int queue_size) : - it_(nh_) +ImagePublisher::ImagePublisher(const std::string& topic, const std::string& encoding, int queue_size) : it_(nh_) { this->encoding_ = encoding; pub_ = it_.advertise(topic, queue_size); @@ -13,4 +12,3 @@ void ImagePublisher::publish(cv::Mat& image_arg) sensor_msgs::ImagePtr msg = cv_bridge::CvImage(header, encoding_, image_arg).toImageMsg(); pub_.publish(msg); } -