#include <CaddyKML.hpp>
Public Member Functions | |
| void | addShipPosition (const auv_msgs::NavSts::ConstPtr &nav) |
| void | addVehiclePosition (const auv_msgs::NavSts::ConstPtr &nav) |
| CaddyKML () | |
| void | run () |
| void | setDiverOrigin (const geometry_msgs::Point::ConstPtr &point) |
| void | write () |
| ~CaddyKML () | |
Private Member Functions | |
| void | addOpRegionToDocument (kmldom::DocumentPtr document) |
| void | addVarianceRegion (const auv_msgs::NavSts &nav, kmldom::DocumentPtr document) |
Private Attributes | |
| auv_msgs::NavSts | diver |
| kmlbase::Vec3 | diverOrigin |
| kmldom::KmlFactory * | factory |
| std::string | filename |
| kmldom::DocumentPtr | folder |
| boost::mutex | kml_mux |
| std::ofstream | kmlFile |
| kmldom::CoordinatesPtr | opRegion |
| CustomLineString < TransparentSegments > | path |
| auv_msgs::NavSts | platform |
| CustomLineString < TransparentSegments > | platformPath |
| bool | runFlag |
| VehiclePolygon | ship |
| VehiclePolygon | vehicle |
| boost::thread | worker |
This class represents an interactive KML file. It opens and writes into a KML file. It will remember a specified number of coordinates. Around each last coordinate it will draw the vehicle position.
The YAML configuration should have a form:
filename: myname.kml diver-path/color="0xAABBGGRR" diver-path/length="200" diver-path/segment-length="20" platform-path/color="0xAABBGGRR"
Definition at line 69 of file CaddyKML.hpp.
Generic constructor.
Definition at line 21 of file CaddyKML.cpp.
Generic destructor.
Definition at line 81 of file CaddyKML.cpp.
| void CaddyKML::addOpRegionToDocument | ( | kmldom::DocumentPtr | document | ) | [private] |
Helper function to add the operating region to the KML file.
Definition at line 182 of file CaddyKML.cpp.
| void labust::gearth::CaddyKML::addShipPosition | ( | const auv_msgs::NavSts::ConstPtr & | nav | ) | [inline] |
Add a new coordinate of the ship.
| nav | Navigation data. |
Definition at line 103 of file CaddyKML.hpp.
| void CaddyKML::addVarianceRegion | ( | const auv_msgs::NavSts & | nav, |
| kmldom::DocumentPtr | document | ||
| ) | [private] |
Helper function to add the variance region.
Definition at line 116 of file CaddyKML.cpp.
| void labust::gearth::CaddyKML::addVehiclePosition | ( | const auv_msgs::NavSts::ConstPtr & | nav | ) | [inline] |
Add a new coordinate and attitude of the vehicle.
| nav | Navigation data. |
Definition at line 86 of file CaddyKML.hpp.
| void CaddyKML::run | ( | ) |
File writer.
Definition at line 236 of file CaddyKML.cpp.
| void CaddyKML::setDiverOrigin | ( | const geometry_msgs::Point::ConstPtr & | point | ) |
Update the diver origin.
Definition at line 217 of file CaddyKML.cpp.
| void CaddyKML::write | ( | ) |
Write data to the KML file.
Definition at line 87 of file CaddyKML.cpp.
auv_msgs::NavSts labust::gearth::CaddyKML::diver [private] |
The navigation stats.
Definition at line 179 of file CaddyKML.hpp.
kmlbase::Vec3 labust::gearth::CaddyKML::diverOrigin [private] |
The diver origin.
Definition at line 155 of file CaddyKML.hpp.
kmldom::KmlFactory* labust::gearth::CaddyKML::factory [private] |
The KML factory for creating KML files.
Definition at line 159 of file CaddyKML.hpp.
std::string labust::gearth::CaddyKML::filename [private] |
KML filename
Definition at line 167 of file CaddyKML.hpp.
kmldom::DocumentPtr labust::gearth::CaddyKML::folder [private] |
Document that holds all components together.
Definition at line 163 of file CaddyKML.hpp.
boost::mutex labust::gearth::CaddyKML::kml_mux [private] |
The write mutex.
Definition at line 175 of file CaddyKML.hpp.
std::ofstream labust::gearth::CaddyKML::kmlFile [private] |
The KML file.
Definition at line 171 of file CaddyKML.hpp.
kmldom::CoordinatesPtr labust::gearth::CaddyKML::opRegion [private] |
The acoustic KML operating region.
Definition at line 151 of file CaddyKML.hpp.
CustomLineString<TransparentSegments> labust::gearth::CaddyKML::path [private] |
Vehicle path
Definition at line 139 of file CaddyKML.hpp.
auv_msgs::NavSts labust::gearth::CaddyKML::platform [private] |
Definition at line 179 of file CaddyKML.hpp.
CustomLineString<TransparentSegments> labust::gearth::CaddyKML::platformPath [private] |
Definition at line 139 of file CaddyKML.hpp.
bool labust::gearth::CaddyKML::runFlag [private] |
The runner flag.
Definition at line 187 of file CaddyKML.hpp.
VehiclePolygon labust::gearth::CaddyKML::ship [private] |
Ship polygon.
Definition at line 147 of file CaddyKML.hpp.
VehiclePolygon labust::gearth::CaddyKML::vehicle [private] |
Vehicle polygon.
Definition at line 143 of file CaddyKML.hpp.
boost::thread labust::gearth::CaddyKML::worker [private] |
The worker thread.
Definition at line 183 of file CaddyKML.hpp.