#include <robotMeshModel.h>
Classes | |
struct | SubMesh |
struct | Vertex |
Public Member Functions | |
void | fromAssimpScene (const aiScene *scene) |
void | initMesh (const aiMesh *mesh) |
void | initRobot () |
void | paintRobot () |
RobotMeshModel () | |
void | setCamera () |
void | setCameraInfo (sensor_msgs::CameraInfoConstPtr cam_info) |
bool | setCameraPose () |
void | updateRobotLinks (const ros::Time time_stamp) |
~RobotMeshModel () | |
Public Attributes | |
std::map< std::string, const aiScene * > | as_meshes |
sensor_msgs::CameraInfoConstPtr | cam_info_ |
std::string | camera_info_topic_ |
std::string | camera_topic_ |
std::string | cameraframe_ |
tf::StampedTransform | cameraPose |
ros::Time | current_time_stamp_ |
std::string | description_path |
std::vector< boost::shared_ptr < urdf::Link > > | links_with_meshes |
std::vector< SubMesh > | meshes_vec |
std::string | modelframe_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_priv_ |
std::map< std::string, tf::Transform > | offsets_ |
std::map< std::string, tf::StampedTransform > | robotLinks_ |
ros::ServiceServer | srver_ |
tf::TransformListener | tf_ |
urdf::Model | urdf_ |
bool | use_assimp_ |
Definition at line 67 of file robotMeshModel.h.
Definition at line 248 of file robotMeshModel.cpp.
Definition at line 335 of file robotMeshModel.cpp.
void RobotMeshModel::fromAssimpScene | ( | const aiScene * | scene | ) |
Definition at line 202 of file robotMeshModel.cpp.
void RobotMeshModel::initMesh | ( | const aiMesh * | mesh | ) |
Definition at line 213 of file robotMeshModel.cpp.
void RobotMeshModel::initRobot | ( | ) |
Definition at line 340 of file robotMeshModel.cpp.
void RobotMeshModel::paintRobot | ( | ) |
mesh.bbox.Diag();
Definition at line 367 of file robotMeshModel.cpp.
void RobotMeshModel::setCamera | ( | ) |
Definition at line 431 of file robotMeshModel.cpp.
void RobotMeshModel::setCameraInfo | ( | sensor_msgs::CameraInfoConstPtr | cam_info | ) |
Definition at line 426 of file robotMeshModel.cpp.
bool RobotMeshModel::setCameraPose | ( | ) |
Definition at line 468 of file robotMeshModel.cpp.
void RobotMeshModel::updateRobotLinks | ( | const ros::Time | time_stamp | ) |
Definition at line 345 of file robotMeshModel.cpp.
std::map<std::string, const aiScene *> RobotMeshModel::as_meshes |
Definition at line 90 of file robotMeshModel.h.
sensor_msgs::CameraInfoConstPtr RobotMeshModel::cam_info_ |
Definition at line 77 of file robotMeshModel.h.
std::string RobotMeshModel::camera_info_topic_ |
Definition at line 85 of file robotMeshModel.h.
std::string RobotMeshModel::camera_topic_ |
Definition at line 84 of file robotMeshModel.h.
std::string RobotMeshModel::cameraframe_ |
Definition at line 83 of file robotMeshModel.h.
Definition at line 87 of file robotMeshModel.h.
Definition at line 95 of file robotMeshModel.h.
std::string RobotMeshModel::description_path |
Definition at line 80 of file robotMeshModel.h.
std::vector<boost::shared_ptr<urdf::Link> > RobotMeshModel::links_with_meshes |
Definition at line 93 of file robotMeshModel.h.
std::vector<SubMesh> RobotMeshModel::meshes_vec |
Definition at line 140 of file robotMeshModel.h.
std::string RobotMeshModel::modelframe_ |
Definition at line 82 of file robotMeshModel.h.
Definition at line 74 of file robotMeshModel.h.
Definition at line 75 of file robotMeshModel.h.
std::map<std::string, tf::Transform > RobotMeshModel::offsets_ |
Definition at line 91 of file robotMeshModel.h.
std::map<std::string, tf::StampedTransform > RobotMeshModel::robotLinks_ |
Definition at line 92 of file robotMeshModel.h.
Definition at line 78 of file robotMeshModel.h.
Definition at line 73 of file robotMeshModel.h.
Definition at line 79 of file robotMeshModel.h.
Definition at line 88 of file robotMeshModel.h.