include
camera_throttle
camera_throttle.h
Go to the documentation of this file.
1
#pragma once
2
3
#include <memory>
4
#include <mutex>
5
#include <optional>
6
7
#include <
cras_cpp_common/nodelet_utils.hpp
>
8
#include <
image_transport/camera_subscriber.h
>
9
#include <
image_transport/camera_publisher.h
>
10
11
namespace
camera_throttle
12
{
13
36
class
CameraThrottleNodelet
:
public
cras::Nodelet
37
{
38
public
:
CameraThrottleNodelet
();
39
public
:
virtual
~CameraThrottleNodelet
() {};
40
41
protected
:
void
onInit
()
override
;
42
43
protected
:
virtual
void
cb
(
const
sensor_msgs::ImageConstPtr& img,
const
sensor_msgs::CameraInfoConstPtr& info);
44
45
protected
:
virtual
void
onFirstConnect
();
46
protected
:
virtual
void
onLastDisconnect
();
47
48
protected
:
ros::NodeHandle
subNh
;
49
protected
:
ros::NodeHandle
pubNh
;
50
protected
: std::unique_ptr<image_transport::ImageTransport>
subTransport
;
51
protected
: std::unique_ptr<image_transport::ImageTransport>
pubTransport
;
52
protected
: std::optional<image_transport::CameraSubscriber>
sub
;
53
protected
:
image_transport::CameraPublisher
pub
;
54
protected
: std::optional<ros::Rate>
rate
;
55
protected
: std::optional<std::string>
frameId
;
56
protected
:
bool
flipHorizontal
{
false
};
57
protected
:
bool
flipVertical
{
false
};
58
protected
:
size_t
queueSize
{10};
59
protected
:
ros::Time
lastUpdate
;
60
protected
: std::string
subBaseName
;
61
protected
: std::string
pubBaseName
;
62
63
protected
: std::mutex
publishersMutex
;
64
65
private
:
void
img_connect_cb
(
const
image_transport::SingleSubscriberPublisher
&);
66
private
:
void
info_connect_cb
(
const
ros::SingleSubscriberPublisher
&);
67
private
:
void
img_disconnect_cb
(
const
image_transport::SingleSubscriberPublisher
&);
68
private
:
void
info_disconnect_cb
(
const
ros::SingleSubscriberPublisher
&);
69
70
struct
CameraThrottlePrivate
;
71
private
: std::unique_ptr<CameraThrottlePrivate>
data
;
72
};
73
74
}
75
camera_throttle::CameraThrottleNodelet::pubBaseName
std::string pubBaseName
Definition:
camera_throttle.h:61
camera_throttle::CameraThrottleNodelet::pub
image_transport::CameraPublisher pub
Definition:
camera_throttle.h:53
camera_throttle::CameraThrottleNodelet::subTransport
std::unique_ptr< image_transport::ImageTransport > subTransport
Definition:
camera_throttle.h:50
camera_throttle::CameraThrottleNodelet::publishersMutex
std::mutex publishersMutex
Definition:
camera_throttle.h:63
camera_throttle::CameraThrottleNodelet::info_connect_cb
void info_connect_cb(const ros::SingleSubscriberPublisher &)
Definition:
camera_throttle.cpp:119
camera_throttle::CameraThrottleNodelet::subNh
ros::NodeHandle subNh
Definition:
camera_throttle.h:48
camera_throttle::CameraThrottleNodelet
Definition:
camera_throttle.h:36
camera_throttle::CameraThrottleNodelet::data
std::unique_ptr< CameraThrottlePrivate > data
Definition:
camera_throttle.h:70
camera_throttle::CameraThrottleNodelet::cb
virtual void cb(const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info)
Definition:
camera_throttle.cpp:54
camera_throttle::CameraThrottleNodelet::pubTransport
std::unique_ptr< image_transport::ImageTransport > pubTransport
Definition:
camera_throttle.h:51
camera_throttle::CameraThrottleNodelet::img_connect_cb
void img_connect_cb(const image_transport::SingleSubscriberPublisher &)
Definition:
camera_throttle.cpp:112
ros::SingleSubscriberPublisher
camera_throttle::CameraThrottleNodelet::flipHorizontal
bool flipHorizontal
Definition:
camera_throttle.h:56
camera_throttle::CameraThrottleNodelet::img_disconnect_cb
void img_disconnect_cb(const image_transport::SingleSubscriberPublisher &)
Definition:
camera_throttle.cpp:126
camera_throttle::CameraThrottleNodelet::onInit
void onInit() override
Definition:
camera_throttle.cpp:21
camera_throttle::CameraThrottleNodelet::onFirstConnect
virtual void onFirstConnect()
Definition:
camera_throttle.cpp:140
camera_subscriber.h
image_transport::CameraPublisher
camera_throttle::CameraThrottleNodelet::CameraThrottleNodelet
CameraThrottleNodelet()
Definition:
camera_throttle.cpp:16
camera_throttle::CameraThrottleNodelet::rate
std::optional< ros::Rate > rate
Definition:
camera_throttle.h:54
camera_throttle::CameraThrottleNodelet::info_disconnect_cb
void info_disconnect_cb(const ros::SingleSubscriberPublisher &)
Definition:
camera_throttle.cpp:133
image_transport::SingleSubscriberPublisher
camera_throttle::CameraThrottleNodelet::flipVertical
bool flipVertical
Definition:
camera_throttle.h:57
ros::Time
camera_throttle::CameraThrottleNodelet::pubNh
ros::NodeHandle pubNh
Definition:
camera_throttle.h:49
camera_throttle::CameraThrottleNodelet::CameraThrottlePrivate
Definition:
camera_throttle.cpp:11
camera_throttle
Definition:
camera_throttle.h:11
cras::Nodelet
camera_throttle::CameraThrottleNodelet::frameId
std::optional< std::string > frameId
Definition:
camera_throttle.h:55
camera_throttle::CameraThrottleNodelet::lastUpdate
ros::Time lastUpdate
Definition:
camera_throttle.h:59
camera_throttle::CameraThrottleNodelet::subBaseName
std::string subBaseName
Definition:
camera_throttle.h:60
camera_throttle::CameraThrottleNodelet::onLastDisconnect
virtual void onLastDisconnect()
Definition:
camera_throttle.cpp:147
camera_throttle::CameraThrottleNodelet::queueSize
size_t queueSize
Definition:
camera_throttle.h:58
camera_throttle::CameraThrottleNodelet::sub
std::optional< image_transport::CameraSubscriber > sub
Definition:
camera_throttle.h:52
ros::NodeHandle
camera_publisher.h
nodelet_utils.hpp
camera_throttle::CameraThrottleNodelet::~CameraThrottleNodelet
virtual ~CameraThrottleNodelet()
Definition:
camera_throttle.h:39
camera_throttle
Author(s): Martin Pecka
autogenerated on Sat Dec 14 2024 03:51:15