17 #ifndef CARTOGRAPHER_RVIZ_SRC_DRAWABLE_SUBMAP_H_ 18 #define CARTOGRAPHER_RVIZ_SRC_DRAWABLE_SUBMAP_H_ 23 #include "Eigen/Geometry" 24 #include "OgreManualObject.h" 25 #include "OgreMaterial.h" 26 #include "OgreQuaternion.h" 27 #include "OgreSceneManager.h" 28 #include "OgreSceneNode.h" 29 #include "OgreTexture.h" 30 #include "OgreVector3.h" 32 #include "cartographer_ros_msgs/SubmapEntry.h" 33 #include "cartographer_ros_msgs/SubmapQuery.h" 50 Ogre::SceneManager* scene_manager,
59 const ::cartographer_ros_msgs::SubmapEntry& metadata,
71 void SetAlpha(
double current_tracking_z);
96 ::cartographer::common::Mutex
mutex_;
104 Ogre::Quaternion orientation_
GUARDED_BY(mutex_);
105 Eigen::Affine3d slice_pose_
GUARDED_BY(mutex_);
106 std::chrono::milliseconds last_query_timestamp_
GUARDED_BY(mutex_);
111 ::cartographer_ros_msgs::SubmapQuery::Response response_
GUARDED_BY(mutex_);
118 #endif // CARTOGRAPHER_RVIZ_SRC_DRAWABLE_SUBMAP_H_ Ogre::ManualObject * manual_object_
Ogre::TexturePtr texture_
void set_visibility(const bool visibility)
Ogre::SceneNode *const scene_node_
std::unique_ptr<::rviz::BoolProperty > visibility_
::cartographer::common::Mutex mutex_
DrawableSubmap & operator=(const DrawableSubmap &)=delete
std::future< void > rpc_request_future_
void SetAlpha(double current_tracking_z)
void Update(const ::std_msgs::Header &header, const ::cartographer_ros_msgs::SubmapEntry &metadata,::rviz::FrameManager *frame_manager)
float UpdateAlpha(float target_alpha)
~DrawableSubmap() override
bool MaybeFetchTexture(ros::ServiceClient *client)
int trajectory_id() const
Ogre::SceneManager *const scene_manager_
Ogre::Vector3 position_ GUARDED_BY(mutex_)
Ogre::MaterialPtr material_
DrawableSubmap(int trajectory_id, int submap_index, Ogre::SceneManager *scene_manager,::rviz::Property *submap_category, const bool visible)