include
costmap_converter
costmap_to_lines_convex_hull.h
Go to the documentation of this file.
1
/*********************************************************************
2
*
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2016,
6
* TU Dortmund - Institute of Control Theory and Systems Engineering.
7
* All rights reserved.
8
*
9
* Redistribution and use in source and binary forms, with or without
10
* modification, are permitted provided that the following conditions
11
* are met:
12
*
13
* * Redistributions of source code must retain the above copyright
14
* notice, this list of conditions and the following disclaimer.
15
* * Redistributions in binary form must reproduce the above
16
* copyright notice, this list of conditions and the following
17
* disclaimer in the documentation and/or other materials provided
18
* with the distribution.
19
* * Neither the name of the institute nor the names of its
20
* contributors may be used to endorse or promote products derived
21
* from this software without specific prior written permission.
22
*
23
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34
* POSSIBILITY OF SUCH DAMAGE.
35
*
36
* Author: Christoph Rösmann, Otniel Rinaldo
37
*********************************************************************/
38
39
#ifndef COSTMAP_TO_LINES_CONVEX_HULL_H_
40
#define COSTMAP_TO_LINES_CONVEX_HULL_H_
41
42
#include <
costmap_converter/costmap_converter_interface.h
>
43
#include <
costmap_converter/costmap_to_polygons.h
>
44
45
// dynamic reconfigure
46
#include <costmap_converter/CostmapToLinesDBSMCCHConfig.h>
47
48
namespace
costmap_converter
49
{
50
69
class
CostmapToLinesDBSMCCH :
public
CostmapToPolygonsDBSMCCH
70
{
71
public
:
72
76
CostmapToLinesDBSMCCH
();
77
81
virtual
~CostmapToLinesDBSMCCH
();
82
87
virtual
void
initialize
(
ros::NodeHandle
nh);
88
92
virtual
void
compute
();
93
94
95
protected
:
96
103
void
extractPointsAndLines
(std::vector<KeyPoint>& cluster,
const
geometry_msgs::Polygon& polygon, std::back_insert_iterator< std::vector<geometry_msgs::Polygon> > lines);
104
105
106
107
protected
:
108
109
double
support_pts_max_dist_inbetween_
;
110
double
support_pts_max_dist_
;
111
int
min_support_pts_
;
112
113
private
:
114
122
void
reconfigureCB
(CostmapToLinesDBSMCCHConfig& config, uint32_t level);
123
124
dynamic_reconfigure::Server<CostmapToLinesDBSMCCHConfig>*
dynamic_recfg_
;
125
126
};
127
128
129
130
131
132
133
134
135
}
//end namespace teb_local_planner
136
137
#endif
/* COSTMAP_TO_LINES_CONVEX_HULL_H_ */
costmap_converter::CostmapToLinesDBSMCCH::support_pts_max_dist_inbetween_
double support_pts_max_dist_inbetween_
Definition:
costmap_to_lines_convex_hull.h:145
costmap_converter::CostmapToLinesDBSMCCH::initialize
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
Definition:
costmap_to_lines_convex_hull.cpp:97
costmap_converter::CostmapToLinesDBSMCCH::support_pts_max_dist_
double support_pts_max_dist_
Definition:
costmap_to_lines_convex_hull.h:146
costmap_converter_interface.h
costmap_converter::CostmapToLinesDBSMCCH::dynamic_recfg_
dynamic_reconfigure::Server< CostmapToLinesDBSMCCHConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime
Definition:
costmap_to_lines_convex_hull.h:160
costmap_converter::CostmapToLinesDBSMCCH::~CostmapToLinesDBSMCCH
virtual ~CostmapToLinesDBSMCCH()
Destructor.
Definition:
costmap_to_lines_convex_hull.cpp:91
costmap_converter::CostmapToLinesDBSMCCH::min_support_pts_
int min_support_pts_
Definition:
costmap_to_lines_convex_hull.h:147
costmap_converter::CostmapToLinesDBSMCCH::compute
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
Definition:
costmap_to_lines_convex_hull.cpp:124
costmap_converter
Definition:
costmap_converter_interface.h:52
costmap_converter::CostmapToLinesDBSMCCH::CostmapToLinesDBSMCCH
CostmapToLinesDBSMCCH()
Constructor.
Definition:
costmap_to_lines_convex_hull.cpp:86
costmap_to_polygons.h
costmap_converter::CostmapToLinesDBSMCCH::reconfigureCB
void reconfigureCB(CostmapToLinesDBSMCCHConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
Definition:
costmap_to_lines_convex_hull.cpp:309
ros::NodeHandle
costmap_converter::CostmapToLinesDBSMCCH::extractPointsAndLines
void extractPointsAndLines(std::vector< KeyPoint > &cluster, const geometry_msgs::Polygon &polygon, std::back_insert_iterator< std::vector< geometry_msgs::Polygon > > lines)
Extract points and lines from a given cluster by checking all keypoint pairs of the convex hull for a...
Definition:
costmap_to_lines_convex_hull.cpp:164
costmap_converter
Author(s): Christoph Rösmann
, Franz Albers
, Otniel Rinaldo
autogenerated on Fri Sep 20 2024 02:19:25