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