Public Member Functions | Protected Attributes | Private Member Functions
lj_laser::Jockey Class Reference

#include <jockey.h>

Inheritance diagram for lj_laser::Jockey:
Inheritance graph
[legend]

List of all members.

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)

Detailed Description

Definition at line 63 of file jockey.h.


Constructor & Destructor Documentation

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.


Member Function Documentation

lama_msgs::DescriptorLink lj_laser::Jockey::crossingDescriptorLink ( const int32_t  id) [private]

Return a DescriptorLink for Crossing.

Returns:
DescriptorLink with correct interface_name and id

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.

Create the setter services for Crossing descriptors.

Returns:
true if interface initialization went fine.

Definition at line 62 of file jockey.cpp.

Create the getter and setter services for LaserScan descriptors.

Returns:
true if interface initialization went fine.

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.

Returns:
DescriptorLink with correct interface_name and id

Definition at line 269 of file jockey.cpp.

Reimplemented from lama_jockeys::LocalizingJockey.

Definition at line 184 of file jockey.cpp.

Reimplemented from lama_jockeys::LocalizingJockey.

Definition at line 163 of file jockey.cpp.

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.

Reimplemented from lama_jockeys::LocalizingJockey.

Definition at line 177 of file jockey.cpp.

Reimplemented from lama_jockeys::LocalizingJockey.

Definition at line 170 of file jockey.cpp.

void lj_laser::Jockey::setDissimilarityServerName ( std::string  name) [inline]

Definition at line 77 of file jockey.h.


Member Data Documentation

Definition at line 96 of file jockey.h.

Definition at line 101 of file jockey.h.

Interface name in the database, access via "~crossing_interface_name".

Definition at line 90 of file jockey.h.

Definition at line 81 of file jockey.h.

Definition at line 99 of file jockey.h.

Service name, access via "~dissimilarity_server_name".

Definition at line 91 of file jockey.h.

Client to laser scan getter for LaMa.

Definition at line 94 of file jockey.h.

Client to laser scan setter for LaMa.

Definition at line 95 of file jockey.h.

std::string lj_laser::Jockey::laser_interface_name_ [protected]

Interface name in the database, access via "~laser_interface_name".

Definition at line 89 of file jockey.h.

Definition at line 84 of file jockey.h.

sensor_msgs::LaserScan lj_laser::Jockey::scan_ [protected]

Last received laser scan.

Definition at line 86 of file jockey.h.

Time of reception of last received laser scan.

Definition at line 85 of file jockey.h.


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


lj_laser
Author(s): Gaƫl Ecorchard
autogenerated on Thu Jun 6 2019 17:50:44