marker_shapes_interface.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #ifndef MARKER_SHAPES_INTERFACE_HPP_
00019 #define MARKER_SHAPES_INTERFACE_HPP_
00020 
00021 #include <boost/shared_ptr.hpp>
00022 #include <stdint.h>
00023 #include <visualization_msgs/Marker.h>
00024 #include <fcl/collision_object.h>
00025 #include <fcl/BVH/BVH_model.h>
00026 
00027 /* BEGIN IMarkerShape *******************************************************************************************/
00029 class IMarkerShape
00030 {
00031     protected:
00032         static uint32_t class_ctr_;
00033         visualization_msgs::Marker marker_;
00034         geometry_msgs::Pose origin_;
00035         bool drawable_; 
00036 
00037     public:
00038          IMarkerShape();
00039          virtual uint32_t getId() const = 0;
00040          virtual void setColor(double color_r, double color_g, double color_b, double color_a = 1.0) = 0;
00041          virtual visualization_msgs::Marker getMarker() = 0;
00042          virtual void updatePose(const geometry_msgs::Vector3& pos, const geometry_msgs::Quaternion& quat) = 0;
00043          virtual void updatePose(const geometry_msgs::Pose& pose) = 0;
00044          virtual fcl::CollisionObject getCollisionObject() const = 0;
00045          virtual geometry_msgs::Pose getMarkerPose() const = 0;
00046          virtual geometry_msgs::Pose getOriginRelToFrame() const = 0;
00047 
00048 
00054          inline void setDrawable(bool can_be_drawn)
00055          {
00056              this->drawable_ = can_be_drawn;
00057          }
00058 
00059          inline bool isDrawable()
00060          {
00061              return this->drawable_;
00062          }
00063 
00064          virtual ~IMarkerShape() {}
00065 };
00066 /* END IMarkerShape *********************************************************************************************/
00067 
00068 typedef boost::shared_ptr< IMarkerShape > PtrIMarkerShape_t;
00069 typedef fcl::BVHModel<fcl::RSS> BVH_RSS_t;
00070 
00071 #endif /* MARKER_SHAPES_INTERFACE_HPP_ */


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Jun 6 2019 21:19:14