#include <robotMeshModel.h>
Public Member Functions | |
| 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 | |
| sensor_msgs::CameraInfoConstPtr | cam_info_ |
| 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::map< std::string, boost::shared_ptr < vcg::GlTrimesh< CMeshO > > > | mesh_wrappers |
| std::map< std::string, boost::shared_ptr< CMeshO > > | meshes |
| std::string | modelframe_ |
| ros::NodeHandle | nh_ |
| ros::NodeHandle | nh_priv_ |
| std::map< std::string, tf::Transform > | offsets_ |
| std::map< std::string, btTransform > | robotLinks_ |
| ros::ServiceServer | srver_ |
| tf::TransformListener | tf_ |
| urdf::Model | urdf_ |
Definition at line 72 of file robotMeshModel.h.
| RobotMeshModel::RobotMeshModel | ( | ) |
Definition at line 54 of file robotMeshModel.cpp.
| RobotMeshModel::~RobotMeshModel | ( | ) |
Definition at line 127 of file robotMeshModel.cpp.
| void RobotMeshModel::initRobot | ( | ) |
Definition at line 131 of file robotMeshModel.cpp.
| void RobotMeshModel::paintRobot | ( | ) |
mesh.bbox.Diag();
Definition at line 184 of file robotMeshModel.cpp.
| void RobotMeshModel::setCamera | ( | ) |
Definition at line 220 of file robotMeshModel.cpp.
| void RobotMeshModel::setCameraInfo | ( | sensor_msgs::CameraInfoConstPtr | cam_info | ) |
Definition at line 215 of file robotMeshModel.cpp.
| bool RobotMeshModel::setCameraPose | ( | ) |
Definition at line 257 of file robotMeshModel.cpp.
| void RobotMeshModel::updateRobotLinks | ( | const ros::Time | time_stamp | ) |
Definition at line 162 of file robotMeshModel.cpp.
| sensor_msgs::CameraInfoConstPtr RobotMeshModel::cam_info_ |
Definition at line 79 of file robotMeshModel.h.
| std::string RobotMeshModel::camera_topic_ |
Definition at line 86 of file robotMeshModel.h.
| std::string RobotMeshModel::cameraframe_ |
Definition at line 85 of file robotMeshModel.h.
| tf::StampedTransform RobotMeshModel::cameraPose |
Definition at line 88 of file robotMeshModel.h.
| ros::Time RobotMeshModel::current_time_stamp_ |
Definition at line 96 of file robotMeshModel.h.
| std::string RobotMeshModel::description_path |
Definition at line 82 of file robotMeshModel.h.
| std::vector<boost::shared_ptr<urdf::Link> > RobotMeshModel::links_with_meshes |
Definition at line 94 of file robotMeshModel.h.
| std::map<std::string, boost::shared_ptr<vcg::GlTrimesh<CMeshO> > > RobotMeshModel::mesh_wrappers |
Definition at line 92 of file robotMeshModel.h.
| std::map<std::string, boost::shared_ptr<CMeshO> > RobotMeshModel::meshes |
Definition at line 90 of file robotMeshModel.h.
| std::string RobotMeshModel::modelframe_ |
Definition at line 84 of file robotMeshModel.h.
| ros::NodeHandle RobotMeshModel::nh_ |
Definition at line 76 of file robotMeshModel.h.
| ros::NodeHandle RobotMeshModel::nh_priv_ |
Definition at line 77 of file robotMeshModel.h.
| std::map<std::string, tf::Transform > RobotMeshModel::offsets_ |
Definition at line 91 of file robotMeshModel.h.
| std::map<std::string, btTransform > RobotMeshModel::robotLinks_ |
Definition at line 93 of file robotMeshModel.h.
| ros::ServiceServer RobotMeshModel::srver_ |
Definition at line 80 of file robotMeshModel.h.
| tf::TransformListener RobotMeshModel::tf_ |
Definition at line 75 of file robotMeshModel.h.
| urdf::Model RobotMeshModel::urdf_ |
Definition at line 81 of file robotMeshModel.h.