#include <image_view2.h>
Public Types | |
enum | KEY_MODE { MODE_RECTANGLE, MODE_SERIES, MODE_SELECT_FORE_AND_BACK, MODE_SELECT_FORE_AND_BACK_RECT } |
Public Member Functions | |
void | addPoint (int x, int y) |
void | addRegionPoint (int x, int y) |
void | clearPointArray () |
void | drawImage () |
KEY_MODE | getMode () |
void | imageCb (const sensor_msgs::ImageConstPtr &msg) |
ImageView2 () | |
ImageView2 (ros::NodeHandle &nh) | |
void | infoCb (const sensor_msgs::CameraInfoConstPtr &msg) |
bool | isValidMovement (const cv::Point2f &start_point, const cv::Point2f &end_point) |
void | markerCb (const image_view2::ImageMarker2ConstPtr &marker) |
void | pressKey (int key) |
void | publishForegroundBackgroundMask () |
void | publishPointArray () |
void | redraw () |
void | setMode (KEY_MODE mode) |
void | setRegionWindowPoint (int x, int y) |
void | showImage () |
bool | toggleSelection () |
void | updateRegionWindowSize (int x, int y) |
~ImageView2 () | |
Static Public Member Functions | |
static void | mouseCb (int event, int x, int y, int flags, void *param) |
Public Attributes | |
bool | use_window |
Private Member Functions | |
void | checkMousePos (int &x, int &y) |
void | drawCircle (const image_view2::ImageMarker2::ConstPtr &marker) |
void | drawCircle3D (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawFrames (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawInfo (ros::Time &before_rendering) |
void | drawInteraction () |
void | drawLineList (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawLineList3D (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawLineStrip (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawLineStrip3D (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawMarkers () |
void | drawPoints (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawPoints3D (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawPolygon (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawPolygon3D (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawText (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
void | drawText3D (const image_view2::ImageMarker2::ConstPtr &marker, std::vector< CvScalar > &colors, std::vector< CvScalar >::iterator &col_it) |
bool | lookupTransformation (std::string frame_id, ros::Time &acquisition_time, std::map< std::string, int > &tf_fail, tf::StampedTransform &transform) |
void | pointArrayToMask (std::vector< cv::Point2d > &points, cv::Mat &mask) |
void | processLeftButtonDown (int x, int y) |
void | processLeftButtonUp (int x, int y) |
void | processMouseEvent (int event, int x, int y, int flags, void *param) |
void | processMove (int x, int y) |
void | publishMonoImage (ros::Publisher &pub, cv::Mat &image, const std_msgs::Header &header) |
void | publishMouseInteractionResult () |
void | resolveLocalMarkerQueue () |
Private Attributes | |
bool | autosize_ |
ros::Publisher | background_mask_pub_ |
bool | blurry_mode_ |
cv::Point2f | button_up_pos_ |
image_geometry::PinholeCameraModel | cam_model_ |
bool | continuous_ready_ |
int | count_ |
cv::Mat | draw_ |
boost::format | filename_format_ |
int | font_ |
ros::Publisher | foreground_mask_pub_ |
std::vector< std::string > | frame_ids_ |
cv::Mat | image_ |
boost::mutex | image_mutex_ |
image_transport::Publisher | image_pub_ |
image_transport::Subscriber | image_sub_ |
cv_bridge::CvImage | img_bridge_ |
sensor_msgs::CameraInfoConstPtr | info_msg_ |
boost::mutex | info_mutex_ |
ros::Subscriber | info_sub_ |
sensor_msgs::ImageConstPtr | last_msg_ |
bool | left_button_clicked_ |
V_ImageMarkerMessage | local_queue_ |
V_ImageMarkerMessage | marker_queue_ |
ros::Subscriber | marker_sub_ |
std::string | marker_topic_ |
KEY_MODE | mode_ |
ros::Publisher | move_point_pub_ |
cv::Mat | original_image_ |
std::vector< cv::Point2d > | point_array_ |
boost::mutex | point_array_mutex_ |
ros::Publisher | point_array_pub_ |
std::vector< cv::Point2d > | point_bg_array_ |
std::vector< cv::Point2d > | point_fg_array_ |
ros::Publisher | point_pub_ |
boost::mutex | queue_mutex_ |
cv::Rect | rect_bg_ |
cv::Rect | rect_fg_ |
ros::Publisher | rectangle_pub_ |
bool | region_continuous_publish_ |
double | resize_x_ |
double | resize_y_ |
bool | selecting_fg_ |
bool | show_info_ |
int | skip_draw_rate_ |
tf::TransformListener | tf_listener_ |
double | tf_timeout_ |
boost::circular_buffer< double > | times_ |
bool | window_initialized_ |
std::string | window_name_ |
CvRect | window_selection_ |
Definition at line 78 of file image_view2.h.
Definition at line 81 of file image_view2.h.
Definition at line 39 of file image_view2.cpp.
Definition at line 43 of file image_view2.cpp.
Definition at line 108 of file image_view2.cpp.
void image_view2::ImageView2::addPoint | ( | int | x, |
int | y | ||
) |
Definition at line 1004 of file image_view2.cpp.
void image_view2::ImageView2::addRegionPoint | ( | int | x, |
int | y | ||
) |
Definition at line 1043 of file image_view2.cpp.
void image_view2::ImageView2::checkMousePos | ( | int & | x, |
int & | y | ||
) | [private] |
Definition at line 1347 of file image_view2.cpp.
Definition at line 1059 of file image_view2.cpp.
void image_view2::ImageView2::drawCircle | ( | const image_view2::ImageMarker2::ConstPtr & | marker | ) | [private] |
Definition at line 161 of file image_view2.cpp.
void image_view2::ImageView2::drawCircle3D | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 649 of file image_view2.cpp.
void image_view2::ImageView2::drawFrames | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 331 of file image_view2.cpp.
void image_view2::ImageView2::drawImage | ( | ) |
Definition at line 998 of file image_view2.cpp.
void image_view2::ImageView2::drawInfo | ( | ros::Time & | before_rendering | ) | [private] |
Definition at line 893 of file image_view2.cpp.
void image_view2::ImageView2::drawInteraction | ( | ) | [private] |
Definition at line 842 of file image_view2.cpp.
void image_view2::ImageView2::drawLineList | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 224 of file image_view2.cpp.
void image_view2::ImageView2::drawLineList3D | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 481 of file image_view2.cpp.
void image_view2::ImageView2::drawLineStrip | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 188 of file image_view2.cpp.
void image_view2::ImageView2::drawLineStrip3D | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 418 of file image_view2.cpp.
void image_view2::ImageView2::drawMarkers | ( | ) | [private] |
Definition at line 739 of file image_view2.cpp.
void image_view2::ImageView2::drawPoints | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 309 of file image_view2.cpp.
void image_view2::ImageView2::drawPoints3D | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 583 of file image_view2.cpp.
void image_view2::ImageView2::drawPolygon | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 258 of file image_view2.cpp.
void image_view2::ImageView2::drawPolygon3D | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 525 of file image_view2.cpp.
void image_view2::ImageView2::drawText | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 403 of file image_view2.cpp.
void image_view2::ImageView2::drawText3D | ( | const image_view2::ImageMarker2::ConstPtr & | marker, |
std::vector< CvScalar > & | colors, | ||
std::vector< CvScalar >::iterator & | col_it | ||
) | [private] |
Definition at line 613 of file image_view2.cpp.
Definition at line 1089 of file image_view2.cpp.
void image_view2::ImageView2::imageCb | ( | const sensor_msgs::ImageConstPtr & | msg | ) |
Definition at line 958 of file image_view2.cpp.
void image_view2::ImageView2::infoCb | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) |
Definition at line 128 of file image_view2.cpp.
bool image_view2::ImageView2::isValidMovement | ( | const cv::Point2f & | start_point, |
const cv::Point2f & | end_point | ||
) |
Definition at line 1183 of file image_view2.cpp.
bool image_view2::ImageView2::lookupTransformation | ( | std::string | frame_id, |
ros::Time & | acquisition_time, | ||
std::map< std::string, int > & | tf_fail, | ||
tf::StampedTransform & | transform | ||
) | [private] |
Definition at line 134 of file image_view2.cpp.
void image_view2::ImageView2::markerCb | ( | const image_view2::ImageMarker2ConstPtr & | marker | ) |
Definition at line 115 of file image_view2.cpp.
void image_view2::ImageView2::mouseCb | ( | int | event, |
int | x, | ||
int | y, | ||
int | flags, | ||
void * | param | ||
) | [static] |
Definition at line 1295 of file image_view2.cpp.
void image_view2::ImageView2::pointArrayToMask | ( | std::vector< cv::Point2d > & | points, |
cv::Mat & | mask | ||
) | [private] |
Definition at line 1101 of file image_view2.cpp.
void image_view2::ImageView2::pressKey | ( | int | key | ) |
Definition at line 1303 of file image_view2.cpp.
void image_view2::ImageView2::processLeftButtonDown | ( | int | x, |
int | y | ||
) | [private] |
Definition at line 1190 of file image_view2.cpp.
void image_view2::ImageView2::processLeftButtonUp | ( | int | x, |
int | y | ||
) | [private] |
Definition at line 1233 of file image_view2.cpp.
void image_view2::ImageView2::processMouseEvent | ( | int | event, |
int | x, | ||
int | y, | ||
int | flags, | ||
void * | param | ||
) | [private] |
Definition at line 1260 of file image_view2.cpp.
void image_view2::ImageView2::processMove | ( | int | x, |
int | y | ||
) | [private] |
Definition at line 1203 of file image_view2.cpp.
Definition at line 1124 of file image_view2.cpp.
void image_view2::ImageView2::publishMonoImage | ( | ros::Publisher & | pub, |
cv::Mat & | image, | ||
const std_msgs::Header & | header | ||
) | [private] |
Definition at line 1115 of file image_view2.cpp.
void image_view2::ImageView2::publishMouseInteractionResult | ( | ) | [private] |
Definition at line 1143 of file image_view2.cpp.
Definition at line 1067 of file image_view2.cpp.
void image_view2::ImageView2::redraw | ( | ) |
Definition at line 928 of file image_view2.cpp.
void image_view2::ImageView2::resolveLocalMarkerQueue | ( | ) | [private] |
Definition at line 707 of file image_view2.cpp.
void image_view2::ImageView2::setMode | ( | KEY_MODE | mode | ) |
Definition at line 1084 of file image_view2.cpp.
void image_view2::ImageView2::setRegionWindowPoint | ( | int | x, |
int | y | ||
) |
Definition at line 1015 of file image_view2.cpp.
void image_view2::ImageView2::showImage | ( | ) |
Definition at line 1333 of file image_view2.cpp.
Definition at line 1094 of file image_view2.cpp.
void image_view2::ImageView2::updateRegionWindowSize | ( | int | x, |
int | y | ||
) |
Definition at line 1029 of file image_view2.cpp.
bool image_view2::ImageView2::autosize_ [private] |
Definition at line 224 of file image_view2.h.
Definition at line 222 of file image_view2.h.
bool image_view2::ImageView2::blurry_mode_ [private] |
Definition at line 211 of file image_view2.h.
cv::Point2f image_view2::ImageView2::button_up_pos_ [private] |
Definition at line 209 of file image_view2.h.
Definition at line 192 of file image_view2.h.
bool image_view2::ImageView2::continuous_ready_ [private] |
Definition at line 215 of file image_view2.h.
int image_view2::ImageView2::count_ [private] |
Definition at line 210 of file image_view2.h.
cv::Mat image_view2::ImageView2::draw_ [private] |
Definition at line 189 of file image_view2.h.
boost::format image_view2::ImageView2::filename_format_ [private] |
Definition at line 204 of file image_view2.h.
int image_view2::ImageView2::font_ [private] |
Definition at line 205 of file image_view2.h.
Definition at line 221 of file image_view2.h.
std::vector<std::string> image_view2::ImageView2::frame_ids_ [private] |
Definition at line 193 of file image_view2.h.
cv::Mat image_view2::ImageView2::image_ [private] |
Definition at line 189 of file image_view2.h.
boost::mutex image_view2::ImageView2::image_mutex_ [private] |
Definition at line 187 of file image_view2.h.
Definition at line 179 of file image_view2.h.
Definition at line 174 of file image_view2.h.
Definition at line 186 of file image_view2.h.
sensor_msgs::CameraInfoConstPtr image_view2::ImageView2::info_msg_ [private] |
Definition at line 185 of file image_view2.h.
boost::mutex image_view2::ImageView2::info_mutex_ [private] |
Definition at line 195 of file image_view2.h.
Definition at line 175 of file image_view2.h.
sensor_msgs::ImageConstPtr image_view2::ImageView2::last_msg_ [private] |
Definition at line 184 of file image_view2.h.
bool image_view2::ImageView2::left_button_clicked_ [private] |
Definition at line 216 of file image_view2.h.
Definition at line 173 of file image_view2.h.
Definition at line 181 of file image_view2.h.
Definition at line 176 of file image_view2.h.
std::string image_view2::ImageView2::marker_topic_ [private] |
Definition at line 177 of file image_view2.h.
KEY_MODE image_view2::ImageView2::mode_ [private] |
Definition at line 223 of file image_view2.h.
Definition at line 220 of file image_view2.h.
cv::Mat image_view2::ImageView2::original_image_ [private] |
Definition at line 189 of file image_view2.h.
std::vector<cv::Point2d> image_view2::ImageView2::point_array_ [private] |
Definition at line 194 of file image_view2.h.
boost::mutex image_view2::ImageView2::point_array_mutex_ [private] |
Definition at line 183 of file image_view2.h.
Definition at line 218 of file image_view2.h.
std::vector<cv::Point2d> image_view2::ImageView2::point_bg_array_ [private] |
Definition at line 199 of file image_view2.h.
std::vector<cv::Point2d> image_view2::ImageView2::point_fg_array_ [private] |
Definition at line 200 of file image_view2.h.
Definition at line 217 of file image_view2.h.
boost::mutex image_view2::ImageView2::queue_mutex_ [private] |
Definition at line 182 of file image_view2.h.
cv::Rect image_view2::ImageView2::rect_bg_ [private] |
Definition at line 201 of file image_view2.h.
cv::Rect image_view2::ImageView2::rect_fg_ [private] |
Definition at line 202 of file image_view2.h.
Definition at line 219 of file image_view2.h.
bool image_view2::ImageView2::region_continuous_publish_ [private] |
Definition at line 214 of file image_view2.h.
double image_view2::ImageView2::resize_x_ [private] |
Definition at line 207 of file image_view2.h.
double image_view2::ImageView2::resize_y_ [private] |
Definition at line 207 of file image_view2.h.
bool image_view2::ImageView2::selecting_fg_ [private] |
Definition at line 198 of file image_view2.h.
bool image_view2::ImageView2::show_info_ [private] |
Definition at line 212 of file image_view2.h.
int image_view2::ImageView2::skip_draw_rate_ [private] |
Definition at line 188 of file image_view2.h.
Definition at line 191 of file image_view2.h.
double image_view2::ImageView2::tf_timeout_ [private] |
Definition at line 213 of file image_view2.h.
boost::circular_buffer<double> image_view2::ImageView2::times_ [private] |
Definition at line 178 of file image_view2.h.
Definition at line 111 of file image_view2.h.
bool image_view2::ImageView2::window_initialized_ [private] |
Definition at line 225 of file image_view2.h.
std::string image_view2::ImageView2::window_name_ [private] |
Definition at line 203 of file image_view2.h.
CvRect image_view2::ImageView2::window_selection_ [private] |
Definition at line 208 of file image_view2.h.