Go to the documentation of this file.
   29 #ifndef SWRI_ROUTE_UTIL_ROUTE_POINT_H_ 
   30 #define SWRI_ROUTE_UTIL_ROUTE_POINT_H_ 
   37 #include <marti_nav_msgs/RoutePosition.h> 
   78   geometry_msgs::Pose 
poseMsg() 
const;
 
   82   const std::string& 
id() 
const;
 
   83   void setId(
const std::string &
id);
 
  118   template <
typename T>
 
  148 #endif  // SWRI_ROUTE_UTIL_ROUTE_POINT_H_ 
  
const tf::Quaternion & orientation() const
const geometry_msgs::Quaternion orientationMsg() const
const tf::Vector3 & position() const
const geometry_msgs::Point positionMsg() const
void setId(const std::string &id)
const std::string & id() const
void setStopPointDelay(double delay)
geometry_msgs::Pose poseMsg() const
void setPose(const tf::Pose &pose)
std::vector< std::string > getPropertyNames() const
T getTypedProperty(const std::string &name) const
void deleteProperty(const std::string &name)
void setOrientation(const tf::Quaternion &orientation)
void setProperty(const std::string &name, const std::string &value)
bool hasProperty(const std::string &name) const
std::string getProperty(const std::string &name) const
tf::Quaternion orientation_
double stopPointDelay() const
void setStopPoint(bool value)
void setPosition(const tf::Vector3 &position)
marti_nav_msgs::RoutePosition routePosition() const
std::map< std::string, std::string > properties_