roswrap
src
rossimu
kinetic
include
sensor_msgs
fill_image.h
Go to the documentation of this file.
1
#include "
sick_scan/sick_scan_base.h
"
/* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2
/*********************************************************************
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2008, Willow Garage, Inc.
6
* All rights reserved.
7
*
8
* Redistribution and use in source and binary forms, with or without
9
* modification, are permitted provided that the following conditions
10
* are met:
11
*
12
* * Redistributions of source code must retain the above copyright
13
* notice, this list of conditions and the following disclaimer.
14
* * Redistributions in binary form must reproduce the above
15
* copyright notice, this list of conditions and the following
16
* disclaimer in the documentation and/or other materials provided
17
* with the distribution.
18
* * Neither the name of the Willow Garage nor the names of its
19
* contributors may be used to endorse or promote products derived
20
* from this software without specific prior written permission.
21
*
22
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33
* POSSIBILITY OF SUCH DAMAGE.
34
*********************************************************************/
35
36
#ifndef FILLIMAGE_HH
37
#define FILLIMAGE_HH
38
39
#include "
sensor_msgs/Image.h
"
40
#include "sensor_msgs/image_encodings.h"
41
42
namespace
sensor_msgs
43
{
44
45
static
inline
bool
fillImage
(
Image
& image,
46
const
std::string& encoding_arg,
47
uint32_t rows_arg,
48
uint32_t cols_arg,
49
uint32_t step_arg,
50
const
void
* data_arg)
51
{
52
image.
encoding
= encoding_arg;
53
image.
height
= rows_arg;
54
image.
width
= cols_arg;
55
image.
step
= step_arg;
56
size_t
st0 = (step_arg * rows_arg);
57
image.
data
.resize(st0);
58
memcpy(&image.
data
[0], data_arg, st0);
59
60
image.
is_bigendian
= 0;
61
return
true
;
62
}
63
64
static
inline
void
clearImage
(
Image
& image)
65
{
66
image.
data
.resize(0);
67
}
68
}
69
70
71
#endif
sensor_msgs::Image_::step
_step_type step
Definition:
Image.h:66
sensor_msgs::fillImage
static bool fillImage(Image &image, const std::string &encoding_arg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, const void *data_arg)
sensor_msgs::clearImage
static void clearImage(Image &image)
sensor_msgs::Image_::data
_data_type data
Definition:
Image.h:69
sensor_msgs::Image_::width
_width_type width
Definition:
Image.h:57
Image.h
sensor_msgs::Image_::encoding
_encoding_type encoding
Definition:
Image.h:60
sensor_msgs::Image_::is_bigendian
_is_bigendian_type is_bigendian
Definition:
Image.h:63
sensor_msgs::Image_::height
_height_type height
Definition:
Image.h:54
sick_scan_base.h
sensor_msgs
Tools for manipulating sensor_msgs.
sensor_msgs::Image_< std::allocator< void > >
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof
, Martin Günther
autogenerated on Fri Oct 25 2024 02:47:08