8 int main(
int argc,
char * argv[])
try 45 const auto window_name =
"Display Image";
46 namedWindow(window_name, WINDOW_NORMAL);
47 setWindowProperty(window_name, WND_PROP_FULLSCREEN, WINDOW_FULLSCREEN);
49 const int display_w = 1280;
50 const int digits = 16;
51 const int circle_w = (display_w - 120) / (digits + 2);
52 const int display_h = 720;
58 while (getWindowProperty(window_name, WND_PROP_AUTOSIZE) >= 0)
80 Mat
display = Mat::zeros(display_h, display_w, CV_8UC1);
89 for (
int i = 0;
i < digits + 2;
i++)
91 const int rad = circle_w / 2 - 6;
93 if (
i == 0 ||
i == digits + 1 || packer.
get()[
i - 1])
95 circle(display,
Point(50 + circle_w *
i + rad, 70 + rad),
96 rad, Scalar(255, 255, 255), -1, 8);
101 imshow(window_name, display);
102 if (waitKey(1) >= 0)
break;
115 catch (
const std::exception& e)
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
static const textual_icon circle
bool try_pack(int number)
const std::string & get_failed_args() const
void submit_frame(rs2::frame f)
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
std::vector< bool > & get()
const std::string & get_failed_function() const
void copy_preview_to(cv::Mat &display)
::geometry_msgs::Point_< std::allocator< void > > Point