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 #include <hector_geotiff/map_writer_interface.h>
00030 #include <hector_geotiff/map_writer_plugin_interface.h>
00031
00032 #include <ros/ros.h>
00033 #include <hector_nav_msgs/GetRobotTrajectory.h>
00034
00035 #include <pluginlib/class_loader.h>
00036 #include <fstream>
00037
00038 namespace hector_geotiff_plugins
00039 {
00040
00041 using namespace hector_geotiff;
00042
00043 class TrajectoryMapWriter : public MapWriterPluginInterface
00044 {
00045 public:
00046 TrajectoryMapWriter();
00047 virtual ~TrajectoryMapWriter();
00048
00049 virtual void initialize(const std::string& name);
00050 virtual void draw(MapWriterInterface *interface);
00051
00052 protected:
00053 ros::NodeHandle nh_;
00054 ros::ServiceClient service_client_;
00055
00056 bool initialized_;
00057 std::string name_;
00058 bool draw_all_objects_;
00059 std::string class_id_;
00060 int path_color_r_;
00061 int path_color_g_;
00062 int path_color_b_;
00063 };
00064
00065 TrajectoryMapWriter::TrajectoryMapWriter()
00066 : initialized_(false)
00067 {}
00068
00069 TrajectoryMapWriter::~TrajectoryMapWriter()
00070 {}
00071
00072 void TrajectoryMapWriter::initialize(const std::string& name)
00073 {
00074 ros::NodeHandle plugin_nh("~/" + name);
00075 std::string service_name_;
00076
00077
00078 plugin_nh.param("service_name", service_name_, std::string("trajectory"));
00079 plugin_nh.param("path_color_r", path_color_r_, 120);
00080 plugin_nh.param("path_color_g", path_color_g_, 0);
00081 plugin_nh.param("path_color_b", path_color_b_, 240);
00082
00083 service_client_ = nh_.serviceClient<hector_nav_msgs::GetRobotTrajectory>(service_name_);
00084
00085 initialized_ = true;
00086 this->name_ = name;
00087 ROS_INFO_NAMED(name_, "Successfully initialized hector_geotiff MapWriter plugin %s.", name_.c_str());
00088 }
00089
00090 void TrajectoryMapWriter::draw(MapWriterInterface *interface)
00091 {
00092 if(!initialized_) return;
00093
00094 hector_nav_msgs::GetRobotTrajectory srv_path;
00095 if (!service_client_.call(srv_path)) {
00096 ROS_ERROR_NAMED(name_, "Cannot draw trajectory, service %s failed", service_client_.getService().c_str());
00097 return;
00098 }
00099
00100 std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
00101
00102 size_t size = traj_vector.size();
00103
00104 std::vector<Eigen::Vector2f> pointVec;
00105 pointVec.resize(size);
00106
00107 for (size_t i = 0; i < size; ++i){
00108 const geometry_msgs::PoseStamped& pose (traj_vector[i]);
00109
00110 pointVec[i] = Eigen::Vector2f(pose.pose.position.x, pose.pose.position.y);
00111 }
00112
00113 if (size > 0){
00114
00115 Eigen::Vector3f startVec(pointVec[0].x(),pointVec[0].y(),0.0f);
00116 interface->drawPath(startVec, pointVec, path_color_r_, path_color_g_, path_color_b_);
00117 }
00118 }
00119
00120 }
00121
00122
00123 #include <pluginlib/class_list_macros.h>
00124 #ifdef PLUGINLIB_EXPORT_CLASS
00125 PLUGINLIB_EXPORT_CLASS(hector_geotiff_plugins::TrajectoryMapWriter, hector_geotiff::MapWriterPluginInterface)
00126 #else
00127 PLUGINLIB_DECLARE_CLASS(hector_geotiff_plugins, TrajectoryMapWriter, hector_geotiff_plugins::TrajectoryMapWriter, hector_geotiff::MapWriterPluginInterface)
00128 #endif