moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
mesh_shape.cpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2008, Willow Garage, Inc.
3 * All rights reserved.
4 *
5 * Redistribution and use in source and binary forms, with or without
6 * modification, are permitted provided that the following conditions are met:
7 *
8 * * Redistributions of source code must retain the above copyright
9 * notice, this list of conditions and the following disclaimer.
10 * * Redistributions in binary form must reproduce the above copyright
11 * notice, this list of conditions and the following disclaimer in the
12 * documentation and/or other materials provided with the distribution.
13 * * Neither the name of the Willow Garage, Inc. nor the names of its
14 * contributors may be used to endorse or promote products derived from
15 * this software without specific prior written permission.
16 *
17 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 * POSSIBILITY OF SUCH DAMAGE.
28 */
29
31
32#include <OgreMesh.h>
33#include <OgreMeshManager.h>
34#include <OgreSceneManager.h>
35#include <OgreSceneNode.h>
36#include <OgreEntity.h>
37#include <OgreMaterialManager.h>
38#include <OgreManualObject.h>
39
40#include <rviz_common/logging.hpp>
41#include <string>
42
43namespace rviz_rendering
44{
45MeshShape::MeshShape(Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node)
46 : Shape(Shape::Mesh, scene_manager, parent_node), started_(false)
47{
48 static uint32_t count = 0;
49 manual_object_ = scene_manager->createManualObject("MeshShape_ManualObject" + std::to_string(count++));
50 material_->setCullingMode(Ogre::CULL_NONE);
51}
52
54{
55 clear();
56 scene_manager_->destroyManualObject(manual_object_);
57}
58
60{
61 if (entity_ == nullptr && !started_)
62 manual_object_->estimateVertexCount(vcount);
63}
64
66{
67 if (!started_ && entity_)
68 {
69 RVIZ_COMMON_LOG_WARNING("Cannot modify mesh once construction is complete");
70 return;
71 }
72
73 if (!started_)
74 {
75 started_ = true;
76 manual_object_->begin(material_name_, Ogre::RenderOperation::OT_TRIANGLE_LIST, "rviz_rendering");
77 }
78}
79
80void MeshShape::addVertex(const Ogre::Vector3& position)
81{
83 manual_object_->position(position);
84}
85
86void MeshShape::addVertex(const Ogre::Vector3& position, const Ogre::Vector3& normal)
87{
89 manual_object_->position(position);
90 manual_object_->normal(normal);
91}
92
93void MeshShape::addVertex(const Ogre::Vector3& position, const Ogre::Vector3& normal, const Ogre::ColourValue& color)
94{
96 manual_object_->position(position);
97 manual_object_->normal(normal);
98 manual_object_->colour(color);
99}
100
101void MeshShape::addNormal(const Ogre::Vector3& normal)
102{
103 manual_object_->normal(normal);
104}
105
106void MeshShape::addColor(const Ogre::ColourValue& color)
107{
108 manual_object_->colour(color);
109}
110
111void MeshShape::addTriangle(unsigned int v1, unsigned int v2, unsigned int v3)
112{
113 manual_object_->triangle(v1, v2, v3);
114}
115
117{
118 if (started_)
119 {
120 started_ = false;
121 manual_object_->end();
122 static uint32_t count = 0;
123 std::string name = "ConvertedMeshShape@" + std::to_string(count++);
124 manual_object_->convertToMesh(name);
125 entity_ = scene_manager_->createEntity(name);
126 if (entity_)
127 {
128 entity_->setMaterialName(material_name_, "rviz_rendering");
129 offset_node_->attachObject(entity_);
130 }
131 else
132 RVIZ_COMMON_LOG_ERROR("Unable to construct triangle mesh");
133 }
134 else
135 RVIZ_COMMON_LOG_ERROR("No triangles added");
136}
137
139{
140 if (entity_)
141 {
142 entity_->detachFromParent();
143 Ogre::MeshManager::getSingleton().remove(entity_->getMesh()->getName());
144 scene_manager_->destroyEntity(entity_);
145 entity_ = nullptr;
146 }
147 manual_object_->clear();
148 started_ = false;
149}
150
151} // namespace rviz_rendering
void addColor(const Ogre::ColourValue &color)
Add color for a vertex.
void beginTriangles()
Start adding triangles to the mesh.
void addTriangle(unsigned int p1, unsigned int p2, unsigned int p3)
Add a triangle by indexing in the defined vertices.
void addVertex(const Ogre::Vector3 &position)
Add a vertex to the mesh (no normal defined). If using this function only (not using addTriangle()) i...
MeshShape(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node=nullptr)
Constructor.
void clear()
Clear the mesh.
void estimateVertexCount(size_t vcount)
void endTriangles()
Notify that the set of triangles to add is complete. No more triangles can be added,...
void addNormal(const Ogre::Vector3 &normal)
Add normal for a vertex.