obstacle_distance_data_types.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 OBSTACLE_DISTANCE_DATA_TYPES_HPP_
19 #define OBSTACLE_DISTANCE_DATA_TYPES_HPP_
20 
21 #include <ros/ros.h>
22 #include <stdint.h>
23 #include <unordered_map>
24 #include <shape_msgs/SolidPrimitive.h>
25 #include <visualization_msgs/Marker.h>
26 
27 #define FCL_BOX_X 0u
28 #define FCL_BOX_Y 1u
29 #define FCL_BOX_Z 2u
30 
31 #define FCL_RADIUS 0u
32 #define FCL_CYL_LENGTH 1u
33 
34 #define MIN_DISTANCE 0.5 // [m]: filter for distances to be published!
35 
36 #define DEFAULT_COL_ALPHA 0.6 // MoveIt! CollisionGeometry does not provide color -> Therefore use default value. 0.5 = Test for taking pictures -> robot arm should be visible behind obstacle
37 
39 {
40  public:
41  std::unordered_map<uint8_t, uint32_t> map_;
42  std_msgs::ColorRGBA obstacle_color_;
43 
45  {
46  map_[shape_msgs::SolidPrimitive::BOX] = visualization_msgs::Marker::CUBE;
47  map_[shape_msgs::SolidPrimitive::SPHERE] = visualization_msgs::Marker::SPHERE;
48  map_[shape_msgs::SolidPrimitive::CYLINDER] = visualization_msgs::Marker::CYLINDER;
49 
50  obstacle_color_.r = 1.0;
51  obstacle_color_.g = 0.0;
52  obstacle_color_.b = 0.0;
53  obstacle_color_.a = DEFAULT_COL_ALPHA;
54  }
55 };
56 
57 
59 {
60  fcl::Vec3f a;
61  fcl::Vec3f b;
62  fcl::Vec3f c;
63 };
64 
66 
67 #endif /* OBSTACLE_DISTANCE_DATA_TYPES_HPP_ */
static ShapeMsgTypeToVisMarkerType g_shapeMsgTypeToVisMarkerType
std::unordered_map< uint8_t, uint32_t > map_
#define DEFAULT_COL_ALPHA


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