#include <route_point.h>
Public Member Functions | |
| void | deleteProperty (const std::string &name) |
| std::string | getProperty (const std::string &name) const |
| std::vector< std::string > | getPropertyNames () const |
| template<typename T > | |
| T | getTypedProperty (const std::string &name) const |
| bool | hasProperty (const std::string &name) const |
| const std::string & | id () const |
| const tf::Quaternion & | orientation () const |
| tf::Quaternion & | orientation () |
| const geometry_msgs::Quaternion | orientationMsg () const |
| tf::Pose | pose () const |
| geometry_msgs::Pose | poseMsg () const |
| const tf::Vector3 & | position () const |
| tf::Vector3 & | position () |
| const geometry_msgs::Point | positionMsg () const |
| RoutePoint () | |
| marti_nav_msgs::RoutePosition | routePosition () const |
| void | setId (const std::string &id) |
| void | setOrientation (const tf::Quaternion &orientation) |
| void | setOrientation (const geometry_msgs::Quaternion &orientation) |
| void | setPose (const tf::Pose &pose) |
| void | setPose (const geometry_msgs::Pose &pose) |
| void | setPosition (const tf::Vector3 &position) |
| void | setPosition (const geometry_msgs::Point &position) |
| void | setProperty (const std::string &name, const std::string &value) |
| void | setStopPoint (bool value) |
| void | setStopPointDelay (double delay) |
| bool | stopPoint () const |
| double | stopPointDelay () const |
Private Attributes | |
| std::string | id_ |
| tf::Quaternion | orientation_ |
| tf::Vector3 | position_ |
| std::map< std::string, std::string > | properties_ |
| bool | stop_point_ |
| double | stop_point_delay_ |
Definition at line 47 of file route_point.h.
Definition at line 33 of file route_point.cpp.
| void swri_route_util::RoutePoint::deleteProperty | ( | const std::string & | name | ) |
Definition at line 87 of file route_point.cpp.
| std::string swri_route_util::RoutePoint::getProperty | ( | const std::string & | name | ) | const |
Definition at line 52 of file route_point.cpp.
| std::vector< std::string > swri_route_util::RoutePoint::getPropertyNames | ( | ) | const |
Definition at line 39 of file route_point.cpp.
| T swri_route_util::RoutePoint::getTypedProperty | ( | const std::string & | name | ) | const [inline] |
Definition at line 179 of file route_point_inline.h.
| bool swri_route_util::RoutePoint::hasProperty | ( | const std::string & | name | ) | const |
Definition at line 69 of file route_point.cpp.
| const std::string & swri_route_util::RoutePoint::id | ( | ) | const [inline] |
Definition at line 133 of file route_point_inline.h.
| const tf::Quaternion & swri_route_util::RoutePoint::orientation | ( | ) | const [inline] |
Definition at line 75 of file route_point_inline.h.
| tf::Quaternion & swri_route_util::RoutePoint::orientation | ( | ) | [inline] |
Definition at line 81 of file route_point_inline.h.
| const geometry_msgs::Quaternion swri_route_util::RoutePoint::orientationMsg | ( | ) | const [inline] |
Definition at line 93 of file route_point_inline.h.
| tf::Pose swri_route_util::RoutePoint::pose | ( | ) | const [inline] |
Definition at line 108 of file route_point_inline.h.
| geometry_msgs::Pose swri_route_util::RoutePoint::poseMsg | ( | ) | const [inline] |
Definition at line 124 of file route_point_inline.h.
| const tf::Vector3 & swri_route_util::RoutePoint::position | ( | ) | const [inline] |
Definition at line 43 of file route_point_inline.h.
| tf::Vector3 & swri_route_util::RoutePoint::position | ( | ) | [inline] |
Definition at line 49 of file route_point_inline.h.
| const geometry_msgs::Point swri_route_util::RoutePoint::positionMsg | ( | ) | const [inline] |
Definition at line 61 of file route_point_inline.h.
| marti_nav_msgs::RoutePosition swri_route_util::RoutePoint::routePosition | ( | ) | const [inline] |
Definition at line 145 of file route_point_inline.h.
| void swri_route_util::RoutePoint::setId | ( | const std::string & | id | ) | [inline] |
Definition at line 139 of file route_point_inline.h.
| void swri_route_util::RoutePoint::setOrientation | ( | const tf::Quaternion & | orientation | ) | [inline] |
Definition at line 69 of file route_point_inline.h.
| void swri_route_util::RoutePoint::setOrientation | ( | const geometry_msgs::Quaternion & | orientation | ) | [inline] |
Definition at line 87 of file route_point_inline.h.
| void swri_route_util::RoutePoint::setPose | ( | const tf::Pose & | pose | ) | [inline] |
Definition at line 101 of file route_point_inline.h.
| void swri_route_util::RoutePoint::setPose | ( | const geometry_msgs::Pose & | pose | ) |
| void swri_route_util::RoutePoint::setPosition | ( | const tf::Vector3 & | position | ) | [inline] |
Definition at line 37 of file route_point_inline.h.
| void swri_route_util::RoutePoint::setPosition | ( | const geometry_msgs::Point & | position | ) |
| void swri_route_util::RoutePoint::setProperty | ( | const std::string & | name, |
| const std::string & | value | ||
| ) |
Definition at line 76 of file route_point.cpp.
| void swri_route_util::RoutePoint::setStopPoint | ( | bool | value | ) | [inline] |
Definition at line 160 of file route_point_inline.h.
| void swri_route_util::RoutePoint::setStopPointDelay | ( | double | delay | ) | [inline] |
Definition at line 172 of file route_point_inline.h.
| bool swri_route_util::RoutePoint::stopPoint | ( | ) | const [inline] |
Definition at line 154 of file route_point_inline.h.
| double swri_route_util::RoutePoint::stopPointDelay | ( | ) | const [inline] |
Definition at line 166 of file route_point_inline.h.
std::string swri_route_util::RoutePoint::id_ [private] |
Definition at line 137 of file route_point.h.
Definition at line 135 of file route_point.h.
Definition at line 134 of file route_point.h.
std::map<std::string, std::string> swri_route_util::RoutePoint::properties_ [private] |
Definition at line 142 of file route_point.h.
bool swri_route_util::RoutePoint::stop_point_ [private] |
Definition at line 139 of file route_point.h.
double swri_route_util::RoutePoint::stop_point_delay_ [private] |
Definition at line 140 of file route_point.h.