#include <jockey.h>

Public Member Functions | |
| Jockey (std::string name, const double frontier_width, const double max_frontier_angle=0.785) | |
| virtual void | onGetDissimilarity () |
| virtual void | onGetEdgesDescriptors () |
| virtual void | onGetVertexDescriptor () |
| virtual void | onLocalizeEdge () |
| virtual void | onLocalizeInVertex () |
| void | setDissimilarityServerName (std::string name) |
Protected Attributes | |
| ros::ServiceClient | crossing_descriptor_setter_ |
| crossing_detector::LaserCrossingDetector | crossing_detector_ |
| std::string | crossing_interface_name_ |
| Interface name in the database, access via "~crossing_interface_name". | |
| bool | data_received_ |
| ros::ServiceClient | dissimilarity_server_ |
| std::string | dissimilarity_server_name_ |
| Service name, access via "~dissimilarity_server_name". | |
| ros::ServiceClient | laser_descriptor_getter_ |
| Client to laser scan getter for LaMa. | |
| ros::ServiceClient | laser_descriptor_setter_ |
| Client to laser scan setter for LaMa. | |
| std::string | laser_interface_name_ |
| Interface name in the database, access via "~laser_interface_name". | |
| ros::Subscriber | laserHandler_ |
| sensor_msgs::LaserScan | scan_ |
| Last received laser scan. | |
| ros::Time | scan_reception_time_ |
| Time of reception of last received laser scan. | |
Private Member Functions | |
| lama_msgs::DescriptorLink | crossingDescriptorLink (const int32_t id) |
| void | getData () |
| void | handleLaser (const sensor_msgs::LaserScanConstPtr &msg) |
| bool | initMapCrossingInterface () |
| bool | initMapLaserInterface () |
| lama_msgs::DescriptorLink | laserDescriptorLink (const int32_t id) |
| lj_laser::Jockey::Jockey | ( | std::string | name, |
| const double | frontier_width, | ||
| const double | max_frontier_angle = 0.785 |
||
| ) |
Definition at line 5 of file jockey.cpp.
| lama_msgs::DescriptorLink lj_laser::Jockey::crossingDescriptorLink | ( | const int32_t | id | ) | [private] |
Return a DescriptorLink for Crossing.
Definition at line 281 of file jockey.cpp.
| void lj_laser::Jockey::getData | ( | ) | [private] |
Start the subscriber, wait for a LaserScan and exit upon reception.
Definition at line 84 of file jockey.cpp.
| void lj_laser::Jockey::handleLaser | ( | const sensor_msgs::LaserScanConstPtr & | msg | ) | [private] |
Receive a LaserScan message and store it.
Definition at line 105 of file jockey.cpp.
| bool lj_laser::Jockey::initMapCrossingInterface | ( | ) | [private] |
Create the setter services for Crossing descriptors.
Definition at line 62 of file jockey.cpp.
| bool lj_laser::Jockey::initMapLaserInterface | ( | ) | [private] |
Create the getter and setter services for LaserScan descriptors.
Definition at line 36 of file jockey.cpp.
| lama_msgs::DescriptorLink lj_laser::Jockey::laserDescriptorLink | ( | const int32_t | id | ) | [private] |
Return a DescriptorLink for LaserScan.
Definition at line 269 of file jockey.cpp.
| void lj_laser::Jockey::onGetDissimilarity | ( | ) | [virtual] |
Reimplemented from lama_jockeys::LocalizingJockey.
Definition at line 184 of file jockey.cpp.
| void lj_laser::Jockey::onGetEdgesDescriptors | ( | ) | [virtual] |
Reimplemented from lama_jockeys::LocalizingJockey.
Definition at line 163 of file jockey.cpp.
| void lj_laser::Jockey::onGetVertexDescriptor | ( | ) | [virtual] |
Return the vertex descriptors associated with the current robot position through result_.
The descriptor are a LaserScan and a Crossing.
Reimplemented from lama_jockeys::LocalizingJockey.
Definition at line 119 of file jockey.cpp.
| void lj_laser::Jockey::onLocalizeEdge | ( | ) | [virtual] |
Reimplemented from lama_jockeys::LocalizingJockey.
Definition at line 177 of file jockey.cpp.
| void lj_laser::Jockey::onLocalizeInVertex | ( | ) | [virtual] |
Reimplemented from lama_jockeys::LocalizingJockey.
Definition at line 170 of file jockey.cpp.
| void lj_laser::Jockey::setDissimilarityServerName | ( | std::string | name | ) | [inline] |
std::string lj_laser::Jockey::crossing_interface_name_ [protected] |
bool lj_laser::Jockey::data_received_ [protected] |
std::string lj_laser::Jockey::dissimilarity_server_name_ [protected] |
std::string lj_laser::Jockey::laser_interface_name_ [protected] |
ros::Subscriber lj_laser::Jockey::laserHandler_ [protected] |
sensor_msgs::LaserScan lj_laser::Jockey::scan_ [protected] |
ros::Time lj_laser::Jockey::scan_reception_time_ [protected] |