Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes
featurenav_base::AJockey Class Reference

#include <ajockey.h>

Inheritance diagram for featurenav_base::AJockey:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 AJockey (const std::string &name, const std::string &segment_interface_name, const std::string &segment_setter_name)
void setDescriptorMatcherFunction (descriptor_matcher_function_ptr f)
void setExtractFeaturesFunction (feature_extractor_function_ptr f)

Public Attributes

can_do_function_ptr canDo
start_do_function_ptr startDo

Private Member Functions

void callback_image (const sensor_msgs::ImageConstPtr &msg)
void callback_odom (const nav_msgs::OdometryConstPtr &msg)
double distance_from_start ()
virtual void onContinue ()
virtual void onInterrupt ()
virtual void onLearn ()
virtual void onStop ()
size_t processImage (const sensor_msgs::ImageConstPtr &image)
void reset ()
lama_msgs::DescriptorLink segmentDescriptorLink (const int32_t id)

Private Attributes

feature_extractor_function_ptr extract_features_
bool has_odom_
image_transport::Subscriber image_handler_
bool image_processing_running_
 true when treating an image.
image_transport::ImageTransport it_
std::vector< PotentialLandmarklandmarks_
 Potential landmarks (features seen once).
descriptor_matcher_function_ptr match_descriptors_
double matcher_max_relative_distance_
double max_segment_length_
double min_landmark_dist_
 A landmark is saved if it was visible on at least such a traveled distance.
nav_msgs::Odometry odom_
 Last received odometry message.
ros::Subscriber odom_handler_
Segment segment_
std::string segment_interface_name_
 Name of the map interface for segments.
std::string segment_setter_name_
 Name of the service to write segments into the map.
ros::ServiceClient segment_setter_proxy_
geometry_msgs::Pose start_pose_
 Pose when learning started.

Static Private Attributes

static const ros::Duration max_landmark_age_ = ros::Duration(2.0)
static const ros::Duration max_odom_age_ = ros::Duration(0.5)

Detailed Description

Definition at line 77 of file ajockey.h.


Constructor & Destructor Documentation

featurenav_base::AJockey::AJockey ( const std::string &  name,
const std::string &  segment_interface_name,
const std::string &  segment_setter_name 
)

Definition at line 9 of file ajockey.cpp.


Member Function Documentation

void featurenav_base::AJockey::callback_image ( const sensor_msgs::ImageConstPtr &  msg) [private]

Definition at line 195 of file ajockey.cpp.

void featurenav_base::AJockey::callback_odom ( const nav_msgs::OdometryConstPtr &  msg) [private]

Definition at line 215 of file ajockey.cpp.

double featurenav_base::AJockey::distance_from_start ( ) [inline, private]

Return the distance since we started learning.

Definition at line 101 of file ajockey.h.

void featurenav_base::AJockey::onContinue ( ) [private, virtual]

Reimplemented from lama_jockeys::LearningJockey.

Definition at line 191 of file ajockey.cpp.

void featurenav_base::AJockey::onInterrupt ( ) [private, virtual]

Reimplemented from lama_jockeys::LearningJockey.

Definition at line 185 of file ajockey.cpp.

void featurenav_base::AJockey::onLearn ( ) [private, virtual]

Implements lama_jockeys::LearningJockey.

Definition at line 44 of file ajockey.cpp.

void featurenav_base::AJockey::onStop ( ) [private, virtual]

Implements lama_jockeys::LearningJockey.

Definition at line 126 of file ajockey.cpp.

size_t featurenav_base::AJockey::processImage ( const sensor_msgs::ImageConstPtr &  image) [private]

Process an image and return the number of tracked features.

Return the number of potential features.

image[in] ROS image message. d[in] distance from the segment start in meters.

Definition at line 233 of file ajockey.cpp.

void featurenav_base::AJockey::reset ( ) [private]

Definition at line 35 of file ajockey.cpp.

lama_msgs::DescriptorLink featurenav_base::AJockey::segmentDescriptorLink ( const int32_t  id) [inline, private]

Return a DescriptorLink with the given id

Definition at line 114 of file ajockey.h.

Definition at line 84 of file ajockey.h.

Definition at line 83 of file ajockey.h.


Member Data Documentation

Definition at line 86 of file ajockey.h.

Definition at line 148 of file ajockey.h.

Definition at line 151 of file ajockey.h.

Definition at line 127 of file ajockey.h.

true when treating an image.

Definition at line 152 of file ajockey.h.

Definition at line 126 of file ajockey.h.

Potential landmarks (features seen once).

Definition at line 155 of file ajockey.h.

Definition at line 149 of file ajockey.h.

A potential descriptor is visible in the new image if the distance to the best-match descriptor is smaller than the distance to the second best match multiplied by this factor.

Definition at line 134 of file ajockey.h.

Definition at line 143 of file ajockey.h.

Definition at line 142 of file ajockey.h.

The jockey will successfully end the action if the traveled distance is at least this. Defaults to 0, which means that the START action never finishes.

Definition at line 138 of file ajockey.h.

A landmark is saved if it was visible on at least such a traveled distance.

Definition at line 137 of file ajockey.h.

nav_msgs::Odometry featurenav_base::AJockey::odom_ [private]

Last received odometry message.

Definition at line 150 of file ajockey.h.

Definition at line 128 of file ajockey.h.

Definition at line 154 of file ajockey.h.

Name of the map interface for segments.

Definition at line 146 of file ajockey.h.

Name of the service to write segments into the map.

Definition at line 147 of file ajockey.h.

Definition at line 131 of file ajockey.h.

Pose when learning started.

Definition at line 153 of file ajockey.h.

Definition at line 87 of file ajockey.h.


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


featurenav_base
Author(s): Gaƫl Ecorchard
autogenerated on Sat Jun 8 2019 19:52:22