Skip to content

Commit

Permalink
linted files and changed templates
Browse files Browse the repository at this point in the history
  • Loading branch information
andrew-aj committed Aug 1, 2022
1 parent 17b6af9 commit 08bfe3f
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 35 deletions.
11 changes: 6 additions & 5 deletions mil_common/utils/mil_tools/include/mil_tools/image_publisher.hpp
Original file line number Diff line number Diff line change
@@ -1,14 +1,15 @@
#include <ros/ros.h>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <ros/ros.h>
#include <opencv2/highgui/highgui.hpp>
#include <cv_bridge/cv_bridge.h>

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_;
Expand Down
51 changes: 24 additions & 27 deletions mil_common/utils/mil_tools/include/mil_tools/image_subscriber.hpp
Original file line number Diff line number Diff line change
@@ -1,38 +1,34 @@
#ifndef IMAGE_SUBSCRIBER_H_
#define IMAGE_SUBSCRIBER_H_

#include <type_traits>
#include <functional>
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/Image.h>
#include <boost/optional.hpp>
#include <image_geometry/pinhole_camera_model.h>
#include <image_transport/image_transport.h>
#include <ros/ros.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/Image.h>
#include <std_msgs/Time.h>
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <image_geometry/pinhole_camera_model.h>
#include <boost/optional.hpp>
#include <functional>
#include <opencv2/opencv.hpp>
#include <type_traits>

template <typename T = void>
class ImageSubscriber
{
public:
template <typename = typename std::enable_if<std::is_same<void, T>::value == false>>
ImageSubscriber(const std::string& topic, std::function<void(T*, cv::Mat&)>& func, T* a,
const std::string& encoding = "bgr8", int queue_size = 1) : encoding_(encoding),
queue_size_(queue_size),
it_(nh_)
public:
template <typename T>
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 <typename = typename std::enable_if<std::is_same<void, T>::value>>
ImageSubscriber(const std::string& topic, std::function<void(cv::Mat&)>& 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;
Expand All @@ -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";
}
Expand All @@ -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();
Expand All @@ -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;
Expand All @@ -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_);
}
Expand All @@ -101,7 +97,8 @@ class ImageSubscriber
{
return camera_info_;
}
private:

private:
std::string encoding_;
int queue_size_;

Expand All @@ -115,4 +112,4 @@ class ImageSubscriber
boost::optional<sensor_msgs::CameraInfo> camera_info_;
boost::optional<std_msgs::Time> last_image_time_;
};
#endif // IMAGE_SUBSCRIBER_H_
#endif // IMAGE_SUBSCRIBER_H_
4 changes: 1 addition & 3 deletions mil_common/utils/mil_tools/src/mil_tools/image_publisher.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include <mil_tools/image_publisher.hpp>

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);
Expand All @@ -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);
}

0 comments on commit 08bfe3f

Please sign in to comment.