MeshPoseTool.hpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Robot Operating System code by the University of Osnabrück
5  * Copyright (c) 2015, University of Osnabrück
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * 1. Redistributions of source code must retain the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer.
15  *
16  * 2. Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  *
21  * 3. Neither the name of the copyright holder nor the names of its
22  * contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  *
26  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
27  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
28  * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
29  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
30  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
31  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
32  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
33  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
34  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
35  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
36  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
37  *
38  *
39  *
40  * MeshPoseTool.hpp
41  *
42  * author: Sebastian Pütz <spuetz@uni-osnabrueck.de>
43  */
44 
45 #ifndef MESH_POSE_TOOL_HPP
46 #define MESH_POSE_TOOL_HPP
47 
48 #include <OGRE/OgreVector3.h>
49 #include <OGRE/OgreQuaternion.h>
50 #include <OGRE/OgreManualObject.h>
51 #include <OGRE/OgreRay.h>
52 
53 #include <QCursor>
54 #include <ros/ros.h>
55 #include <rviz/tool.h>
57 
58 namespace rviz_map_plugin
59 {
60 class MeshPoseTool : public rviz::Tool
61 {
62 public:
63  MeshPoseTool();
64  virtual ~MeshPoseTool();
65 
66  virtual void onInitialize();
67 
68  virtual void activate();
69  virtual void deactivate();
70 
71  virtual int processMouseEvent(rviz::ViewportMouseEvent& event);
72 
73 protected:
74  virtual void onPoseSet(const Ogre::Vector3& position, const Ogre::Quaternion& orientation) = 0;
75 
76  void getRawManualObjectData(const Ogre::ManualObject* mesh, const size_t sectionNumber, size_t& vertexCount,
77  Ogre::Vector3*& vertices, size_t& indexCount, unsigned long*& indices);
78 
79  bool getPositionAndOrientation(const Ogre::ManualObject* mesh, const Ogre::Ray& ray, Ogre::Vector3& position,
80  Ogre::Vector3& orientation);
81 
82  bool selectTriangle(rviz::ViewportMouseEvent& event, Ogre::Vector3& position, Ogre::Vector3& orientation);
83 
85  enum State
86  {
89  };
91  Ogre::Vector3 pos_;
92  Ogre::Vector3 ori_;
93 };
94 
95 } /* namespace rviz_map_plugin */
96 
97 #endif
rviz::Tool
rviz::Arrow
rviz_map_plugin::MeshPoseTool::getRawManualObjectData
void getRawManualObjectData(const Ogre::ManualObject *mesh, const size_t sectionNumber, size_t &vertexCount, Ogre::Vector3 *&vertices, size_t &indexCount, unsigned long *&indices)
Definition: MeshPoseTool.cpp:241
ros.h
rviz_map_plugin::MeshPoseTool::arrow_
rviz::Arrow * arrow_
Definition: MeshPoseTool.hpp:84
rviz::ViewportMouseEvent
rviz_map_plugin::MeshPoseTool::onPoseSet
virtual void onPoseSet(const Ogre::Vector3 &position, const Ogre::Quaternion &orientation)=0
rviz_map_plugin::MeshPoseTool::~MeshPoseTool
virtual ~MeshPoseTool()
Definition: MeshPoseTool.cpp:66
rviz_map_plugin::MeshPoseTool::processMouseEvent
virtual int processMouseEvent(rviz::ViewportMouseEvent &event)
Definition: MeshPoseTool.cpp:89
rviz_map_plugin::MeshPoseTool::MeshPoseTool
MeshPoseTool()
Definition: MeshPoseTool.cpp:62
arrow.h
rviz_map_plugin::MeshPoseTool::Orientation
@ Orientation
Definition: MeshPoseTool.hpp:88
rviz_map_plugin::MeshPoseTool::pos_
Ogre::Vector3 pos_
Definition: MeshPoseTool.hpp:91
rviz_map_plugin::MeshPoseTool::onInitialize
virtual void onInitialize()
Definition: MeshPoseTool.cpp:71
rviz_map_plugin::MeshPoseTool::Position
@ Position
Definition: MeshPoseTool.hpp:87
rviz_map_plugin
Definition: ClusterLabelDisplay.hpp:120
rviz_map_plugin::MeshPoseTool::State
State
Definition: MeshPoseTool.hpp:85
rviz_map_plugin::MeshPoseTool::deactivate
virtual void deactivate()
Definition: MeshPoseTool.cpp:84
rviz_map_plugin::MeshPoseTool
Definition: MeshPoseTool.hpp:60
rviz_map_plugin::MeshPoseTool::selectTriangle
bool selectTriangle(rviz::ViewportMouseEvent &event, Ogre::Vector3 &position, Ogre::Vector3 &orientation)
Definition: MeshPoseTool.cpp:160
rviz_map_plugin::MeshPoseTool::state_
State state_
Definition: MeshPoseTool.hpp:90
rviz_map_plugin::MeshPoseTool::activate
virtual void activate()
Definition: MeshPoseTool.cpp:78
rviz_map_plugin::MeshPoseTool::ori_
Ogre::Vector3 ori_
Definition: MeshPoseTool.hpp:92
mesh
HalfEdgeMesh< Vec > mesh
tool.h
rviz_map_plugin::MeshPoseTool::getPositionAndOrientation
bool getPositionAndOrientation(const Ogre::ManualObject *mesh, const Ogre::Ray &ray, Ogre::Vector3 &position, Ogre::Vector3 &orientation)
Definition: MeshPoseTool.cpp:189


rviz_map_plugin
Author(s): Sebastian Pütz , Kristin Schmidt , Jan Philipp Vogtherr , Malte kleine Piening
autogenerated on Sun Jan 21 2024 04:06:25