include
next_best_view
pcl
SpaceSamplePoint.hpp
Go to the documentation of this file.
1
20
#ifndef SPACESAMPLEPOINT_HPP_
21
#define SPACESAMPLEPOINT_HPP_
22
23
#define PCL_NO_PRECOMPILE
24
#include "
typedef.hpp
"
25
#include <geometry_msgs/Pose.h>
26
#include <string>
27
#include <pcl/point_types.h>
28
#include <pcl/impl/point_types.hpp>
29
#include <pcl/search/search.h>
30
#include <pcl/search/organized.h>
31
#include <pcl/search/impl/organized.hpp>
32
#include <pcl/search/kdtree.h>
33
#include <pcl/search/impl/kdtree.hpp>
34
#include <pcl/kdtree/kdtree_flann.h>
35
#include <pcl/kdtree/impl/kdtree_flann.hpp>
36
#include <pcl/segmentation/conditional_euclidean_clustering.h>
37
#include <pcl/segmentation/impl/conditional_euclidean_clustering.hpp>
38
#include <pcl/pcl_base.h>
39
#include <pcl/impl/pcl_base.hpp>
40
41
namespace
next_best_view
{
42
namespace
gm
=
geometry_msgs
;
43
52
/* Describes a point in the space in the point cloud.
53
* Space Points stands for possible position of the robot to look at objects.
54
*/
55
struct
SpaceSamplePoint
{
56
public
:
57
PCL_ADD_POINT4D
;
58
59
IndicesPtr
child_indices
;
60
public
:
61
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
62
SpaceSamplePoint
(
const
gm::Pose &pose = gm::Pose()) {
63
x = pose.position.x;
64
y = pose.position.y;
65
z = pose.position.z;
66
}
67
68
SpaceSamplePoint
(
const
SimpleVector3
&vector) {
69
x = vector[0];
70
y = vector[1];
71
z = vector[2];
72
}
73
74
gm::Point
getPoint
()
const
{
75
gm::Point pt;
76
pt.x = x;
77
pt.y = y;
78
pt.z = z;
79
return
pt;
80
}
81
82
SimpleVector3
getSimpleVector3
()
const
{
83
return
SimpleVector3
(x, y, z);
84
}
85
}
EIGEN_ALIGN16
;
86
typedef
boost::shared_ptr<SpaceSamplePoint>
SpaceSamplePointPtr
;
87
88
std::ostream&
operator<<
(std::ostream &strm,
const
next_best_view::SpaceSamplePoint
&p);
89
std::ostream&
operator<<
(std::ostream &strm,
const
next_best_view::SpaceSamplePointPtr
&p);
90
}
91
92
POINT_CLOUD_REGISTER_POINT_STRUCT (
next_best_view::SpaceSamplePoint
,
93
(
float
, x, x)
94
(
float
, y, y)
95
(
float
, z, z)
96
)
97
98
99
#endif
/* SPACESAMPLEPOINT_HPP_ */
next_best_view::SpaceSamplePointPtr
boost::shared_ptr< SpaceSamplePoint > SpaceSamplePointPtr
Definition:
SpaceSamplePoint.hpp:86
next_best_view::SpaceSamplePoint
SpaceSamplePoint.
Definition:
SpaceSamplePoint.hpp:55
next_best_view::SpaceSamplePoint::child_indices
IndicesPtr child_indices
Definition:
SpaceSamplePoint.hpp:59
next_best_view::SimpleVector3
Eigen::Matrix< Precision, 3, 1 > SimpleVector3
Definition:
typedef.hpp:53
next_best_view::SpaceSamplePoint::SpaceSamplePoint
SpaceSamplePoint(const SimpleVector3 &vector)
Definition:
SpaceSamplePoint.hpp:68
next_best_view::SpaceSamplePoint::PCL_ADD_POINT4D
PCL_ADD_POINT4D
Definition:
SpaceSamplePoint.hpp:57
next_best_view::SpaceSamplePoint::SpaceSamplePoint
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SpaceSamplePoint(const gm::Pose &pose=gm::Pose())
Definition:
SpaceSamplePoint.hpp:62
boost::shared_ptr< Indices >
next_best_view
this namespace contains all generally usable classes.
Definition:
CameraModelFilter.hpp:26
typedef.hpp
next_best_view::SpaceSamplePoint::getPoint
gm::Point getPoint() const
Definition:
SpaceSamplePoint.hpp:74
next_best_view::SpaceSamplePoint::getSimpleVector3
SimpleVector3 getSimpleVector3() const
Definition:
SpaceSamplePoint.hpp:82
geometry_msgs
next_best_view::EIGEN_ALIGN16
struct next_best_view::DefaultViewportPoint EIGEN_ALIGN16
next_best_view::operator<<
std::ostream & operator<<(std::ostream &strm, const next_best_view::DefaultViewportPoint &p)
Definition:
DefaultViewportPoint.cpp:24
asr_next_best_view
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Mon Feb 28 2022 21:49:03