#include <route_point.h>
Definition at line 47 of file route_point.h.
◆ RoutePoint()
| swri_route_util::RoutePoint::RoutePoint |
( |
| ) |
|
◆ deleteProperty()
| void swri_route_util::RoutePoint::deleteProperty |
( |
const std::string & |
name | ) |
|
◆ getProperty()
| std::string swri_route_util::RoutePoint::getProperty |
( |
const std::string & |
name | ) |
const |
◆ getPropertyNames()
| std::vector< std::string > swri_route_util::RoutePoint::getPropertyNames |
( |
| ) |
const |
◆ getTypedProperty()
template<typename T >
| T swri_route_util::RoutePoint::getTypedProperty |
( |
const std::string & |
name | ) |
const |
|
inline |
◆ hasProperty()
| bool swri_route_util::RoutePoint::hasProperty |
( |
const std::string & |
name | ) |
const |
◆ id()
| const std::string & swri_route_util::RoutePoint::id |
( |
| ) |
const |
|
inline |
◆ orientation() [1/2]
◆ orientation() [2/2]
◆ orientationMsg()
| const geometry_msgs::Quaternion swri_route_util::RoutePoint::orientationMsg |
( |
| ) |
const |
|
inline |
◆ pose()
| tf::Pose swri_route_util::RoutePoint::pose |
( |
| ) |
const |
|
inline |
◆ poseMsg()
◆ position() [1/2]
| tf::Vector3& swri_route_util::RoutePoint::position |
( |
| ) |
|
◆ position() [2/2]
| tf::Vector3 & swri_route_util::RoutePoint::position |
( |
| ) |
const |
|
inline |
◆ positionMsg()
◆ routePosition()
| marti_nav_msgs::RoutePosition swri_route_util::RoutePoint::routePosition |
( |
| ) |
const |
|
inline |
◆ setId()
| void swri_route_util::RoutePoint::setId |
( |
const std::string & |
id | ) |
|
|
inline |
◆ setOrientation() [1/2]
| void swri_route_util::RoutePoint::setOrientation |
( |
const geometry_msgs::Quaternion & |
orientation | ) |
|
|
inline |
◆ setOrientation() [2/2]
| void swri_route_util::RoutePoint::setOrientation |
( |
const tf::Quaternion & |
orientation | ) |
|
|
inline |
◆ setPose() [1/2]
◆ setPose() [2/2]
| void swri_route_util::RoutePoint::setPose |
( |
const tf::Pose & |
pose | ) |
|
|
inline |
◆ setPosition() [1/2]
◆ setPosition() [2/2]
| void swri_route_util::RoutePoint::setPosition |
( |
const tf::Vector3 & |
position | ) |
|
|
inline |
◆ setProperty()
| void swri_route_util::RoutePoint::setProperty |
( |
const std::string & |
name, |
|
|
const std::string & |
value |
|
) |
| |
◆ setStopPoint()
| void swri_route_util::RoutePoint::setStopPoint |
( |
bool |
value | ) |
|
|
inline |
◆ setStopPointDelay()
| void swri_route_util::RoutePoint::setStopPointDelay |
( |
double |
delay | ) |
|
|
inline |
◆ stopPoint()
| bool swri_route_util::RoutePoint::stopPoint |
( |
| ) |
const |
|
inline |
◆ stopPointDelay()
| double swri_route_util::RoutePoint::stopPointDelay |
( |
| ) |
const |
|
inline |
◆ id_
| std::string swri_route_util::RoutePoint::id_ |
|
private |
◆ orientation_
◆ position_
| tf::Vector3 swri_route_util::RoutePoint::position_ |
|
private |
◆ properties_
| std::map<std::string, std::string> swri_route_util::RoutePoint::properties_ |
|
private |
◆ stop_point_
| bool swri_route_util::RoutePoint::stop_point_ |
|
private |
◆ stop_point_delay_
| double swri_route_util::RoutePoint::stop_point_delay_ |
|
private |
The documentation for this class was generated from the following files: