trajectory_geotiff_plugin.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012, Gregor Gebhardt, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
31 
32 #include <ros/ros.h>
33 #include <hector_nav_msgs/GetRobotTrajectory.h>
34 
35 #include <pluginlib/class_loader.h>
36 #include <fstream>
37 
39 {
40 
41 using namespace hector_geotiff;
42 
44 {
45 public:
47  virtual ~TrajectoryMapWriter();
48 
49  virtual void initialize(const std::string& name);
50  virtual void draw(MapWriterInterface *interface);
51 
52 protected:
55 
57  std::string name_;
59  std::string class_id_;
63 };
64 
66  : initialized_(false)
67 {}
68 
70 {}
71 
72 void TrajectoryMapWriter::initialize(const std::string& name)
73 {
74  ros::NodeHandle plugin_nh("~/" + name);
75  std::string service_name_;
76 
77 
78  plugin_nh.param("service_name", service_name_, std::string("trajectory"));
79  plugin_nh.param("path_color_r", path_color_r_, 120);
80  plugin_nh.param("path_color_g", path_color_g_, 0);
81  plugin_nh.param("path_color_b", path_color_b_, 240);
82 
83  service_client_ = nh_.serviceClient<hector_nav_msgs::GetRobotTrajectory>(service_name_);
84 
85  initialized_ = true;
86  this->name_ = name;
87  ROS_INFO_NAMED(name_, "Successfully initialized hector_geotiff MapWriter plugin %s.", name_.c_str());
88 }
89 
91 {
92  if(!initialized_) return;
93 
94  hector_nav_msgs::GetRobotTrajectory srv_path;
95  if (!service_client_.call(srv_path)) {
96  ROS_ERROR_NAMED(name_, "Cannot draw trajectory, service %s failed", service_client_.getService().c_str());
97  return;
98  }
99 
100  std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
101 
102  size_t size = traj_vector.size();
103 
104  std::vector<Eigen::Vector2f> pointVec;
105  pointVec.resize(size);
106 
107  for (size_t i = 0; i < size; ++i){
108  const geometry_msgs::PoseStamped& pose (traj_vector[i]);
109 
110  pointVec[i] = Eigen::Vector2f(pose.pose.position.x, pose.pose.position.y);
111  }
112 
113  if (size > 0){
114  //Eigen::Vector3f startVec(pose_vector[0].x,pose_vector[0].y,pose_vector[0].z);
115  Eigen::Vector3f startVec(pointVec[0].x(),pointVec[0].y(),0.0f);
116  interface->drawPath(startVec, pointVec, path_color_r_, path_color_g_, path_color_b_);
117  }
118 }
119 
120 } // namespace
121 
122 //register this planner as a MapWriterPluginInterface plugin
124 #ifdef PLUGINLIB_EXPORT_CLASS
126 #else
128 #endif
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
#define ROS_INFO_NAMED(name,...)
virtual void initialize(const std::string &name)
f
ROSCONSOLE_DECL void initialize()
bool call(MReq &req, MRes &res)
virtual void draw(MapWriterInterface *interface)
#define PLUGINLIB_DECLARE_CLASS(pkg, class_name, class_type, base_class_type)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_ERROR_NAMED(name,...)
virtual void drawPath(const Eigen::Vector3f &start, const std::vector< Eigen::Vector2f > &points)
std::string getService()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)


hector_geotiff_plugins
Author(s): Stefan Kohlbrecher , Gregor Gebhardt
autogenerated on Sun Nov 3 2019 03:18:39