Public Member Functions | List of all members
tuw::ros_msgs::RouteSegments Class Reference

#include <route_segments.h>

Inheritance diagram for tuw::ros_msgs::RouteSegments:
Inheritance graph
[legend]

Public Member Functions

void convert (nav_msgs::Path &path, double sample_distance) const
 
 RouteSegments ()
 
 RouteSegments (size_t n)
 
void set_center (const std::vector< double > &x, const std::vector< double > &y, const std::vector< double > &theta)
 
void set_end (const std::vector< double > &x, const std::vector< double > &y, const std::vector< double > &theta)
 
void set_ids (const std::vector< unsigned int > &id)
 
void set_level (const std::vector< int > &level)
 
void set_motion_type (const std::vector< unsigned int > &motion_type)
 
void set_orientation (const std::vector< unsigned int > &orientation)
 
void set_start (const std::vector< double > &x, const std::vector< double > &y, const std::vector< double > &theta)
 
void set_type (const std::vector< unsigned int > &type)
 

Detailed Description

Definition at line 44 of file route_segments.h.

Constructor & Destructor Documentation

RouteSegments::RouteSegments ( )

Definition at line 39 of file route_segments.cpp.

RouteSegments::RouteSegments ( size_t  n)

Definition at line 43 of file route_segments.cpp.

Member Function Documentation

void RouteSegments::convert ( nav_msgs::Path &  path,
double  sample_distance 
) const

check if an additional end point is needed

add the additional end point

Definition at line 138 of file route_segments.cpp.

void RouteSegments::set_center ( const std::vector< double > &  x,
const std::vector< double > &  y,
const std::vector< double > &  theta 
)

Definition at line 112 of file route_segments.cpp.

void RouteSegments::set_end ( const std::vector< double > &  x,
const std::vector< double > &  y,
const std::vector< double > &  theta 
)

Definition at line 94 of file route_segments.cpp.

void RouteSegments::set_ids ( const std::vector< unsigned int > &  id)

Definition at line 48 of file route_segments.cpp.

void RouteSegments::set_level ( const std::vector< int > &  level)

Definition at line 130 of file route_segments.cpp.

void RouteSegments::set_motion_type ( const std::vector< unsigned int > &  motion_type)

Definition at line 69 of file route_segments.cpp.

void RouteSegments::set_orientation ( const std::vector< unsigned int > &  orientation)

Definition at line 62 of file route_segments.cpp.

void RouteSegments::set_start ( const std::vector< double > &  x,
const std::vector< double > &  y,
const std::vector< double > &  theta 
)

Definition at line 76 of file route_segments.cpp.

void RouteSegments::set_type ( const std::vector< unsigned int > &  type)

Definition at line 55 of file route_segments.cpp.


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


tuw_nav_msgs
Author(s): Markus Bader
autogenerated on Mon Jun 10 2019 15:37:22