#include <ajockey.h>
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< PotentialLandmark > | landmarks_ |
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) |
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.
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] |
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] |
bool featurenav_base::AJockey::has_odom_ [private] |
bool featurenav_base::AJockey::image_processing_running_ [private] |
std::vector<PotentialLandmark> featurenav_base::AJockey::landmarks_ [private] |
double featurenav_base::AJockey::matcher_max_relative_distance_ [private] |
const ros::Duration featurenav_base::AJockey::max_landmark_age_ = ros::Duration(2.0) [static, private] |
const ros::Duration featurenav_base::AJockey::max_odom_age_ = ros::Duration(0.5) [static, private] |
double featurenav_base::AJockey::max_segment_length_ [private] |
double featurenav_base::AJockey::min_landmark_dist_ [private] |
nav_msgs::Odometry featurenav_base::AJockey::odom_ [private] |
Segment featurenav_base::AJockey::segment_ [private] |
std::string featurenav_base::AJockey::segment_interface_name_ [private] |
std::string featurenav_base::AJockey::segment_setter_name_ [private] |