#include <njockey.h>

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). | |
| 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.
| 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] |
| 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.
| bool featurenav_base::NJockey::retrieveSegment | ( | ) | [private] |
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.
| 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.
double featurenav_base::NJockey::forward_velocity_ [private] |
bool featurenav_base::NJockey::has_odom_ [private] |
const int featurenav_base::NJockey::histogram_bin_size_ = 20 [static, private] |
bool featurenav_base::NJockey::image_processing_running_ [private] |
double featurenav_base::NJockey::kp_ [private] |
double featurenav_base::NJockey::matcher_max_relative_distance_ [private] |
double featurenav_base::NJockey::max_angular_velocity_ [private] |
const ros::Duration featurenav_base::NJockey::max_odom_age_ = ros::Duration(0.5) [static, private] |
double featurenav_base::NJockey::min_angular_velocity_ [private] |
nav_msgs::Odometry featurenav_base::NJockey::odom_ [private] |
const double featurenav_base::NJockey::reach_angular_distance_ = 0.001 [static, private] |
::featurenav_base::Segment featurenav_base::NJockey::segment_ [private] |
std::string featurenav_base::NJockey::segment_getter_name_ [private] |
std::string featurenav_base::NJockey::segment_interface_name_ [private] |
bool featurenav_base::NJockey::start_angle_reached_ [private] |