Go to the documentation of this file.
29 #ifndef SWRI_ROUTE_UTIL_ROUTE_POINT_INLINE_H_
30 #define SWRI_ROUTE_UTIL_ROUTE_POINT_INLINE_H_
32 #include <boost/lexical_cast.hpp>
63 geometry_msgs::Point p;
95 geometry_msgs::Quaternion q;
126 geometry_msgs::Pose
pose;
147 marti_nav_msgs::RoutePosition
position;
177 template <
typename T>
184 #endif // SWRI_ROUTE_UTIL_ROUTE_POINT_INLINE_H_
const tf::Quaternion & orientation() const
const geometry_msgs::Quaternion orientationMsg() const
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
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)
static void pointTFToMsg(const Point &bt_v, geometry_msgs::Point &msg_v)
geometry_msgs::Pose poseMsg() const
void setPose(const tf::Pose &pose)
T getTypedProperty(const std::string &name) const
void setOrientation(const tf::Quaternion &orientation)
static void pointMsgToTF(const geometry_msgs::Point &msg_v, Point &bt_v)
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
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