A container for a mesh, using a frame and dimensions. More...
#include <shape_tools.h>
Public Member Functions | |
| Mesh (const char *mesh_source, const tf::Vector3 &dims_in) | |
| Mesh (const char *mesh_source, const tf::Pose &frame_in, const tf::Vector3 &dims_in) | |
| Mesh () | |
| void | transform (const tf::Transform &T) |
Public Attributes | |
| tf::Vector3 | dims |
| tf::Pose | frame |
| std_msgs::Header | header |
| std::string | mesh_resource |
| bool | use_embedded_materials |
A container for a mesh, using a frame and dimensions.
This description is displayed lower in the doxygen as an extended description along with the above brief description.
Definition at line 115 of file shape_tools.h.
| object_manipulator::shapes::Mesh::Mesh | ( | ) | [inline] |
Definition at line 118 of file shape_tools.h.
| object_manipulator::shapes::Mesh::Mesh | ( | const char * | mesh_source, | |
| const tf::Pose & | frame_in, | |||
| const tf::Vector3 & | dims_in | |||
| ) | [inline] |
Definition at line 120 of file shape_tools.h.
| object_manipulator::shapes::Mesh::Mesh | ( | const char * | mesh_source, | |
| const tf::Vector3 & | dims_in | |||
| ) | [inline] |
Definition at line 122 of file shape_tools.h.
| void object_manipulator::shapes::Mesh::transform | ( | const tf::Transform & | T | ) | [inline] |
Definition at line 124 of file shape_tools.h.
| tf::Vector3 object_manipulator::shapes::Mesh::dims |
Definition at line 130 of file shape_tools.h.
Definition at line 129 of file shape_tools.h.
| std_msgs::Header object_manipulator::shapes::Mesh::header |
Definition at line 126 of file shape_tools.h.
| std::string object_manipulator::shapes::Mesh::mesh_resource |
Definition at line 127 of file shape_tools.h.
Definition at line 128 of file shape_tools.h.