#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) |
Definition at line 83 of file image_view2.h.
typedef ImageView2Config image_view2::ImageView2::Config |
Definition at line 86 of file image_view2.h.
Enumerator | |
---|---|
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.
image_view2::ImageView2::ImageView2 | ( | ) |
Definition at line 39 of file image_view2.cpp.
image_view2::ImageView2::ImageView2 | ( | ros::NodeHandle & | nh | ) |
Definition at line 43 of file image_view2.cpp.
image_view2::ImageView2::~ImageView2 | ( | ) |
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.
|
private |
Definition at line 1818 of file image_view2.cpp.
|
private |
Definition at line 1711 of file image_view2.cpp.
void image_view2::ImageView2::clearPointArray | ( | ) |
Definition at line 1261 of file image_view2.cpp.
|
private |
Definition at line 1626 of file image_view2.cpp.
|
private |
Definition at line 130 of file image_view2.cpp.
|
private |
Definition at line 1083 of file image_view2.cpp.
|
private |
Definition at line 1036 of file image_view2.cpp.
|
private |
Definition at line 190 of file image_view2.cpp.
|
private |
Definition at line 725 of file image_view2.cpp.
|
private |
Definition at line 360 of file image_view2.cpp.
|
private |
Definition at line 1109 of file image_view2.cpp.
void image_view2::ImageView2::drawImage | ( | ) |
Definition at line 1196 of file image_view2.cpp.
|
private |
Definition at line 1001 of file image_view2.cpp.
|
private |
Definition at line 918 of file image_view2.cpp.
|
private |
Definition at line 253 of file image_view2.cpp.
|
private |
Definition at line 557 of file image_view2.cpp.
|
private |
Definition at line 217 of file image_view2.cpp.
|
private |
Definition at line 494 of file image_view2.cpp.
|
private |
Definition at line 815 of file image_view2.cpp.
|
private |
Definition at line 338 of file image_view2.cpp.
|
private |
Definition at line 659 of file image_view2.cpp.
|
private |
Definition at line 287 of file image_view2.cpp.
|
private |
Definition at line 601 of file image_view2.cpp.
|
private |
Definition at line 443 of file image_view2.cpp.
|
private |
Definition at line 689 of file image_view2.cpp.
|
private |
Definition at line 1858 of file image_view2.cpp.
|
private |
Definition at line 1614 of file image_view2.cpp.
|
private |
Definition at line 1462 of file image_view2.cpp.
|
private |
Definition at line 1456 of file image_view2.cpp.
ImageView2::KEY_MODE image_view2::ImageView2::getMode | ( | ) |
Definition at line 1291 of file image_view2.cpp.
|
private |
Definition at line 1768 of file image_view2.cpp.
|
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.
|
private |
Definition at line 1620 of file image_view2.cpp.
|
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.
|
private |
Definition at line 1788 of file image_view2.cpp.
|
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.
|
static |
Definition at line 1676 of file image_view2.cpp.
|
private |
Definition at line 1808 of file image_view2.cpp.
|
private |
Definition at line 1303 of file image_view2.cpp.
|
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.
|
private |
Definition at line 1491 of file image_view2.cpp.
|
private |
Definition at line 1547 of file image_view2.cpp.
|
private |
Definition at line 1633 of file image_view2.cpp.
|
private |
Definition at line 1507 of file image_view2.cpp.
void image_view2::ImageView2::publishForegroundBackgroundMask | ( | ) |
Definition at line 1326 of file image_view2.cpp.
|
private |
Definition at line 1379 of file image_view2.cpp.
|
private |
Definition at line 1317 of file image_view2.cpp.
|
private |
Definition at line 1394 of file image_view2.cpp.
void image_view2::ImageView2::publishPointArray | ( | ) |
Definition at line 1269 of file image_view2.cpp.
|
private |
Definition at line 1593 of file image_view2.cpp.
|
private |
Definition at line 1348 of file image_view2.cpp.
|
private |
Definition at line 432 of file image_view2.cpp.
|
private |
Definition at line 1748 of file image_view2.cpp.
void image_view2::ImageView2::redraw | ( | ) |
Definition at line 1050 of file image_view2.cpp.
|
private |
Definition at line 1718 of file image_view2.cpp.
|
private |
Definition at line 783 of file image_view2.cpp.
|
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.
|
private |
Definition at line 1829 of file image_view2.cpp.
bool image_view2::ImageView2::toggleSelection | ( | ) |
Definition at line 1296 of file image_view2.cpp.
|
private |
Definition at line 1450 of file image_view2.cpp.
|
private |
Definition at line 1468 of file image_view2.cpp.
|
private |
Definition at line 1444 of file image_view2.cpp.
|
private |
Definition at line 1587 of file image_view2.cpp.
|
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.
|
private |
Definition at line 260 of file image_view2.h.
|
private |
Definition at line 254 of file image_view2.h.
|
private |
Definition at line 256 of file image_view2.h.
|
private |
Definition at line 242 of file image_view2.h.
|
private |
Definition at line 239 of file image_view2.h.
|
private |
Definition at line 219 of file image_view2.h.
|
private |
Definition at line 292 of file image_view2.h.
|
private |
Definition at line 246 of file image_view2.h.
|
private |
Definition at line 240 of file image_view2.h.
|
private |
Definition at line 211 of file image_view2.h.
|
private |
Definition at line 212 of file image_view2.h.
|
private |
Definition at line 212 of file image_view2.h.
|
private |
Definition at line 210 of file image_view2.h.
|
private |
Definition at line 241 of file image_view2.h.
|
private |
Definition at line 193 of file image_view2.h.
|
private |
Definition at line 234 of file image_view2.h.
|
private |
Definition at line 216 of file image_view2.h.
|
private |
Definition at line 235 of file image_view2.h.
|
private |
Definition at line 253 of file image_view2.h.
|
private |
Definition at line 255 of file image_view2.h.
|
private |
Definition at line 220 of file image_view2.h.
|
private |
Definition at line 287 of file image_view2.h.
|
private |
Definition at line 288 of file image_view2.h.
|
private |
Definition at line 214 of file image_view2.h.
|
private |
Definition at line 214 of file image_view2.h.
|
private |
Definition at line 214 of file image_view2.h.
|
private |
Definition at line 215 of file image_view2.h.
|
private |
Definition at line 210 of file image_view2.h.
|
private |
Definition at line 208 of file image_view2.h.
|
private |
Definition at line 198 of file image_view2.h.
|
private |
Definition at line 192 of file image_view2.h.
|
private |
Definition at line 207 of file image_view2.h.
|
private |
Definition at line 206 of file image_view2.h.
|
private |
Definition at line 222 of file image_view2.h.
|
private |
Definition at line 194 of file image_view2.h.
|
private |
Definition at line 205 of file image_view2.h.
|
private |
Definition at line 247 of file image_view2.h.
|
private |
Definition at line 269 of file image_view2.h.
|
private |
Definition at line 289 of file image_view2.h.
|
private |
Definition at line 265 of file image_view2.h.
|
private |
Definition at line 257 of file image_view2.h.
|
private |
Definition at line 266 of file image_view2.h.
|
private |
Definition at line 267 of file image_view2.h.
|
private |
Definition at line 268 of file image_view2.h.
|
private |
Definition at line 199 of file image_view2.h.
|
private |
Definition at line 191 of file image_view2.h.
|
private |
Definition at line 202 of file image_view2.h.
|
private |
Definition at line 195 of file image_view2.h.
|
private |
Definition at line 196 of file image_view2.h.
|
private |
Definition at line 259 of file image_view2.h.
|
private |
Definition at line 252 of file image_view2.h.
|
private |
Definition at line 290 of file image_view2.h.
|
private |
Definition at line 210 of file image_view2.h.
|
private |
Definition at line 221 of file image_view2.h.
|
private |
Definition at line 204 of file image_view2.h.
|
private |
Definition at line 249 of file image_view2.h.
|
private |
Definition at line 226 of file image_view2.h.
|
private |
Definition at line 227 of file image_view2.h.
|
private |
Definition at line 248 of file image_view2.h.
|
private |
Definition at line 291 of file image_view2.h.
|
private |
Definition at line 264 of file image_view2.h.
|
private |
Definition at line 228 of file image_view2.h.
|
private |
Definition at line 258 of file image_view2.h.
|
private |
Definition at line 230 of file image_view2.h.
|
private |
Definition at line 229 of file image_view2.h.
|
private |
Definition at line 214 of file image_view2.h.
|
private |
Definition at line 214 of file image_view2.h.
|
private |
Definition at line 214 of file image_view2.h.
|
private |
Definition at line 213 of file image_view2.h.
|
private |
Definition at line 215 of file image_view2.h.
|
private |
Definition at line 203 of file image_view2.h.
|
private |
Definition at line 231 of file image_view2.h.
|
private |
Definition at line 232 of file image_view2.h.
|
private |
Definition at line 251 of file image_view2.h.
|
private |
Definition at line 285 of file image_view2.h.
|
private |
Definition at line 250 of file image_view2.h.
|
private |
Definition at line 245 of file image_view2.h.
|
private |
Definition at line 237 of file image_view2.h.
|
private |
Definition at line 237 of file image_view2.h.
|
private |
Definition at line 225 of file image_view2.h.
|
private |
Definition at line 286 of file image_view2.h.
|
private |
Definition at line 243 of file image_view2.h.
|
private |
Definition at line 209 of file image_view2.h.
|
private |
Definition at line 213 of file image_view2.h.
|
private |
Definition at line 200 of file image_view2.h.
|
private |
Definition at line 218 of file image_view2.h.
|
private |
Definition at line 244 of file image_view2.h.
|
private |
Definition at line 197 of file image_view2.h.
bool image_view2::ImageView2::use_window |
Definition at line 120 of file image_view2.h.
|
private |
Definition at line 261 of file image_view2.h.
|
private |
Definition at line 233 of file image_view2.h.
|
private |
Definition at line 238 of file image_view2.h.