include
image_cb_detector
depth_to_pointcloud.h
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2012, Willow Garage, Inc.
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of the Willow Garage nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*********************************************************************/
34
35
36
#ifndef DEPTH_TO_POINTCLOUD_H_
37
#define DEPTH_TO_POINTCLOUD_H_
38
39
#include <sensor_msgs/CameraInfo.h>
40
#include <sensor_msgs/Image.h>
41
42
#include <vector>
43
#include <
assert.h
>
44
45
class
DepthToPointCloud
46
{
47
public
:
48
DepthToPointCloud
();
49
virtual
~DepthToPointCloud
();
50
51
void
initialize
(sensor_msgs::ImageConstPtr depth_msg,
52
sensor_msgs::CameraInfoConstPtr camera_info_msg);
53
54
template
<
typename
Po
int
2D_T,
typename
Po
int
3D_T>
55
void
depthTo3DPoint
(Point2D_T& image_pos,
float
depth, Point3D_T& point)
56
{
57
assert(image_pos.x<
projection_map_x_
.size());
58
assert(image_pos.y<
projection_map_y_
.size());
59
60
point.x =
projection_map_x_
[(
unsigned
int)image_pos.x] * depth;
61
point.y =
projection_map_y_
[(
unsigned
int
)image_pos.y] * depth;
62
point.z = depth;
63
}
64
65
66
protected
:
67
// projection matrix
68
std::vector<float>
projection_map_x_
;
69
std::vector<float>
projection_map_y_
;
70
};
71
72
#endif
/* DEPTH_TO_POINTCLOUD_H_ */
DepthToPointCloud::projection_map_x_
std::vector< float > projection_map_x_
Definition:
depth_to_pointcloud.h:100
DepthToPointCloud::~DepthToPointCloud
virtual ~DepthToPointCloud()
Definition:
depth_to_pointcloud.cpp:46
DepthToPointCloud::DepthToPointCloud
DepthToPointCloud()
Definition:
depth_to_pointcloud.cpp:40
DepthToPointCloud::depthTo3DPoint
void depthTo3DPoint(Point2D_T &image_pos, float depth, Point3D_T &point)
Definition:
depth_to_pointcloud.h:87
DepthToPointCloud::initialize
void initialize(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::CameraInfoConstPtr camera_info_msg)
Definition:
depth_to_pointcloud.cpp:51
DepthToPointCloud::projection_map_y_
std::vector< float > projection_map_y_
Definition:
depth_to_pointcloud.h:101
DepthToPointCloud
Definition:
depth_to_pointcloud.h:45
assert.h
image_cb_detector
Author(s): Vijay Pradeep, Eitan Marder-Eppstein
autogenerated on Tue Mar 1 2022 23:58:48