18 #ifndef OBSTACLE_DISTANCE_DATA_TYPES_HPP_ 19 #define OBSTACLE_DISTANCE_DATA_TYPES_HPP_ 23 #include <unordered_map> 24 #include <shape_msgs/SolidPrimitive.h> 25 #include <visualization_msgs/Marker.h> 32 #define FCL_CYL_LENGTH 1u 34 #define MIN_DISTANCE 0.5 // [m]: filter for distances to be published! 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 41 std::unordered_map<uint8_t, uint32_t>
map_;
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;
50 obstacle_color_.r = 1.0;
51 obstacle_color_.g = 0.0;
52 obstacle_color_.b = 0.0;
std_msgs::ColorRGBA obstacle_color_
ShapeMsgTypeToVisMarkerType()
static ShapeMsgTypeToVisMarkerType g_shapeMsgTypeToVisMarkerType
std::unordered_map< uint8_t, uint32_t > map_
#define DEFAULT_COL_ALPHA