marker_shapes_interface.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 MARKER_SHAPES_INTERFACE_HPP_
19 #define MARKER_SHAPES_INTERFACE_HPP_
20 
21 #include <boost/shared_ptr.hpp>
22 #include <stdint.h>
23 #include <visualization_msgs/Marker.h>
24 #include <fcl/collision_object.h>
25 #include <fcl/BVH/BVH_model.h>
26 
27 /* BEGIN IMarkerShape *******************************************************************************************/
30 {
31  protected:
32  static uint32_t class_ctr_;
33  visualization_msgs::Marker marker_;
34  geometry_msgs::Pose origin_;
35  bool drawable_;
36 
37  public:
38  IMarkerShape();
39  virtual uint32_t getId() const = 0;
40  virtual void setColor(double color_r, double color_g, double color_b, double color_a = 1.0) = 0;
41  virtual visualization_msgs::Marker getMarker() = 0;
42  virtual void updatePose(const geometry_msgs::Vector3& pos, const geometry_msgs::Quaternion& quat) = 0;
43  virtual void updatePose(const geometry_msgs::Pose& pose) = 0;
44  virtual fcl::CollisionObject getCollisionObject() const = 0;
45  virtual geometry_msgs::Pose getMarkerPose() const = 0;
46  virtual geometry_msgs::Pose getOriginRelToFrame() const = 0;
47 
48 
54  inline void setDrawable(bool can_be_drawn)
55  {
56  this->drawable_ = can_be_drawn;
57  }
58 
59  inline bool isDrawable()
60  {
61  return this->drawable_;
62  }
63 
64  virtual ~IMarkerShape() {}
65 };
66 /* END IMarkerShape *********************************************************************************************/
67 
68 typedef std::shared_ptr< IMarkerShape > PtrIMarkerShape_t;
69 typedef fcl::BVHModel<fcl::RSS> BVH_RSS_t;
70 
71 #endif /* MARKER_SHAPES_INTERFACE_HPP_ */
virtual void setColor(double color_r, double color_g, double color_b, double color_a=1.0)=0
visualization_msgs::Marker marker_
virtual geometry_msgs::Pose getMarkerPose() const =0
std::shared_ptr< IMarkerShape > PtrIMarkerShape_t
virtual void updatePose(const geometry_msgs::Vector3 &pos, const geometry_msgs::Quaternion &quat)=0
fcl::BVHModel< fcl::RSS > BVH_RSS_t
virtual geometry_msgs::Pose getOriginRelToFrame() const =0
virtual uint32_t getId() const =0
static uint32_t class_ctr_
geometry_msgs::Pose origin_
void setDrawable(bool can_be_drawn)
IMarkerShape()
If the marker shape is even drawable or not.
Interface class marking methods that have to be implemented in derived classes.
virtual fcl::CollisionObject getCollisionObject() const =0
virtual visualization_msgs::Marker getMarker()=0


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