Public Member Functions | Private Member Functions | Private Attributes
lj_costmap::Jockey Class Reference

#include <jockey.h>

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

List of all members.

Public Member Functions

 Jockey (std::string name, double frontier_width, double max_frontier_angle=0.785)
virtual void onGetDissimilarity ()
virtual void onGetVertexDescriptor ()
virtual void onLocalizeInVertex ()
void setDissimilarityServerName (std::string name)

Private Member Functions

lama_msgs::DescriptorLink crossingDescriptorLink (int32_t id)
void getLiveData ()
void handleMap (const nav_msgs::OccupancyGridConstPtr &msg)
void initMapCrossingInterface ()
void initMapPlaceProfileInterface ()
lama_msgs::DescriptorLink placeProfileDescriptorLink (int32_t id)

Private Attributes

crossing_detector::CostmapCrossingDetector crossing_detector_
std::string crossing_interface_name_
ros::ServiceClient crossing_setter_
bool data_received_
std::string dissimilarity_server_name_
std::string localize_service_
nav_msgs::OccupancyGrid map_
ros::ServiceClient place_profile_getter_
std::string place_profile_interface_name_
ros::ServiceClient place_profile_setter_
lama_msgs::PlaceProfile profile_
double range_cutoff_
 A range longer that this is considered to be free (m).
bool range_cutoff_set_

Detailed Description

Definition at line 64 of file jockey.h.


Constructor & Destructor Documentation

lj_costmap::Jockey::Jockey ( std::string  name,
double  frontier_width,
double  max_frontier_angle = 0.785 
)

Definition at line 6 of file jockey.cpp.


Member Function Documentation

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

Return a DescriptorLink for the Crossing interface

Definition at line 326 of file jockey.cpp.

void lj_costmap::Jockey::getLiveData ( ) [private]

Start the subscriber, wait for an OccupancyGrid and exit upon reception.

Definition at line 74 of file jockey.cpp.

void lj_costmap::Jockey::handleMap ( const nav_msgs::OccupancyGridConstPtr &  msg) [private]

Callback for OccupancyGrid subscriber, receive a message and store it.

Definition at line 99 of file jockey.cpp.

Create the setter services for Crossing descriptors.

Definition at line 52 of file jockey.cpp.

Create the getter and setter services for PlaceProfile descriptors.

Definition at line 28 of file jockey.cpp.

Reimplemented from lama_jockeys::LocalizingJockey.

Definition at line 223 of file jockey.cpp.

Return the vertex descriptors associated with the current robot position through result_.

The descriptors are a LaserScan and a Crossing.

Reimplemented from lama_jockeys::LocalizingJockey.

Definition at line 113 of file jockey.cpp.

Return the transformation between the current and requested PlaceProfiles.

Reimplemented from lama_jockeys::LocalizingJockey.

Definition at line 165 of file jockey.cpp.

lama_msgs::DescriptorLink lj_costmap::Jockey::placeProfileDescriptorLink ( int32_t  id) [private]

Return a DescriptorLink for the PlaceProfile interface

Definition at line 316 of file jockey.cpp.

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

Definition at line 74 of file jockey.h.


Member Data Documentation

Definition at line 109 of file jockey.h.

Definition at line 101 of file jockey.h.

Definition at line 102 of file jockey.h.

Definition at line 90 of file jockey.h.

Definition at line 107 of file jockey.h.

Definition at line 105 of file jockey.h.

nav_msgs::OccupancyGrid lj_costmap::Jockey::map_ [private]

Definition at line 94 of file jockey.h.

Definition at line 99 of file jockey.h.

Definition at line 98 of file jockey.h.

Definition at line 100 of file jockey.h.

lama_msgs::PlaceProfile lj_costmap::Jockey::profile_ [private]

Definition at line 95 of file jockey.h.

A range longer that this is considered to be free (m).

Definition at line 87 of file jockey.h.

Definition at line 91 of file jockey.h.


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


lj_costmap
Author(s): Gaƫl Ecorchard
autogenerated on Sat Jun 8 2019 20:58:41