src
publishers
image_publisher.h
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2019 Roboception GmbH
3
* All rights reserved
4
*
5
* Author: Heiko Hirschmueller
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions are met:
9
*
10
* 1. Redistributions of source code must retain the above copyright notice,
11
* this list of conditions and the following disclaimer.
12
*
13
* 2. Redistributions in binary form must reproduce the above copyright notice,
14
* this list of conditions and the following disclaimer in the documentation
15
* and/or other materials provided with the distribution.
16
*
17
* 3. Neither the name of the copyright holder nor the names of its contributors
18
* may be used to endorse or promote products derived from this software without
19
* specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31
* POSSIBILITY OF SUCH DAMAGE.
32
*/
33
34
#ifndef RCGCCAM_IMAGEPUBLISHER_H
35
#define RCGCCAM_IMAGEPUBLISHER_H
36
37
#include <
ros/ros.h
>
38
#include <
image_transport/image_transport.h
>
39
#include <sensor_msgs/Image.h>
40
41
#include <
rc_genicam_api/buffer.h
>
42
43
#include <string>
44
45
namespace
rcgccam
46
{
47
class
ImagePublisher
48
{
49
public
:
50
ImagePublisher
();
51
57
void
init
(
image_transport::ImageTransport
&
id
);
58
59
bool
used
();
60
61
void
publish
(
const
sensor_msgs::ImagePtr& image);
62
63
private
:
64
ImagePublisher
(
const
ImagePublisher
&);
// forbidden
65
ImagePublisher
&
operator=
(
const
ImagePublisher
&);
// forbidden
66
67
image_transport::Publisher
pub_
;
68
};
69
74
std::string
rosPixelformat
(
int
& bytes_per_pixel, uint64_t pixelformat);
75
79
sensor_msgs::ImagePtr
rosImageFromBuffer
(
const
std::string& frame_id,
const
rcg::Buffer
* buffer,
80
uint32_t part,
bool
rotate);
81
82
}
// namespace rcgccam
83
84
#endif
rcgccam::ImagePublisher::ImagePublisher
ImagePublisher()
Definition:
image_publisher.cc:48
image_transport::ImageTransport
rcg::Buffer
rcgccam::rosImageFromBuffer
sensor_msgs::ImagePtr rosImageFromBuffer(const std::string &frame_id, const rcg::Buffer *buffer, uint32_t part, bool rotate)
Converts a (supported) image in a GenICam buffer into a ROS image.
Definition:
image_publisher.cc:229
ros.h
rcgccam::ImagePublisher::operator=
ImagePublisher & operator=(const ImagePublisher &)
buffer.h
rcgccam
Definition:
camerainfolist.cc:40
rcgccam::ImagePublisher::init
void init(image_transport::ImageTransport &id)
Initialization of publisher.
Definition:
image_publisher.cc:51
rcgccam::ImagePublisher::publish
void publish(const sensor_msgs::ImagePtr &image)
Definition:
image_publisher.cc:61
image_transport.h
rcgccam::ImagePublisher::pub_
image_transport::Publisher pub_
Definition:
image_publisher.h:67
rcgccam::ImagePublisher::used
bool used()
Definition:
image_publisher.cc:56
image_transport::Publisher
rcgccam::ImagePublisher
Definition:
image_publisher.h:47
rcgccam::rosPixelformat
std::string rosPixelformat(int &bytes_per_pixel, uint64_t pixelformat)
Translates pixel format from GenICam to ROS.
Definition:
image_publisher.cc:69
rc_genicam_camera
Author(s): Heiko Hirschmueller
autogenerated on Wed Mar 2 2022 00:49:18