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 };
00061
00062 TrajectoryMapWriter::TrajectoryMapWriter()
00063 : initialized_(false)
00064 {}
00065
00066 TrajectoryMapWriter::~TrajectoryMapWriter()
00067 {}
00068
00069 void TrajectoryMapWriter::initialize(const std::string& name)
00070 {
00071 ros::NodeHandle plugin_nh("~/" + name);
00072 std::string service_name_;
00073
00074 plugin_nh.param("service_name", service_name_, std::string("trajectory"));
00075
00076 service_client_ = nh_.serviceClient<hector_nav_msgs::GetRobotTrajectory>(service_name_);
00077
00078 initialized_ = true;
00079 this->name_ = name;
00080 ROS_INFO_NAMED(name_, "Successfully initialized hector_geotiff MapWriter plugin %s.", name_.c_str());
00081 }
00082
00083 void TrajectoryMapWriter::draw(MapWriterInterface *interface)
00084 {
00085 if(!initialized_) return;
00086
00087 hector_nav_msgs::GetRobotTrajectory srv_path;
00088 if (!service_client_.call(srv_path)) {
00089 ROS_ERROR_NAMED(name_, "Cannot draw trajectory, service %s failed", service_client_.getService().c_str());
00090 return;
00091 }
00092
00093 std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
00094
00095 size_t size = traj_vector.size();
00096
00097 std::vector<Eigen::Vector2f> pointVec;
00098 pointVec.resize(size);
00099
00100 for (size_t i = 0; i < size; ++i){
00101 const geometry_msgs::PoseStamped& pose (traj_vector[i]);
00102
00103 pointVec[i] = Eigen::Vector2f(pose.pose.position.x, pose.pose.position.y);
00104 }
00105
00106 if (size > 0){
00107
00108 Eigen::Vector3f startVec(pointVec[0].x(),pointVec[0].y(),0.0f);
00109 interface->drawPath(startVec, pointVec);
00110 }
00111 }
00112
00113 }
00114
00115
00116 #include <pluginlib/class_list_macros.h>
00117 #ifdef PLUGINLIB_EXPORT_CLASS
00118 PLUGINLIB_EXPORT_CLASS(hector_geotiff_plugins::TrajectoryMapWriter, hector_geotiff::MapWriterPluginInterface)
00119 #else
00120 PLUGINLIB_DECLARE_CLASS(hector_geotiff_plugins, TrajectoryMapWriter, hector_geotiff_plugins::TrajectoryMapWriter, hector_geotiff::MapWriterPluginInterface)
00121 #endif