#include <map_keyframe_based.h>
Public Member Functions | |
void | getDescriptors (const ucl_drone::Pose3D &pose, cv::Mat &descriptors, std::vector< int > &idx, bool only_visible=true) |
old implementation of searches in the map, do not use keyframe, not used anymore | |
void | getDescriptors (const std::vector< int > &idx, cv::Mat &descriptors) |
old implementation of searches in the map, do not use keyframe, not used anymore | |
void | getVisibleKeyFrames (const ucl_drone::Pose3D &pose, std::vector< std::vector< int > > &keyframes_ID) |
void | getVisiblePoints (const ucl_drone::Pose3D &pose, std::vector< int > &idx) |
Map () | |
Contructor. Initialize an empty map. | |
void | publishPoseVisual (ucl_drone::Pose3D poseFrame, ucl_drone::Pose3D posePnP) |
void | targetDetectedPublisher () |
better if in the future, PnP is used, for the moment, detection with 2D hypothesis. | |
~Map () | |
Destructor. | |
Public Attributes | |
pcl::PointCloud < pcl::PointXYZRGBSIFT >::Ptr | cloud |
The cloud object containing 3D points. | |
bool | pending_reset |
true during a reset | |
boost::shared_ptr < pcl::visualization::PCLVisualizer > | visualizer |
The visualizer object to perform projection. | |
Private Member Functions | |
bool | closestKeyFrame (const ucl_drone::Pose3D &pose, int &keyframe_ID, Frame current_frame) |
bool | doPnP (Frame current_frame, ucl_drone::Pose3D &PnP_pose, std::vector< int > &inliers, KeyFrame *ref_keyframe) |
void | endResetPoseCb (const std_msgs::Empty &msg) |
Callback. | |
void | init_planes () |
bool | newKeyFrameNeeded (int number_of_common_keypoints) |
bool | newKeyFrameNeeded (int number_of_common_keypoints, KeyFrame *reference_keyframe_candidate) |
void | processedImageCb (const ucl_drone::ProcessedImageMsg::ConstPtr processed_image_in) |
Callback when image is received. | |
void | resetPoseCb (const std_msgs::Empty &msg) |
Callback. | |
Private Attributes | |
cv::Mat | cam_plane_bottom |
cv::Mat | cam_plane_left |
cv::Mat | cam_plane_right |
cv::Mat | cam_plane_top |
cv::Mat | camera_matrix_K |
bool | do_search |
parameter: if true the previous keyframe are used to perform searches | |
std::string | end_reset_pose_channel |
ros::Subscriber | end_reset_pose_sub |
EndPoseReset subscriber. | |
ucl_drone::ProcessedImageMsg::ConstPtr | lastProcessedImgReceived |
s last message received | |
ros::NodeHandle | nh |
ucl_drone::Pose3D | PnP_pose |
last visual pose estimation | |
std::string | pose_correction_channel |
ros::Publisher | pose_correction_pub |
std::string | pose_PnP_channel |
ros::Publisher | pose_PnP_pub |
visual pose estimation publisher | |
Frame | previous_frame |
Frame built with the previous ImageProcessed message. | |
std::string | processed_image_channel_in |
ros::Subscriber | processed_image_sub |
ProcessedImage subscriber. | |
bool | processedImgReceived |
true after receiving the first ProcessedImage message | |
KeyFrame * | reference_keyframe |
The reference KeyFrame is the last matching keyframe. | |
std::string | reset_pose_channel |
ros::Subscriber | reset_pose_sub |
PoseReset subscriber. | |
cv::Mat | rvec |
last rotational vector (PnP estimation) | |
bool | stop_if_lost |
parameter: if true the mapping stops when tracking_lost is true | |
std::string | target_channel_out |
ros::Publisher | target_pub |
target publisher | |
int | threshold_lost |
int | threshold_new_keyframe |
double | threshold_new_keyframe_percentage |
bool | tracking_lost |
cv::Mat | tvec |
last translation vector (PnP estimation) |
This object wraps functions to execute the mapping node
Definition at line 68 of file map_keyframe_based.h.
Map::Map | ( | ) |
Contructor. Initialize an empty map.
Definition at line 12 of file map_keyframe_based.cpp.
Map::~Map | ( | ) |
Destructor.
Definition at line 91 of file map_keyframe_based.cpp.
bool Map::closestKeyFrame | ( | const ucl_drone::Pose3D & | pose, |
int & | keyframe_ID, | ||
Frame | current_frame | ||
) | [private] |
This method searches among previously mapped KeyFrame the closest one with the given Frame
[in] | pose | The estimated pose |
[out] | keyframe_ID | The identification number of the closest KeyFrame |
[in] | current_frame | The frame object |
Definition at line 422 of file map_keyframe_based.cpp.
bool Map::doPnP | ( | Frame | current_frame, |
ucl_drone::Pose3D & | PnP_pose, | ||
std::vector< int > & | inliers, | ||
KeyFrame * | ref_keyframe | ||
) | [private] |
This method computes the PnP estimation
[in] | current_frame | The frame containing keypoint of the last camera observation |
[out] | PnP_pose | The visual pose estimation |
[out] | inliers | The indexes of keypoints with a correct matching |
[in] | ref_keyframe | The KeyFrame used to perform the estimation |
Definition at line 265 of file map_keyframe_based.cpp.
void Map::endResetPoseCb | ( | const std_msgs::Empty & | msg | ) | [private] |
Callback.
Definition at line 111 of file map_keyframe_based.cpp.
void Map::getDescriptors | ( | const ucl_drone::Pose3D & | pose, |
cv::Mat & | descriptors, | ||
std::vector< int > & | idx, | ||
bool | only_visible = true |
||
) |
old implementation of searches in the map, do not use keyframe, not used anymore
Definition at line 565 of file map_keyframe_based.cpp.
void Map::getDescriptors | ( | const std::vector< int > & | idx, |
cv::Mat & | descriptors | ||
) |
old implementation of searches in the map, do not use keyframe, not used anymore
Definition at line 594 of file map_keyframe_based.cpp.
void Map::getVisibleKeyFrames | ( | const ucl_drone::Pose3D & | pose, |
std::vector< std::vector< int > > & | keyframes_ID | ||
) |
This method searches all keyframes containing keypoints visible frome the pose given
[in] | pose | The pose of the drone |
[out] | keyframes_ID | Identification number of all keyframes in the map visible from the given pose |
Definition at line 487 of file map_keyframe_based.cpp.
void Map::getVisiblePoints | ( | const ucl_drone::Pose3D & | pose, |
std::vector< int > & | idx | ||
) |
This method searches all keypoints visible frome the pose given
[in] | pose | The pose of the drone |
[out] | idx | Indexes of all keypoints in the map visible from the given pose |
Definition at line 522 of file map_keyframe_based.cpp.
void Map::init_planes | ( | ) | [private] |
This method initializes planes defining the visible area from the camera (according to camera parameters)
Definition at line 395 of file map_keyframe_based.cpp.
bool Map::newKeyFrameNeeded | ( | int | number_of_common_keypoints | ) | [private] |
bool Map::newKeyFrameNeeded | ( | int | number_of_common_keypoints, |
KeyFrame * | reference_keyframe_candidate | ||
) | [private] |
Definition at line 611 of file map_keyframe_based.cpp.
void Map::processedImageCb | ( | const ucl_drone::ProcessedImageMsg::ConstPtr | processed_image_in | ) | [private] |
Callback when image is received.
IF THE MAP IS NOT EMPTY
IF THE MAP IS EMPTY
Definition at line 116 of file map_keyframe_based.cpp.
void Map::publishPoseVisual | ( | ucl_drone::Pose3D | poseFrame, |
ucl_drone::Pose3D | posePnP | ||
) |
This method publishes a message containing the visual pose estimation
[in] | poseFrame | Pose published by sensors when the camera picture was received |
[in] | poseFrame | Pose estimated with visual information and the contents of the map |
Definition at line 251 of file map_keyframe_based.cpp.
void Map::resetPoseCb | ( | const std_msgs::Empty & | msg | ) | [private] |
Callback.
Definition at line 95 of file map_keyframe_based.cpp.
void Map::targetDetectedPublisher | ( | ) |
better if in the future, PnP is used, for the moment, detection with 2D hypothesis.
TODO: for the moment, detection with 2D hypothesis. In the future, use PnP.
This method publishes a message if the last ImageProcessed contains information about the target detection and add the estimated pose of the detected target in world coordinates
Definition at line 369 of file map_keyframe_based.cpp.
cv::Mat Map::cam_plane_bottom [private] |
Definition at line 138 of file map_keyframe_based.h.
cv::Mat Map::cam_plane_left [private] |
Definition at line 139 of file map_keyframe_based.h.
cv::Mat Map::cam_plane_right [private] |
Definition at line 140 of file map_keyframe_based.h.
cv::Mat Map::cam_plane_top [private] |
Definition at line 137 of file map_keyframe_based.h.
cv::Mat Map::camera_matrix_K [private] |
Definition at line 129 of file map_keyframe_based.h.
pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr Map::cloud |
The cloud object containing 3D points.
Definition at line 163 of file map_keyframe_based.h.
bool Map::do_search [private] |
parameter: if true the previous keyframe are used to perform searches
Definition at line 79 of file map_keyframe_based.h.
std::string Map::end_reset_pose_channel [private] |
Definition at line 88 of file map_keyframe_based.h.
ros::Subscriber Map::end_reset_pose_sub [private] |
EndPoseReset subscriber.
Definition at line 87 of file map_keyframe_based.h.
ucl_drone::ProcessedImageMsg::ConstPtr Map::lastProcessedImgReceived [private] |
s last message received
Definition at line 125 of file map_keyframe_based.h.
ros::NodeHandle Map::nh [private] |
Definition at line 73 of file map_keyframe_based.h.
bool Map::pending_reset |
true during a reset
Definition at line 160 of file map_keyframe_based.h.
ucl_drone::Pose3D Map::PnP_pose [private] |
last visual pose estimation
Definition at line 76 of file map_keyframe_based.h.
std::string Map::pose_correction_channel [private] |
Definition at line 95 of file map_keyframe_based.h.
ros::Publisher Map::pose_correction_pub [private] |
correction between sensors and visual estimation publisher
Definition at line 93 of file map_keyframe_based.h.
std::string Map::pose_PnP_channel [private] |
Definition at line 92 of file map_keyframe_based.h.
ros::Publisher Map::pose_PnP_pub [private] |
visual pose estimation publisher
Definition at line 91 of file map_keyframe_based.h.
Frame Map::previous_frame [private] |
Frame built with the previous ImageProcessed message.
Definition at line 134 of file map_keyframe_based.h.
std::string Map::processed_image_channel_in [private] |
Definition at line 84 of file map_keyframe_based.h.
ros::Subscriber Map::processed_image_sub [private] |
ProcessedImage subscriber.
Definition at line 83 of file map_keyframe_based.h.
bool Map::processedImgReceived [private] |
true after receiving the first ProcessedImage message
Definition at line 75 of file map_keyframe_based.h.
KeyFrame* Map::reference_keyframe [private] |
The reference KeyFrame is the last matching keyframe.
Definition at line 135 of file map_keyframe_based.h.
std::string Map::reset_pose_channel [private] |
Definition at line 86 of file map_keyframe_based.h.
ros::Subscriber Map::reset_pose_sub [private] |
PoseReset subscriber.
Definition at line 85 of file map_keyframe_based.h.
cv::Mat Map::rvec [private] |
last rotational vector (PnP estimation)
Definition at line 132 of file map_keyframe_based.h.
bool Map::stop_if_lost [private] |
parameter: if true the mapping stops when tracking_lost is true
Definition at line 80 of file map_keyframe_based.h.
std::string Map::target_channel_out [private] |
Definition at line 97 of file map_keyframe_based.h.
ros::Publisher Map::target_pub [private] |
target publisher
Definition at line 96 of file map_keyframe_based.h.
int Map::threshold_lost [private] |
min number of matching keypoints in the keyframe to compute pose estimation
Definition at line 100 of file map_keyframe_based.h.
int Map::threshold_new_keyframe [private] |
min number of matching keypoints with the keyframe to build a new keyframe
Definition at line 102 of file map_keyframe_based.h.
double Map::threshold_new_keyframe_percentage [private] |
percentage of matching keypoints with the keyframe to build a new keyframe
Definition at line 104 of file map_keyframe_based.h.
bool Map::tracking_lost [private] |
true if the last visual information does not permit to estimate the drone pose
Definition at line 77 of file map_keyframe_based.h.
cv::Mat Map::tvec [private] |
last translation vector (PnP estimation)
Definition at line 131 of file map_keyframe_based.h.
boost::shared_ptr< pcl::visualization::PCLVisualizer > Map::visualizer |
The visualizer object to perform projection.
Definition at line 166 of file map_keyframe_based.h.