#include <image_processor.h>
Public Member Functions | |
ImageProcessor () | |
the last Image message received | |
void | publishProcessedImg () |
~ImageProcessor () | |
Destructor. | |
Public Attributes | |
bool | pose_publishing |
bool | video_publishing |
true after receiving the first pose3D message from pose_estimation | |
Private Member Functions | |
void | endResetPoseCb (const std_msgs::Empty &msg) |
Callback when the pose reset end is received. | |
void | imageCb (const sensor_msgs::Image::ConstPtr &msg) |
Callback when image is received. | |
void | navdataCb (const ardrone_autonomy::Navdata::ConstPtr navdataPtr) |
Callback when a naavdata is received. | |
void | poseCb (const ucl_drone::Pose3D::ConstPtr &posePtr) |
Callback when pose is received. | |
void | resetPoseCb (const std_msgs::Empty &msg) |
Callback when a pose reset begining is received. | |
Private Attributes | |
std::string | end_reset_pose_channel |
ros::Subscriber | end_reset_pose_sub |
image_transport::Subscriber | image_sub_ |
image_transport::ImageTransport | it_ |
sensor_msgs::Image::ConstPtr | lastImageReceived |
the last Navdata message received | |
ardrone_autonomy::Navdata | lastNavdataReceived |
the last Pose3D message received | |
ucl_drone::Pose3D::ConstPtr | lastPoseReceived |
ros::NodeHandle | nh_ |
bool | pending_reset |
true during a reset | |
std::string | pose_channel |
ros::Subscriber | pose_sub |
ProcessedImage * | prev_cam_img |
the last image processed | |
std::string | processed_image_channel_out |
ros::Publisher | processed_image_pub |
std::string | reset_pose_channel |
ros::Subscriber | reset_pose_sub |
Target | target |
the target to detect (this object wraps all needed procedures) | |
bool | target_loaded |
true if the target is successfully loaded | |
bool | use_OpticalFlowPyrLK |
launch parameter: if true, processed_image has to use OpticalFlowPyrLK | |
std::string | video_channel_ |
Definition at line 20 of file image_processor.h.
Destructor.
Definition at line 128 of file computer_vision.cpp.
void ImageProcessor::endResetPoseCb | ( | const std_msgs::Empty & | msg | ) | [private] |
Callback when the pose reset end is received.
Definition at line 142 of file computer_vision.cpp.
void ImageProcessor::imageCb | ( | const sensor_msgs::Image::ConstPtr & | msg | ) | [private] |
Callback when image is received.
Definition at line 148 of file computer_vision.cpp.
void ImageProcessor::navdataCb | ( | const ardrone_autonomy::Navdata::ConstPtr | navdataPtr | ) | [private] |
Callback when a naavdata is received.
void ImageProcessor::poseCb | ( | const ucl_drone::Pose3D::ConstPtr & | posePtr | ) | [private] |
Callback when pose is received.
Definition at line 158 of file computer_vision.cpp.
void ImageProcessor::publishProcessedImg | ( | ) |
Definition at line 168 of file computer_vision.cpp.
void ImageProcessor::resetPoseCb | ( | const std_msgs::Empty & | msg | ) | [private] |
Callback when a pose reset begining is received.
Definition at line 136 of file computer_vision.cpp.
std::string ImageProcessor::end_reset_pose_channel [private] |
Definition at line 34 of file image_processor.h.
Definition at line 33 of file image_processor.h.
Definition at line 27 of file image_processor.h.
Definition at line 26 of file image_processor.h.
sensor_msgs::Image::ConstPtr ImageProcessor::lastImageReceived [private] |
the last Navdata message received
Definition at line 72 of file image_processor.h.
ardrone_autonomy::Navdata ImageProcessor::lastNavdataReceived [private] |
the last Pose3D message received
Definition at line 71 of file image_processor.h.
ucl_drone::Pose3D::ConstPtr ImageProcessor::lastPoseReceived [private] |
Definition at line 70 of file image_processor.h.
ros::NodeHandle ImageProcessor::nh_ [private] |
Definition at line 23 of file image_processor.h.
bool ImageProcessor::pending_reset [private] |
true during a reset
Definition at line 50 of file image_processor.h.
std::string ImageProcessor::pose_channel [private] |
Definition at line 30 of file image_processor.h.
function to build and send messages with all computed keypoints and target detected
Definition at line 84 of file image_processor.h.
ros::Subscriber ImageProcessor::pose_sub [private] |
Definition at line 29 of file image_processor.h.
ProcessedImage* ImageProcessor::prev_cam_img [private] |
the last image processed
Definition at line 41 of file image_processor.h.
std::string ImageProcessor::processed_image_channel_out [private] |
Definition at line 38 of file image_processor.h.
Definition at line 37 of file image_processor.h.
std::string ImageProcessor::reset_pose_channel [private] |
Definition at line 32 of file image_processor.h.
Definition at line 31 of file image_processor.h.
Target ImageProcessor::target [private] |
the target to detect (this object wraps all needed procedures)
Definition at line 53 of file image_processor.h.
bool ImageProcessor::target_loaded [private] |
true if the target is successfully loaded
Definition at line 47 of file image_processor.h.
bool ImageProcessor::use_OpticalFlowPyrLK [private] |
launch parameter: if true, processed_image has to use OpticalFlowPyrLK
Definition at line 44 of file image_processor.h.
std::string ImageProcessor::video_channel_ [private] |
Definition at line 28 of file image_processor.h.
true after receiving the first pose3D message from pose_estimation
Definition at line 85 of file image_processor.h.