#include <image_view2.h>
Public Types | |
typedef ImageView2Config | Config |
enum | KEY_MODE { MODE_RECTANGLE, MODE_SERIES, MODE_SELECT_FORE_AND_BACK, MODE_SELECT_FORE_AND_BACK_RECT, MODE_LINE, MODE_POLY, MODE_NONE } |
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 | |
bool | changeModeServiceCallback (image_view2::ChangeModeRequest &req, image_view2::ChangeModeResponse &res) |
void | checkMousePos (int &x, int &y) |
void | clearPolyPoints () |
void | config_callback (Config &config, uint32_t level) |
void | createDistortGridImage () |
void | cropROI () |
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 | drawGrid () |
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) |
void | eventCb (const image_view2::MouseEvent::ConstPtr &event_msg) |
void | finishSelectingPoly () |
cv::Point | getLineEndPoint () |
cv::Point | getLineStartPoint () |
bool | grabcutModeServiceCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res) |
bool | grabcutRectModeServiceCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res) |
bool | isPolySelectingFirstTime () |
bool | isSelectingLineStartPoint () |
bool | lineModeServiceCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res) |
bool | lookupTransformation (std::string frame_id, ros::Time &acquisition_time, std::map< std::string, int > &tf_fail, tf::StampedTransform &transform) |
bool | noneModeServiceCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res) |
void | pointArrayToMask (std::vector< cv::Point2d > &points, cv::Mat &mask) |
bool | polyModeServiceCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res) |
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 | publishLinePoints () |
void | publishMonoImage (ros::Publisher &pub, cv::Mat &image, const std_msgs::Header &header) |
void | publishMouseInteractionResult () |
void | publishPolyPoints () |
void | publishRectFromMaskImage (ros::Publisher &pub, cv::Mat &image, const std_msgs::Header &header) |
cv::Point | ratioPoint (double x, double y) |
bool | rectangleModeServiceCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res) |
void | resetInteraction () |
void | resolveLocalMarkerQueue () |
bool | seriesModeServiceCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res) |
KEY_MODE | stringToMode (const std::string &str) |
void | updateLineEndPoint (cv::Point p) |
void | updateLinePoint (cv::Point p) |
void | updateLineStartPoint (cv::Point p) |
void | updatePolyPoint (cv::Point p) |
void | updatePolySelectingPoint (cv::Point p) |
Private Attributes | |
bool | autosize_ |
ros::Publisher | background_mask_pub_ |
ros::Publisher | background_rect_pub_ |
bool | blurry_mode_ |
cv::Point2f | button_up_pos_ |
image_geometry::PinholeCameraModel | cam_model_ |
ros::ServiceServer | change_mode_srv_ |
bool | continuous_ready_ |
int | count_ |
cv::Mat | distort_grid_mask_ |
int | div_u_ |
int | div_v_ |
cv::Mat | draw_ |
bool | draw_grid_ |
ros::Subscriber | event_sub_ |
boost::format | filename_format_ |
bool | fisheye_mode_ |
int | font_ |
ros::Publisher | foreground_mask_pub_ |
ros::Publisher | foreground_rect_pub_ |
std::vector< std::string > | frame_ids_ |
ros::ServiceServer | grabcut_mode_srv_ |
ros::ServiceServer | grabcut_rect_mode_srv_ |
int | grid_blue_ |
int | grid_green_ |
int | grid_red_ |
int | grid_thickness_ |
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_ |
cv::Point | line_end_point_ |
ros::ServiceServer | line_mode_srv_ |
boost::mutex | line_point_mutex_ |
ros::Publisher | line_pub_ |
bool | line_select_start_point_ |
bool | line_selected_ |
cv::Point | line_start_point_ |
image_transport::Publisher | local_image_pub_ |
V_ImageMarkerMessage | local_queue_ |
V_ImageMarkerMessage | marker_queue_ |
ros::Subscriber | marker_sub_ |
std::string | marker_topic_ |
KEY_MODE | mode_ |
ros::Publisher | move_point_pub_ |
ros::ServiceServer | none_mode_srv_ |
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_ |
ros::ServiceServer | poly_mode_srv_ |
boost::mutex | poly_point_mutex_ |
std::vector< cv::Point2d > | poly_points_ |
ros::Publisher | poly_pub_ |
bool | poly_selecting_done_ |
cv::Point | poly_selecting_point_ |
int | prev_blue_ |
int | prev_green_ |
int | prev_red_ |
int | prev_space_ |
int | prev_thickness_ |
boost::mutex | queue_mutex_ |
cv::Rect | rect_bg_ |
cv::Rect | rect_fg_ |
ros::Publisher | rectangle_img_pub_ |
ros::ServiceServer | rectangle_mode_srv_ |
ros::Publisher | rectangle_pub_ |
bool | region_continuous_publish_ |
double | resize_x_ |
double | resize_y_ |
bool | selecting_fg_ |
ros::ServiceServer | series_mode_srv_ |
bool | show_info_ |
int | skip_draw_rate_ |
int | space_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
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 83 of file image_view2.h.
typedef ImageView2Config image_view2::ImageView2::Config |
Definition at line 86 of file image_view2.h.
MODE_RECTANGLE | |
MODE_SERIES | |
MODE_SELECT_FORE_AND_BACK | |
MODE_SELECT_FORE_AND_BACK_RECT | |
MODE_LINE | |
MODE_POLY | |
MODE_NONE |
Definition at line 87 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 123 of file image_view2.cpp.
void image_view2::ImageView2::addPoint | ( | int | x, |
int | y | ||
) |
Definition at line 1202 of file image_view2.cpp.
void image_view2::ImageView2::addRegionPoint | ( | int | x, |
int | y | ||
) |
Definition at line 1245 of file image_view2.cpp.
bool image_view2::ImageView2::changeModeServiceCallback | ( | image_view2::ChangeModeRequest & | req, |
image_view2::ChangeModeResponse & | res | ||
) | [private] |
Definition at line 1818 of file image_view2.cpp.
void image_view2::ImageView2::checkMousePos | ( | int & | x, |
int & | y | ||
) | [private] |
Definition at line 1711 of file image_view2.cpp.
Definition at line 1261 of file image_view2.cpp.
void image_view2::ImageView2::clearPolyPoints | ( | ) | [private] |
Definition at line 1626 of file image_view2.cpp.
void image_view2::ImageView2::config_callback | ( | Config & | config, |
uint32_t | level | ||
) | [private] |
Definition at line 130 of file image_view2.cpp.
void image_view2::ImageView2::createDistortGridImage | ( | ) | [private] |
Definition at line 1083 of file image_view2.cpp.
void image_view2::ImageView2::cropROI | ( | ) | [private] |
Definition at line 1036 of file image_view2.cpp.
void image_view2::ImageView2::drawCircle | ( | const image_view2::ImageMarker2::ConstPtr & | marker | ) | [private] |
Definition at line 190 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 725 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 360 of file image_view2.cpp.
void image_view2::ImageView2::drawGrid | ( | ) | [private] |
Definition at line 1109 of file image_view2.cpp.
void image_view2::ImageView2::drawImage | ( | ) |
Definition at line 1196 of file image_view2.cpp.
void image_view2::ImageView2::drawInfo | ( | ros::Time & | before_rendering | ) | [private] |
Definition at line 1001 of file image_view2.cpp.
void image_view2::ImageView2::drawInteraction | ( | ) | [private] |
Definition at line 918 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 253 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 557 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 217 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 494 of file image_view2.cpp.
void image_view2::ImageView2::drawMarkers | ( | ) | [private] |
Definition at line 815 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 338 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 659 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 287 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 601 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 443 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 689 of file image_view2.cpp.
void image_view2::ImageView2::eventCb | ( | const image_view2::MouseEvent::ConstPtr & | event_msg | ) | [private] |
Definition at line 1858 of file image_view2.cpp.
void image_view2::ImageView2::finishSelectingPoly | ( | ) | [private] |
Definition at line 1614 of file image_view2.cpp.
cv::Point image_view2::ImageView2::getLineEndPoint | ( | ) | [private] |
Definition at line 1462 of file image_view2.cpp.
cv::Point image_view2::ImageView2::getLineStartPoint | ( | ) | [private] |
Definition at line 1456 of file image_view2.cpp.
Definition at line 1291 of file image_view2.cpp.
bool image_view2::ImageView2::grabcutModeServiceCallback | ( | std_srvs::EmptyRequest & | req, |
std_srvs::EmptyResponse & | res | ||
) | [private] |
Definition at line 1768 of file image_view2.cpp.
bool image_view2::ImageView2::grabcutRectModeServiceCallback | ( | std_srvs::EmptyRequest & | req, |
std_srvs::EmptyResponse & | res | ||
) | [private] |
Definition at line 1778 of file image_view2.cpp.
void image_view2::ImageView2::imageCb | ( | const sensor_msgs::ImageConstPtr & | msg | ) |
Definition at line 1147 of file image_view2.cpp.
void image_view2::ImageView2::infoCb | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) |
Definition at line 157 of file image_view2.cpp.
bool image_view2::ImageView2::isPolySelectingFirstTime | ( | ) | [private] |
Definition at line 1620 of file image_view2.cpp.
bool image_view2::ImageView2::isSelectingLineStartPoint | ( | ) | [private] |
Definition at line 1485 of file image_view2.cpp.
bool image_view2::ImageView2::isValidMovement | ( | const cv::Point2f & | start_point, |
const cv::Point2f & | end_point | ||
) |
Definition at line 1437 of file image_view2.cpp.
bool image_view2::ImageView2::lineModeServiceCallback | ( | std_srvs::EmptyRequest & | req, |
std_srvs::EmptyResponse & | res | ||
) | [private] |
Definition at line 1788 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 163 of file image_view2.cpp.
void image_view2::ImageView2::markerCb | ( | const image_view2::ImageMarker2ConstPtr & | marker | ) |
Definition at line 144 of file image_view2.cpp.
void image_view2::ImageView2::mouseCb | ( | int | event, |
int | x, | ||
int | y, | ||
int | flags, | ||
void * | param | ||
) | [static] |
Definition at line 1676 of file image_view2.cpp.
bool image_view2::ImageView2::noneModeServiceCallback | ( | std_srvs::EmptyRequest & | req, |
std_srvs::EmptyResponse & | res | ||
) | [private] |
Definition at line 1808 of file image_view2.cpp.
void image_view2::ImageView2::pointArrayToMask | ( | std::vector< cv::Point2d > & | points, |
cv::Mat & | mask | ||
) | [private] |
Definition at line 1303 of file image_view2.cpp.
bool image_view2::ImageView2::polyModeServiceCallback | ( | std_srvs::EmptyRequest & | req, |
std_srvs::EmptyResponse & | res | ||
) | [private] |
Definition at line 1798 of file image_view2.cpp.
void image_view2::ImageView2::pressKey | ( | int | key | ) |
Definition at line 1684 of file image_view2.cpp.
void image_view2::ImageView2::processLeftButtonDown | ( | int | x, |
int | y | ||
) | [private] |
Definition at line 1491 of file image_view2.cpp.
void image_view2::ImageView2::processLeftButtonUp | ( | int | x, |
int | y | ||
) | [private] |
Definition at line 1547 of file image_view2.cpp.
void image_view2::ImageView2::processMouseEvent | ( | int | event, |
int | x, | ||
int | y, | ||
int | flags, | ||
void * | param | ||
) | [private] |
Definition at line 1633 of file image_view2.cpp.
void image_view2::ImageView2::processMove | ( | int | x, |
int | y | ||
) | [private] |
Definition at line 1507 of file image_view2.cpp.
Definition at line 1326 of file image_view2.cpp.
void image_view2::ImageView2::publishLinePoints | ( | ) | [private] |
Definition at line 1379 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 1317 of file image_view2.cpp.
void image_view2::ImageView2::publishMouseInteractionResult | ( | ) | [private] |
Definition at line 1394 of file image_view2.cpp.
Definition at line 1269 of file image_view2.cpp.
void image_view2::ImageView2::publishPolyPoints | ( | ) | [private] |
Definition at line 1593 of file image_view2.cpp.
void image_view2::ImageView2::publishRectFromMaskImage | ( | ros::Publisher & | pub, |
cv::Mat & | image, | ||
const std_msgs::Header & | header | ||
) | [private] |
Definition at line 1348 of file image_view2.cpp.
cv::Point image_view2::ImageView2::ratioPoint | ( | double | x, |
double | y | ||
) | [private] |
Definition at line 432 of file image_view2.cpp.
bool image_view2::ImageView2::rectangleModeServiceCallback | ( | std_srvs::EmptyRequest & | req, |
std_srvs::EmptyResponse & | res | ||
) | [private] |
Definition at line 1748 of file image_view2.cpp.
void image_view2::ImageView2::redraw | ( | ) |
Definition at line 1050 of file image_view2.cpp.
void image_view2::ImageView2::resetInteraction | ( | ) | [private] |
Definition at line 1718 of file image_view2.cpp.
void image_view2::ImageView2::resolveLocalMarkerQueue | ( | ) | [private] |
Definition at line 783 of file image_view2.cpp.
bool image_view2::ImageView2::seriesModeServiceCallback | ( | std_srvs::EmptyRequest & | req, |
std_srvs::EmptyResponse & | res | ||
) | [private] |
Definition at line 1758 of file image_view2.cpp.
void image_view2::ImageView2::setMode | ( | KEY_MODE | mode | ) |
Definition at line 1286 of file image_view2.cpp.
void image_view2::ImageView2::setRegionWindowPoint | ( | int | x, |
int | y | ||
) |
Definition at line 1213 of file image_view2.cpp.
void image_view2::ImageView2::showImage | ( | ) |
Definition at line 1696 of file image_view2.cpp.
ImageView2::KEY_MODE image_view2::ImageView2::stringToMode | ( | const std::string & | str | ) | [private] |
Definition at line 1829 of file image_view2.cpp.
Definition at line 1296 of file image_view2.cpp.
void image_view2::ImageView2::updateLineEndPoint | ( | cv::Point | p | ) | [private] |
Definition at line 1450 of file image_view2.cpp.
void image_view2::ImageView2::updateLinePoint | ( | cv::Point | p | ) | [private] |
Definition at line 1468 of file image_view2.cpp.
void image_view2::ImageView2::updateLineStartPoint | ( | cv::Point | p | ) | [private] |
Definition at line 1444 of file image_view2.cpp.
void image_view2::ImageView2::updatePolyPoint | ( | cv::Point | p | ) | [private] |
Definition at line 1587 of file image_view2.cpp.
void image_view2::ImageView2::updatePolySelectingPoint | ( | cv::Point | p | ) | [private] |
Definition at line 1608 of file image_view2.cpp.
void image_view2::ImageView2::updateRegionWindowSize | ( | int | x, |
int | y | ||
) |
Definition at line 1231 of file image_view2.cpp.
bool image_view2::ImageView2::autosize_ [private] |
Definition at line 260 of file image_view2.h.
Definition at line 254 of file image_view2.h.
Definition at line 256 of file image_view2.h.
bool image_view2::ImageView2::blurry_mode_ [private] |
Definition at line 242 of file image_view2.h.
cv::Point2f image_view2::ImageView2::button_up_pos_ [private] |
Definition at line 239 of file image_view2.h.
Definition at line 219 of file image_view2.h.
Definition at line 292 of file image_view2.h.
bool image_view2::ImageView2::continuous_ready_ [private] |
Definition at line 246 of file image_view2.h.
int image_view2::ImageView2::count_ [private] |
Definition at line 240 of file image_view2.h.
cv::Mat image_view2::ImageView2::distort_grid_mask_ [private] |
Definition at line 211 of file image_view2.h.
int image_view2::ImageView2::div_u_ [private] |
Definition at line 212 of file image_view2.h.
int image_view2::ImageView2::div_v_ [private] |
Definition at line 212 of file image_view2.h.
cv::Mat image_view2::ImageView2::draw_ [private] |
Definition at line 210 of file image_view2.h.
bool image_view2::ImageView2::draw_grid_ [private] |
Definition at line 241 of file image_view2.h.
Definition at line 193 of file image_view2.h.
boost::format image_view2::ImageView2::filename_format_ [private] |
Definition at line 234 of file image_view2.h.
bool image_view2::ImageView2::fisheye_mode_ [private] |
Definition at line 216 of file image_view2.h.
int image_view2::ImageView2::font_ [private] |
Definition at line 235 of file image_view2.h.
Definition at line 253 of file image_view2.h.
Definition at line 255 of file image_view2.h.
std::vector<std::string> image_view2::ImageView2::frame_ids_ [private] |
Definition at line 220 of file image_view2.h.
Definition at line 287 of file image_view2.h.
Definition at line 288 of file image_view2.h.
int image_view2::ImageView2::grid_blue_ [private] |
Definition at line 214 of file image_view2.h.
int image_view2::ImageView2::grid_green_ [private] |
Definition at line 214 of file image_view2.h.
int image_view2::ImageView2::grid_red_ [private] |
Definition at line 214 of file image_view2.h.
int image_view2::ImageView2::grid_thickness_ [private] |
Definition at line 215 of file image_view2.h.
cv::Mat image_view2::ImageView2::image_ [private] |
Definition at line 210 of file image_view2.h.
boost::mutex image_view2::ImageView2::image_mutex_ [private] |
Definition at line 208 of file image_view2.h.
Definition at line 198 of file image_view2.h.
Definition at line 192 of file image_view2.h.
Definition at line 207 of file image_view2.h.
sensor_msgs::CameraInfoConstPtr image_view2::ImageView2::info_msg_ [private] |
Definition at line 206 of file image_view2.h.
boost::mutex image_view2::ImageView2::info_mutex_ [private] |
Definition at line 222 of file image_view2.h.
Definition at line 194 of file image_view2.h.
sensor_msgs::ImageConstPtr image_view2::ImageView2::last_msg_ [private] |
Definition at line 205 of file image_view2.h.
bool image_view2::ImageView2::left_button_clicked_ [private] |
Definition at line 247 of file image_view2.h.
Definition at line 269 of file image_view2.h.
Definition at line 289 of file image_view2.h.
boost::mutex image_view2::ImageView2::line_point_mutex_ [private] |
Definition at line 265 of file image_view2.h.
Definition at line 257 of file image_view2.h.
bool image_view2::ImageView2::line_select_start_point_ [private] |
Definition at line 266 of file image_view2.h.
bool image_view2::ImageView2::line_selected_ [private] |
Definition at line 267 of file image_view2.h.
Definition at line 268 of file image_view2.h.
Definition at line 199 of file image_view2.h.
Definition at line 191 of file image_view2.h.
Definition at line 202 of file image_view2.h.
Definition at line 195 of file image_view2.h.
std::string image_view2::ImageView2::marker_topic_ [private] |
Definition at line 196 of file image_view2.h.
KEY_MODE image_view2::ImageView2::mode_ [private] |
Definition at line 259 of file image_view2.h.
Definition at line 252 of file image_view2.h.
Definition at line 290 of file image_view2.h.
cv::Mat image_view2::ImageView2::original_image_ [private] |
Definition at line 210 of file image_view2.h.
std::vector<cv::Point2d> image_view2::ImageView2::point_array_ [private] |
Definition at line 221 of file image_view2.h.
boost::mutex image_view2::ImageView2::point_array_mutex_ [private] |
Definition at line 204 of file image_view2.h.
Definition at line 249 of file image_view2.h.
std::vector<cv::Point2d> image_view2::ImageView2::point_bg_array_ [private] |
Definition at line 226 of file image_view2.h.
std::vector<cv::Point2d> image_view2::ImageView2::point_fg_array_ [private] |
Definition at line 227 of file image_view2.h.
Definition at line 248 of file image_view2.h.
Definition at line 291 of file image_view2.h.
boost::mutex image_view2::ImageView2::poly_point_mutex_ [private] |
Definition at line 264 of file image_view2.h.
std::vector<cv::Point2d> image_view2::ImageView2::poly_points_ [private] |
Definition at line 228 of file image_view2.h.
Definition at line 258 of file image_view2.h.
bool image_view2::ImageView2::poly_selecting_done_ [private] |
Definition at line 230 of file image_view2.h.
Definition at line 229 of file image_view2.h.
int image_view2::ImageView2::prev_blue_ [private] |
Definition at line 214 of file image_view2.h.
int image_view2::ImageView2::prev_green_ [private] |
Definition at line 214 of file image_view2.h.
int image_view2::ImageView2::prev_red_ [private] |
Definition at line 214 of file image_view2.h.
int image_view2::ImageView2::prev_space_ [private] |
Definition at line 213 of file image_view2.h.
int image_view2::ImageView2::prev_thickness_ [private] |
Definition at line 215 of file image_view2.h.
boost::mutex image_view2::ImageView2::queue_mutex_ [private] |
Definition at line 203 of file image_view2.h.
cv::Rect image_view2::ImageView2::rect_bg_ [private] |
Definition at line 231 of file image_view2.h.
cv::Rect image_view2::ImageView2::rect_fg_ [private] |
Definition at line 232 of file image_view2.h.
Definition at line 251 of file image_view2.h.
Definition at line 285 of file image_view2.h.
Definition at line 250 of file image_view2.h.
bool image_view2::ImageView2::region_continuous_publish_ [private] |
Definition at line 245 of file image_view2.h.
double image_view2::ImageView2::resize_x_ [private] |
Definition at line 237 of file image_view2.h.
double image_view2::ImageView2::resize_y_ [private] |
Definition at line 237 of file image_view2.h.
bool image_view2::ImageView2::selecting_fg_ [private] |
Definition at line 225 of file image_view2.h.
Definition at line 286 of file image_view2.h.
bool image_view2::ImageView2::show_info_ [private] |
Definition at line 243 of file image_view2.h.
int image_view2::ImageView2::skip_draw_rate_ [private] |
Definition at line 209 of file image_view2.h.
int image_view2::ImageView2::space_ [private] |
Definition at line 213 of file image_view2.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > image_view2::ImageView2::srv_ [private] |
Definition at line 200 of file image_view2.h.
Definition at line 218 of file image_view2.h.
double image_view2::ImageView2::tf_timeout_ [private] |
Definition at line 244 of file image_view2.h.
boost::circular_buffer<double> image_view2::ImageView2::times_ [private] |
Definition at line 197 of file image_view2.h.
Definition at line 120 of file image_view2.h.
bool image_view2::ImageView2::window_initialized_ [private] |
Definition at line 261 of file image_view2.h.
std::string image_view2::ImageView2::window_name_ [private] |
Definition at line 233 of file image_view2.h.
CvRect image_view2::ImageView2::window_selection_ [private] |
Definition at line 238 of file image_view2.h.