#include <route.h>
Public Member Functions | |
| void | deleteProperty (const std::string &name) |
| bool | findPointId (size_t &index, const std::string &id) const |
| bool | findPointIdConst (size_t &index, const std::string &id) const |
| std::string | getProperty (const std::string &name) const |
| std::vector< std::string > | getPropertyNames () const |
| template<typename T > | |
| T | getTypedProperty (const std::string &name) const |
| std::string | guid () const |
| bool | hasProperty (const std::string &name) const |
| std::string | name () const |
| void | rebuildPointIndex () const |
| Route () | |
| Route (const marti_nav_msgs::Route &msg) | |
| void | setGuid (const std::string &guid) |
| void | setName (const std::string &name) |
| void | setProperty (const std::string &name, const std::string &value) |
| void | toMsg (marti_nav_msgs::Route &msg) const |
| marti_nav_msgs::RoutePtr | toMsgPtr () const |
| bool | valid () const |
Public Attributes | |
| std::string | guid_ |
| std_msgs::Header | header |
| std::string | name_ |
| std::map< std::string, size_t > | point_index_ |
| std::vector< RoutePoint > | points |
| std::map< std::string, std::string > | properties_ |
| swri_route_util::Route::Route | ( | const marti_nav_msgs::Route & | msg | ) |
| void swri_route_util::Route::deleteProperty | ( | const std::string & | name | ) |
| bool swri_route_util::Route::findPointId | ( | size_t & | index, |
| const std::string & | id | ||
| ) | const |
| bool swri_route_util::Route::findPointIdConst | ( | size_t & | index, |
| const std::string & | id | ||
| ) | const |
| std::string swri_route_util::Route::getProperty | ( | const std::string & | name | ) | const |
| std::vector< std::string > swri_route_util::Route::getPropertyNames | ( | ) | const |
| T swri_route_util::Route::getTypedProperty | ( | const std::string & | name | ) | const [inline] |
| std::string swri_route_util::Route::guid | ( | ) | const |
| bool swri_route_util::Route::hasProperty | ( | const std::string & | name | ) | const |
| std::string swri_route_util::Route::name | ( | ) | const |
| void swri_route_util::Route::rebuildPointIndex | ( | ) | const |
| void swri_route_util::Route::setGuid | ( | const std::string & | guid | ) |
| void swri_route_util::Route::setName | ( | const std::string & | name | ) |
| void swri_route_util::Route::setProperty | ( | const std::string & | name, |
| const std::string & | value | ||
| ) |
| void swri_route_util::Route::toMsg | ( | marti_nav_msgs::Route & | msg | ) | const |
| mnm::RoutePtr swri_route_util::Route::toMsgPtr | ( | ) | const |
| bool swri_route_util::Route::valid | ( | ) | const |
| std::string swri_route_util::Route::guid_ |
| std::string swri_route_util::Route::name_ |
std::map<std::string, size_t> swri_route_util::Route::point_index_ [mutable] |
| std::vector<RoutePoint> swri_route_util::Route::points |
| std::map<std::string, std::string> swri_route_util::Route::properties_ |