Go to the documentation of this file.
   31 #include <boost/make_shared.hpp> 
   33 namespace mnm = marti_nav_msgs;
 
   48   for (
auto const &prop : src.properties) {
 
   58   for (
size_t i = 0; i < 
points.size(); ++i) {
 
   62   for (
auto const &prop : 
msg.properties) {
 
   77   dst.properties.resize(names.size());
 
   78   for (
size_t i = 0; i < names.size(); ++i) {
 
   79     dst.properties[i].key = names[i];
 
   80     dst.properties[i].value = src.
getProperty(names[i]);
 
   89   for (
size_t i = 0; i < 
points.size(); ++i) {
 
   94   msg.properties.resize(names.size());
 
   95   for (
size_t i = 0; i < names.size(); ++i) {
 
   96     msg.properties[i].key = names[i];
 
  160   std::vector<std::string> names;
 
  161   names.push_back(
"name");
 
  162   names.push_back(
"guid");
 
  165     names.push_back(it.first);
 
  173   if (
name == 
"name") {
 
  175   } 
else if (
name == 
"guid") {
 
  186   if (
name == 
"name") {
 
  188   } 
else if (
name == 
"guid") {
 
  197   if (
name == 
"name") {
 
  199   } 
else if (
name == 
"guid") {
 
  240   for (
size_t i = 0; i < 
points.size(); ++i) {
 
  245     ROS_ERROR(
"Route points do not have unique IDs.  This will likely cause problems.");
 
  
void toMsg(marti_nav_msgs::Route &msg) const
boost::shared_ptr< Route > RoutePtr
std::map< std::string, std::string > properties_
static void pointFromMsg(RoutePoint &dst, const marti_nav_msgs::RoutePoint &src)
std::vector< std::string > getPropertyNames() const
void setId(const std::string &id)
const std::string & id() const
std::string getProperty(const std::string &name) const
void rebuildPointIndex() const
std::map< std::string, size_t > point_index_
void setName(const std::string &name)
geometry_msgs::Pose poseMsg() const
void setPose(const tf::Pose &pose)
bool findPointIdConst(size_t &index, const std::string &id) const
static void msgFromPoint(marti_nav_msgs::RoutePoint &dst, const RoutePoint &src)
std::vector< RoutePoint > points
std::vector< std::string > getPropertyNames() const
bool findPointId(size_t &index, const std::string &id) const
void deleteProperty(const std::string &name)
void setProperty(const std::string &name, const std::string &value)
std::string getProperty(const std::string &name) const
void setGuid(const std::string &guid)
bool hasProperty(const std::string &name) const
void setProperty(const std::string &name, const std::string &value)
marti_nav_msgs::RoutePtr toMsgPtr() const