#include <validator.h>
|
enum | Response : uint8_t {
SUCCESS,
VIOLATES_RESAMPLING,
VIOLATES_KEEP_OUT,
VIOLATES_KEEP_IN,
VIOLATES_MINIMUM_FREQUENCY,
VIOLATES_STATIONARY_ENDPOINT,
VIOLATES_FIRST_IN_PAST,
VIOLATES_MINIMUM_SETPOINTS,
VIOLATES_HARD_LIMIT_VEL,
VIOLATES_HARD_LIMIT_ACCEL,
VIOLATES_HARD_LIMIT_OMEGA,
VIOLATES_HARD_LIMIT_ALPHA
} |
|
◆ Response
Enumerator |
---|
SUCCESS | |
VIOLATES_RESAMPLING | |
VIOLATES_KEEP_OUT | |
VIOLATES_KEEP_IN | |
VIOLATES_MINIMUM_FREQUENCY | |
VIOLATES_STATIONARY_ENDPOINT | |
VIOLATES_FIRST_IN_PAST | |
VIOLATES_MINIMUM_SETPOINTS | |
VIOLATES_HARD_LIMIT_VEL | |
VIOLATES_HARD_LIMIT_ACCEL | |
VIOLATES_HARD_LIMIT_OMEGA | |
VIOLATES_HARD_LIMIT_ALPHA | |
◆ CheckSegment()
◆ GetZonesCallback()
bool choreographer::Validator::GetZonesCallback |
( |
ff_msgs::GetZones::Request & |
req, |
|
|
ff_msgs::GetZones::Response & |
res |
|
) |
| |
|
protected |
◆ GetZonesMap()
bool choreographer::Validator::GetZonesMap |
( |
| ) |
|
|
protected |
◆ GetZonesMapCallback()
bool choreographer::Validator::GetZonesMapCallback |
( |
ff_msgs::GetOccupancyMap::Request & |
req, |
|
|
ff_msgs::GetOccupancyMap::Response & |
res |
|
) |
| |
|
protected |
◆ Init()
◆ ProcessZone()
void choreographer::Validator::ProcessZone |
( |
std::vector< signed char > & |
map, |
|
|
int |
type, |
|
|
char |
cell_value, |
|
|
bool |
surface |
|
) |
| |
|
protected |
◆ PublishMarkers()
void choreographer::Validator::PublishMarkers |
( |
| ) |
|
|
protected |
◆ SetZonesCallback()
bool choreographer::Validator::SetZonesCallback |
( |
ff_msgs::SetZones::Request & |
req, |
|
|
ff_msgs::SetZones::Response & |
res |
|
) |
| |
|
protected |
The documentation for this class was generated from the following files: