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

#include <njockey.h>

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

List of all members.

Public Member Functions

 NJockey (const std::string &name, const std::string &segment_interface_name, const std::string &segment_getter_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)
vector< double > compute_horizontal_differences (const vector< Landmark > &landmarks, const vector< cv::KeyPoint > &keypoints, const vector< Feature > &descriptors, const double d)
double distance_from_start ()
virtual void onContinue ()
virtual void onInterrupt ()
virtual void onStop ()
virtual void onTraverse ()
size_t processImage (const sensor_msgs::ImageConstPtr &image, double &w)
void reset ()
bool retrieveSegment ()
double saturate (double w) const
vector< Landmark > select_tracked_landmarks (const double d) const
geometry_msgs::Twist turnToAngle (const double direction)

Private Attributes

feature_extractor_function_ptr extract_features_
double forward_velocity_
 Linear velocity (m/s).
bool has_odom_
 true after an Odometry message was received.
image_transport::Subscriber image_handler_
bool image_processing_running_
 true when treating an image.
image_transport::ImageTransport it_
double kp_
descriptor_matcher_function_ptr match_descriptors_
double matcher_max_relative_distance_
 > Proportional factor for the angular velocity (s^-1).
double max_angular_velocity_
 Max. angular velocity (rad/s).
double min_angular_velocity_
 Min. angular velocity for dead-zone management (rad/s).
nav_msgs::Odometry odom_
 Last received odometry message.
ros::Subscriber odom_handler_
::featurenav_base::Segment segment_
 Segment we will traverse.
std::string segment_getter_name_
 Name of the service to write segments into the map.
ros::ServiceClient segment_getter_proxy_
std::string segment_interface_name_
 Name of the map interface for segments.
bool start_angle_reached_
 true after the initial rotation.
geometry_msgs::Pose start_pose_
 Pose when learning started.
ros::Publisher twist_publisher_

Static Private Attributes

static const int histogram_bin_size_ = 20
 Histogram bin size in pixels.
static const ros::Duration max_odom_age_ = ros::Duration(0.5)
static const double reach_angular_distance_ = 0.001
 dtheta to reach when turning (rad).

Detailed Description

Definition at line 37 of file njockey.h.


Constructor & Destructor Documentation

featurenav_base::NJockey::NJockey ( const std::string &  name,
const std::string &  segment_interface_name,
const std::string &  segment_getter_name 
)

Definition at line 10 of file njockey.cpp.


Member Function Documentation

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

Definition at line 218 of file njockey.cpp.

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

Definition at line 207 of file njockey.cpp.

vector< double > featurenav_base::NJockey::compute_horizontal_differences ( const vector< Landmark > &  landmarks,
const vector< cv::KeyPoint > &  keypoints,
const vector< Feature > &  descriptors,
const double  d 
) [private]

Definition at line 386 of file njockey.cpp.

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

Return the distance since we started learning.

Definition at line 71 of file njockey.h.

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

Reimplemented from lama_jockeys::NavigatingJockey.

Definition at line 201 of file njockey.cpp.

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

Reimplemented from lama_jockeys::NavigatingJockey.

Definition at line 195 of file njockey.cpp.

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

Implements lama_jockeys::NavigatingJockey.

Definition at line 184 of file njockey.cpp.

void featurenav_base::NJockey::onTraverse ( ) [private, virtual]

Implements lama_jockeys::NavigatingJockey.

Definition at line 84 of file njockey.cpp.

size_t featurenav_base::NJockey::processImage ( const sensor_msgs::ImageConstPtr &  image,
double &  dtheta 
) [private]

Return the number of matched landmarks and the angular deviation to the learned path

Definition at line 299 of file njockey.cpp.

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

Definition at line 43 of file njockey.cpp.

Definition at line 50 of file njockey.cpp.

double featurenav_base::NJockey::saturate ( double  w) const [private]

Definition at line 268 of file njockey.cpp.

vector< Landmark > featurenav_base::NJockey::select_tracked_landmarks ( const double  d) const [private]

Definition at line 373 of file njockey.cpp.

Definition at line 44 of file njockey.h.

Definition at line 43 of file njockey.h.

geometry_msgs::Twist featurenav_base::NJockey::turnToAngle ( const double  direction) [private]

GoToGoal behavior for pure rotation

direction[in] direction the robot should have at the end (in odometry_ frame). twist[out] set velocity.

Definition at line 251 of file njockey.cpp.


Member Data Documentation

Definition at line 46 of file njockey.h.

Definition at line 108 of file njockey.h.

Linear velocity (m/s).

Definition at line 92 of file njockey.h.

true after an Odometry message was received.

Definition at line 111 of file njockey.h.

const int featurenav_base::NJockey::histogram_bin_size_ = 20 [static, private]

Histogram bin size in pixels.

Definition at line 102 of file njockey.h.

Definition at line 84 of file njockey.h.

true when treating an image.

Definition at line 113 of file njockey.h.

Definition at line 83 of file njockey.h.

Definition at line 93 of file njockey.h.

Definition at line 109 of file njockey.h.

> Proportional factor for the angular velocity (s^-1).

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 94 of file njockey.h.

Max. angular velocity (rad/s).

Definition at line 97 of file njockey.h.

Definition at line 101 of file njockey.h.

Min. angular velocity for dead-zone management (rad/s).

Definition at line 98 of file njockey.h.

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

Last received odometry message.

Definition at line 110 of file njockey.h.

Definition at line 85 of file njockey.h.

const double featurenav_base::NJockey::reach_angular_distance_ = 0.001 [static, private]

dtheta to reach when turning (rad).

Definition at line 103 of file njockey.h.

::featurenav_base::Segment featurenav_base::NJockey::segment_ [private]

Segment we will traverse.

Definition at line 115 of file njockey.h.

Name of the service to write segments into the map.

Definition at line 107 of file njockey.h.

Definition at line 89 of file njockey.h.

Name of the map interface for segments.

Definition at line 106 of file njockey.h.

true after the initial rotation.

Definition at line 112 of file njockey.h.

Pose when learning started.

Definition at line 114 of file njockey.h.

Definition at line 47 of file njockey.h.

Definition at line 86 of file njockey.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