Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <kml/engine.h>
00038 #include <kml/dom.h>
00039
00040 #include <std_msgs/String.h>
00041 #include <std_msgs/Float64MultiArray.h>
00042 #include <ros/ros.h>
00043
00044 #include <boost/bind.hpp>
00045
00046 #include <fstream>
00047
00048
00049
00050 class PlacemarkFilter : public kmldom::ParserObserver {
00051 public:
00052 PlacemarkFilter():
00053 msgptr(new std_msgs::Float64MultiArray()){}
00054
00055 virtual bool NewElement(const kmldom::ElementPtr& element)
00056 {
00057 if (kmldom::PlacemarkPtr placemark = kmldom::AsPlacemark(element))
00058 placemarks.push_back(placemark);
00059 return true;
00060 }
00061
00062 inline void processPlacemarks()
00063 {
00064 for(int i=0; i<placemarks.size(); ++i) processPlacemark(placemarks[i]);
00065 }
00066
00067 void processPlacemark(kmldom::PlacemarkPtr placemark)
00068 {
00069 ROS_INFO("Found placemark %s",placemark->get_name().c_str());
00070 kmldom::GeometryPtr geom = placemark->get_geometry();
00071 kmldom::CoordinatesPtr coordinates;
00072 if (kmldom::PointPtr point = kmldom::AsPoint(geom))
00073 {
00074 coordinates = point->get_coordinates();
00075 ROS_INFO("Placemark type is point:");
00076 }
00077 else if (kmldom::LineStringPtr lstring = kmldom::AsLineString(geom))
00078 {
00079 ROS_INFO("Placemark type is line string.");
00080 coordinates = lstring->get_coordinates();
00081 }
00082 else
00083 {
00084 ROS_INFO("Placemark type is unknown.");
00085 }
00086
00087 for (int i=0; i<coordinates->get_coordinates_array_size(); ++i)
00088 {
00089 kmlbase::Vec3 point = coordinates->get_coordinates_array_at(i);
00090 msgptr->data.push_back(point.get_latitude());
00091 msgptr->data.push_back(point.get_longitude());
00092 }
00093 }
00094
00095 std::vector < kmldom::PlacemarkPtr > placemarks;
00096 std_msgs::Float64MultiArrayPtr msgptr;
00097 };
00098
00099 void readKml(std::ifstream& input_file, std::string& kmlfile)
00100 {
00101 int n = 0;
00102 do
00103 {
00104 char buffer[100];
00105 n = input_file.readsome(buffer,sizeof(buffer));
00106 kmlfile.append(buffer,n);
00107 }
00108 while ((n != 0) && (!input_file.eof()));
00109 }
00110
00111 void onUploadRequest(ros::Publisher& kmlout, const std_msgs::String::ConstPtr& path)
00112 {
00113 std::ifstream input_file(path->data.c_str(), std::ios_base::in|std::ios_base::binary);
00114 if (!input_file.is_open() || !input_file.good())
00115 {
00116 ROS_ERROR("Failed to open file: %s", path->data.c_str());
00117 return;
00118 }
00119
00120 std::string kmlfile;
00121 readKml(input_file,kmlfile);
00122 ROS_INFO("Loaded kml file %s",path->data.c_str());
00123
00124
00125 kmldom::Parser parser;
00126 PlacemarkFilter filter;
00127 parser.AddObserver(&filter);
00128 std::string errors;
00129 kmldom::ElementPtr root = parser.Parse(kmlfile,&errors);
00130
00131 if (!root)
00132 {
00133 ROS_ERROR("Kml parse errors: %s",errors.c_str());
00134 return;
00135 }
00136
00137 filter.processPlacemarks();
00138
00139 kmlout.publish(filter.msgptr);
00140 }
00141
00143 int main(int argc, char* argv[])
00144 {
00145 ros::init(argc,argv,"kml_upload");
00146 ros::NodeHandle nh;
00147
00148 ros::Publisher kmlout = nh.advertise<std_msgs::Float64MultiArray>("kml_array",1);
00149 ros::Subscriber platform = nh.subscribe<std_msgs::String>("kml_file",
00150 1, boost::bind(&onUploadRequest,boost::ref(kmlout),_1));
00151
00152 ros::spin();
00153 return 0;
00154 }
00155
00156
00157
00158
00159