#include <jockey.h>
Public Member Functions | |
bool | getRotationInvariance () |
double | getSampleCount () |
double | getScaleCount () |
Jockey (const std::string &name) | |
void | onGetDissimilarity () |
void | setRotationInvariance (bool rotation_invariance) |
void | setSampleCount (double sample_count) |
void | setScaleCount (double scale_count) |
Private Member Functions | |
void | getData () |
void | handlePolygon (const geometry_msgs::PolygonConstPtr &msg) |
void | initMapPlaceProfileInterface () |
Private Attributes | |
geometry_msgs::Polygon | current_polygon_ |
DissimilarityGetter | dissimilarity_getter_ |
bool | has_polygon_data_ |
std::string | place_profile_getter_service_name_ |
std::string | place_profile_interface_name_ |
bool | place_profile_interface_name_defined_ |
place_matcher_mcc::Jockey::Jockey | ( | const std::string & | name | ) |
Reimplemented from lama_jockeys::Jockey.
Definition at line 6 of file jockey.cpp.
void place_matcher_mcc::Jockey::getData | ( | ) | [private] |
Start subscribers, wait for an appropriate message and exit upon completion.
Start the subscribers, wait for a Polygon, a LaserScan, or a PlaceProfile and exit upon reception of the first of those.
Definition at line 134 of file jockey.cpp.
bool place_matcher_mcc::Jockey::getRotationInvariance | ( | ) | [inline] |
double place_matcher_mcc::Jockey::getSampleCount | ( | ) | [inline] |
double place_matcher_mcc::Jockey::getScaleCount | ( | ) | [inline] |
void place_matcher_mcc::Jockey::handlePolygon | ( | const geometry_msgs::PolygonConstPtr & | msg | ) | [private] |
Callback for Polygon subscriber, receive a message and store it.
Definition at line 158 of file jockey.cpp.
void place_matcher_mcc::Jockey::initMapPlaceProfileInterface | ( | ) | [private] |
Create the getter proxies for PlaceProfile descriptors.
Definition at line 21 of file jockey.cpp.
void place_matcher_mcc::Jockey::onGetDissimilarity | ( | ) | [virtual] |
Reimplemented from lama_jockeys::LocalizingJockey.
Definition at line 41 of file jockey.cpp.
void place_matcher_mcc::Jockey::setRotationInvariance | ( | bool | rotation_invariance | ) | [inline] |
void place_matcher_mcc::Jockey::setSampleCount | ( | double | sample_count | ) | [inline] |
void place_matcher_mcc::Jockey::setScaleCount | ( | double | scale_count | ) | [inline] |
geometry_msgs::Polygon place_matcher_mcc::Jockey::current_polygon_ [private] |
bool place_matcher_mcc::Jockey::has_polygon_data_ [private] |
std::string place_matcher_mcc::Jockey::place_profile_getter_service_name_ [private] |
std::string place_matcher_mcc::Jockey::place_profile_interface_name_ [private] |