20 #include <boost/optional.hpp> 22 #include <geometry_msgs/PoseStamped.h> 26 #include <sensor_msgs/NavSatFix.h> 29 #include <OGRE/OgreMaterial.h> 30 #include <OGRE/OgreVector3.h> 47 class PositionReferenceProperty;
49 class RosTopicProperty;
51 class TfFrameProperty;
74 void reset()
override;
75 void update(
float,
float)
override;
80 void updateDrawUnder();
84 void updateMapTransformType();
85 void updateMapFrame();
86 void updateUtmFrame();
88 void updateXYReference();
89 void updateZReference();
94 void onEnable()
override;
95 void onDisable()
override;
96 void onInitialize()
override;
104 void navFixCallback(sensor_msgs::NavSatFixConstPtr
const& msg);
109 void requestTileTextures();
115 bool updateCenterTile(sensor_msgs::NavSatFixConstPtr
const& msg);
120 void assembleScene();
125 void triggerSceneAssembly();
135 void destroyTileObjects();
140 void createTileObjects();
145 void transformTileToReferenceFrame();
150 void transformTileToUtmFrame();
155 void transformTileToMapFrame();
160 void transformMapTileToFixedFrame();
165 void checkRequestErrorRate();
180 MapObject(Ogre::ManualObject* o, Ogre::MaterialPtr m) : object(o), material(m)
182 assert(!material.isNull());
238 bool dirty_{
false };
240 sensor_msgs::NavSatFixConstPtr ref_fix_{
nullptr };
246 boost::optional<TileId> center_tile_{ boost::none };
251 std::shared_ptr<tf2_ros::Buffer const> tf_buffer_{
nullptr };
IntProperty * utm_zone_property_
IntProperty * zoom_property_
Ogre::MaterialPtr material
std::string map_frame_
the map frame, rigidly attached to the world with ENU convention - see https://www.ros.org/reps/rep-0105.html#map
EnumProperty * map_transform_type_property_
Property * draw_under_property_
float alpha_
the alpha value of the tile's material
FloatProperty * z_offset_property_
Ogre::ManualObject * object
std::string tile_url_
the URL of the tile server to use
Displays a satellite map along the XY plane.
IntProperty * blocks_property_
PositionReferenceProperty * xy_reference_property_
FloatProperty * alpha_property_
TileCacheDelay< OgreTile > tile_cache_
caches tile images, hashed by their fetch URL
std::string utm_frame_
the utm frame, representing a UTM coordinate frame in a chosen zone
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
TfFrameProperty * utm_frame_property_
PositionReferenceType
Which reference should be used for determining position.
TfFrameProperty * map_frame_property_
MapTransformType
Whether the tiles should be transformed via an intermediate map frame, or directly via a UTM frame...
ros::Duration tf_reference_update_duration_
timeout for periodic TF_FRAME reference update
geometry_msgs::PoseStamped center_tile_pose_
translation of the center-tile w.r.t. the map/utm frame
PositionReferenceType xy_reference_type_
Type of XY position reference.
ros::Timer tf_reference_update_timer_
timer that updates the reference position when using TF_FRAME references
MapTransformType map_transform_type_
Whether the tiles should be transformed via an intermediate map frame, or directly via a UTM frame...
RosTopicProperty * topic_property_
std::string z_reference_frame_
Z position reference TF frame (if TF_FRAME type is used)
int blocks_
the number of tiles loaded in each direction around the center tile
double z_offset_
Offset of the tiles in Z axis (relative to map/utm)
std::string xy_reference_frame_
XY position reference TF frame (if TF_FRAME type is used)
boost::optional< WGSCoordinate > ref_coords_
lat/lon of the reference position that lead to updating the tiles
bool draw_under_
determines which render queue to use
PositionReferenceType z_reference_type_
Type of Z position reference.
StringProperty * tile_url_property_
ros::Subscriber navsat_fix_sub_
the subscriber for the NavSatFix topic
MapObject(Ogre::ManualObject *o, Ogre::MaterialPtr m)
int zoom_
the zoom to use (Mercator)
PositionReferenceProperty * z_reference_property_
std::vector< MapObject > objects_
the tile scene objects
int utm_zone_
UTM zone to work in.