Go to the documentation of this file.
   29 #ifndef SWRI_ROUTE_UTIL_ROUTE_H_ 
   30 #define SWRI_ROUTE_UTIL_ROUTE_H_ 
   36 #include <boost/lexical_cast.hpp> 
   38 #include <marti_nav_msgs/Route.h> 
   67   Route(
const marti_nav_msgs::Route &
msg);
 
   70   void toMsg(marti_nav_msgs::Route &
msg) 
const;
 
   94   bool findPointId(
size_t &index, 
const std::string &
id) 
const;
 
  115   std::string 
name() 
const;
 
  120   std::string 
guid() 
const;
 
  136   template <
typename T>
 
  183 #endif  // SWRI_ROUTE_UTIL_ROUTE_H_ 
  
void toMsg(marti_nav_msgs::Route &msg) const
boost::shared_ptr< Route > RoutePtr
std::map< std::string, std::string > properties_
std::vector< std::string > getPropertyNames() const
std::string getProperty(const std::string &name) const
void rebuildPointIndex() const
std::map< std::string, size_t > point_index_
void setName(const std::string &name)
bool findPointIdConst(size_t &index, const std::string &id) const
T getTypedProperty(const std::string &name) const
std::vector< RoutePoint > points
bool findPointId(size_t &index, const std::string &id) const
void deleteProperty(const std::string &name)
void setGuid(const std::string &guid)
bool hasProperty(const std::string &name) const
boost::shared_ptr< Route const  > RouteConstPtr
void setProperty(const std::string &name, const std::string &value)
marti_nav_msgs::RoutePtr toMsgPtr() const