shapes_manager.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef SHAPES_MANAGER_HPP_
19 #define SHAPES_MANAGER_HPP_
20 
21 #include <ros/ros.h>
22 #include <unordered_map>
23 
24 #include <visualization_msgs/MarkerArray.h>
26 
29 {
30  private:
31  std::unordered_map<std::string, PtrIMarkerShape_t> shapes_;
33 
34  public:
35  typedef std::unordered_map<std::string, PtrIMarkerShape_t>::iterator MapIter_t;
36  typedef std::unordered_map<std::string, PtrIMarkerShape_t>::const_iterator MapConstIter_t;
37 
43 
45 
51  void addShape(const std::string& id, PtrIMarkerShape_t s);
52 
57  void removeShape(const std::string& id);
58 
59 
66  bool getShape(const std::string& id, PtrIMarkerShape_t& s);
67 
68 
72  void draw();
73 
77  void clear();
78 
83  uint32_t count() const;
84 
89  uint32_t count(const std::string& id) const;
90 
91 
92  MapIter_t begin() {return this->shapes_.begin(); }
93  MapConstIter_t begin() const {return this->shapes_.begin(); }
94  MapIter_t end() {return this->shapes_.end(); }
95  MapConstIter_t end() const {return this->shapes_.end(); }
96 };
97 
98 #endif /* SHAPES_MANAGER_HPP_ */
Class to manage fcl::Shapes and connect with RVIZ marker type.
MapConstIter_t end() const
std::shared_ptr< IMarkerShape > PtrIMarkerShape_t
void addShape(const std::string &id, PtrIMarkerShape_t s)
ShapesManager(const ros::Publisher &pub)
MapIter_t end()
MapConstIter_t begin() const
std::unordered_map< std::string, PtrIMarkerShape_t >::iterator MapIter_t
std::unordered_map< std::string, PtrIMarkerShape_t > shapes_
std::unordered_map< std::string, PtrIMarkerShape_t >::const_iterator MapConstIter_t
void removeShape(const std::string &id)
const ros::Publisher & pub_
bool getShape(const std::string &id, PtrIMarkerShape_t &s)
uint32_t count() const
MapIter_t begin()


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Apr 8 2021 02:39:47