Public Member Functions | Private Attributes
swri_route_util::RoutePoint Class Reference

#include <route_point.h>

List of all members.

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::Quaternionorientation () const
tf::Quaternionorientation ()
const geometry_msgs::Quaternion orientationMsg () const
tf::Pose pose () const
geometry_msgs::Pose poseMsg () const
const tf::Vector3position () const
tf::Vector3position ()
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_

Detailed Description

Definition at line 47 of file route_point.h.


Constructor & Destructor Documentation

Definition at line 33 of file route_point.cpp.


Member Function Documentation

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.

template<typename T >
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.

Definition at line 75 of file route_point_inline.h.

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.

Definition at line 108 of file route_point_inline.h.

Definition at line 124 of file route_point_inline.h.

Definition at line 43 of file route_point_inline.h.

Definition at line 49 of file route_point_inline.h.

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::setPosition ( const tf::Vector3 position) [inline]

Definition at line 37 of file route_point_inline.h.

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.

Definition at line 166 of file route_point_inline.h.


Member Data Documentation

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.

Definition at line 139 of file route_point.h.

Definition at line 140 of file route_point.h.


The documentation for this class was generated from the following files:


swri_route_util
Author(s):
autogenerated on Tue Oct 3 2017 03:19:53