33 #include <hector_nav_msgs/GetRobotTrajectory.h> 49 virtual void initialize(
const std::string& name);
75 std::string service_name_;
78 plugin_nh.
param(
"service_name", service_name_, std::string(
"trajectory"));
94 hector_nav_msgs::GetRobotTrajectory srv_path;
100 std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
102 size_t size = traj_vector.size();
104 std::vector<Eigen::Vector2f> pointVec;
105 pointVec.resize(size);
107 for (
size_t i = 0; i < size; ++i){
108 const geometry_msgs::PoseStamped& pose (traj_vector[i]);
110 pointVec[i] = Eigen::Vector2f(pose.pose.position.x, pose.pose.position.y);
115 Eigen::Vector3f startVec(pointVec[0].x(),pointVec[0].y(),0.0
f);
124 #ifdef PLUGINLIB_EXPORT_CLASS
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)
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)
virtual ~TrajectoryMapWriter()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define ROS_ERROR_NAMED(name,...)
ros::ServiceClient service_client_
virtual void drawPath(const Eigen::Vector3f &start, const std::vector< Eigen::Vector2f > &points)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)