mesh_loader.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2022 Michael Ferguson
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 // Author: Michael Ferguson
18 
19 #ifndef ROBOT_CALIBRATION_MESH_LOADER_H
20 #define ROBOT_CALIBRATION_MESH_LOADER_H
21 
22 #include <memory>
23 #include <string>
24 #include <vector>
25 
27 #include <urdf/model.h>
28 
29 namespace robot_calibration
30 {
31 
32 using MeshPtr = std::shared_ptr<shapes::Mesh>;
33 
35 {
36 public:
37  MeshLoader(urdf::Model& model);
38 
42  MeshPtr getCollisionMesh(const std::string& link_name);
43 
44 private:
46  std::vector<std::string> link_names_;
47  std::vector<MeshPtr> meshes_;
48 };
49 
50 } // namespace robot_calibration
51 
52 #endif // ROBOT_CALIBRATION_MESH_LOADER_H
shape_operations.h
urdf::Model
robot_calibration::MeshPtr
std::shared_ptr< shapes::Mesh > MeshPtr
Definition: mesh_loader.h:32
robot_calibration::MeshLoader::meshes_
std::vector< MeshPtr > meshes_
Definition: mesh_loader.h:47
robot_calibration::MeshLoader::getCollisionMesh
MeshPtr getCollisionMesh(const std::string &link_name)
Get the collision mesh associated with a link in a URDF.
Definition: mesh_loader.cpp:32
robot_calibration::MeshLoader::link_names_
std::vector< std::string > link_names_
Definition: mesh_loader.h:46
model.h
robot_calibration::MeshLoader
Definition: mesh_loader.h:34
robot_calibration::MeshLoader::MeshLoader
MeshLoader(urdf::Model &model)
Definition: mesh_loader.cpp:28
robot_calibration::MeshLoader::model_
urdf::Model model_
Definition: mesh_loader.h:45
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01