$search
00001 //================================================================================================= 00002 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt 00003 // All rights reserved. 00004 00005 // Redistribution and use in source and binary forms, with or without 00006 // modification, are permitted provided that the following conditions are met: 00007 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Flight Systems and Automatic Control group, 00013 // TU Darmstadt, nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 00029 #include <geotiff_writer/map_writer_interface.h> 00030 #include <geotiff_writer/map_writer_plugin_interface.h> 00031 00032 #include <ros/ros.h> 00033 #include <worldmodel_msgs/GetObjectModel.h> 00034 00035 #include <pluginlib/class_loader.h> 00036 #include <fstream> 00037 00038 namespace worldmodel_geotiff_plugins { 00039 00040 using namespace hector_geotiff; 00041 00042 class MapWriterPlugin : public MapWriterPluginInterface 00043 { 00044 public: 00045 MapWriterPlugin(); 00046 virtual ~MapWriterPlugin(); 00047 00048 virtual void initialize(const std::string& name); 00049 virtual void draw(MapWriterInterface *interface) = 0; 00050 00051 protected: 00052 ros::NodeHandle nh_; 00053 ros::ServiceClient service_client_; 00054 00055 bool initialized_; 00056 std::string name_; 00057 bool draw_all_objects_; 00058 std::string class_id_; 00059 }; 00060 00061 MapWriterPlugin::MapWriterPlugin() 00062 : initialized_(false) 00063 {} 00064 00065 MapWriterPlugin::~MapWriterPlugin() 00066 {} 00067 00068 void MapWriterPlugin::initialize(const std::string& name) 00069 { 00070 ros::NodeHandle plugin_nh("~/" + name); 00071 std::string service_name_; 00072 00073 plugin_nh.param("service_name", service_name_, std::string("worldmodel/get_object_model")); 00074 plugin_nh.param("draw_all_objects", draw_all_objects_, false); 00075 plugin_nh.param("class_id", class_id_, std::string()); 00076 00077 service_client_ = nh_.serviceClient<worldmodel_msgs::GetObjectModel>(service_name_); 00078 00079 initialized_ = true; 00080 this->name_ = name; 00081 ROS_INFO_NAMED(name_, "Successfully initialized hector_geotiff MapWriter plugin %s.", name_.c_str()); 00082 } 00083 00084 class VictimMapWriter : public MapWriterPlugin 00085 { 00086 public: 00087 virtual ~VictimMapWriter() {} 00088 00089 void draw(MapWriterInterface *interface) 00090 { 00091 if (!initialized_) return; 00092 00093 worldmodel_msgs::GetObjectModel data; 00094 if (!service_client_.call(data)) { 00095 ROS_ERROR_NAMED(name_, "Cannot draw victims, service %s failed", service_client_.getService().c_str()); 00096 return; 00097 } 00098 00099 int counter = 0; 00100 for(worldmodel_msgs::ObjectModel::_objects_type::const_iterator it = data.response.model.objects.begin(); it != data.response.model.objects.end(); ++it) { 00101 const worldmodel_msgs::Object& object = *it; 00102 if (!draw_all_objects_ && object.state.state != worldmodel_msgs::ObjectState::CONFIRMED) continue; 00103 if (!class_id_.empty() && object.info.class_id != class_id_) continue; 00104 00105 Eigen::Vector2f coords; 00106 coords.x() = object.pose.pose.position.x; 00107 coords.y() = object.pose.pose.position.y; 00108 interface->drawObjectOfInterest(coords, boost::lexical_cast<std::string>(++counter), MapWriterInterface::Color(240,10,10)); 00109 } 00110 } 00111 }; 00112 00113 class QRCodeMapWriter : public MapWriterPlugin 00114 { 00115 public: 00116 virtual ~QRCodeMapWriter() {} 00117 00118 void draw(MapWriterInterface *interface) 00119 { 00120 if (!initialized_) return; 00121 00122 worldmodel_msgs::GetObjectModel data; 00123 if (!service_client_.call(data)) { 00124 ROS_ERROR_NAMED(name_, "Cannot draw victims, service %s failed", service_client_.getService().c_str()); 00125 return; 00126 } 00127 00128 00129 std::ofstream description_file((interface->getBasePathAndFileName() + ".qrcodes.txt").c_str()); 00130 00131 int counter = 0; 00132 for(worldmodel_msgs::ObjectModel::_objects_type::const_iterator it = data.response.model.objects.begin(); it != data.response.model.objects.end(); ++it) { 00133 const worldmodel_msgs::Object& object = *it; 00134 if (!draw_all_objects_ && object.state.state != worldmodel_msgs::ObjectState::CONFIRMED) continue; 00135 if (!class_id_.empty() && object.info.class_id != class_id_) continue; 00136 00137 Eigen::Vector2f coords; 00138 coords.x() = object.pose.pose.position.x; 00139 coords.y() = object.pose.pose.position.y; 00140 interface->drawObjectOfInterest(coords, boost::lexical_cast<std::string>(++counter), MapWriterInterface::Color(10,10,240)); 00141 00142 if (description_file.is_open()) { 00143 description_file << counter << "," << object.info.object_id << "," << object.pose.pose.position.x << "," << object.pose.pose.position.y << std::endl; 00144 } 00145 } 00146 00147 description_file.close(); 00148 } 00149 }; 00150 00151 } // namespace 00152 00153 //register this planner as a MapWriterPluginInterface plugin 00154 #include <pluginlib/class_list_macros.h> 00155 PLUGINLIB_DECLARE_CLASS(worldmodel_geotiff_plugins, VictimMapWriter, worldmodel_geotiff_plugins::VictimMapWriter, hector_geotiff::MapWriterPluginInterface) 00156 PLUGINLIB_DECLARE_CLASS(worldmodel_geotiff_plugins, QRCodeMapWriter, worldmodel_geotiff_plugins::QRCodeMapWriter, hector_geotiff::MapWriterPluginInterface) 00157