10 request_(request), connection_(connection), nh_(nh), inactive_(false)
21 ImageStreamer(request, connection, nh), it_(nh), initialized_(false)
39 for (
size_t it = 0; it<available_topics.size(); it++){
40 std::string available_topic_name = available_topics[it].name;
41 if(available_topic_name ==
topic_ || (available_topic_name.find(
"/") == 0 &&
42 available_topic_name.substr(1) ==
topic_)) {
63 catch (boost::system::system_error &e)
66 ROS_DEBUG(
"system_error exception: %s", e.what());
70 catch (std::exception &e)
92 if (msg->encoding.find(
"F") != std::string::npos)
96 cv::Mat_<float> float_image = float_image_bridge;
98 cv::minMaxIdx(float_image, 0, &max_val);
102 float_image *= (255 / max_val);
112 int input_width = img.cols;
113 int input_height = img.rows;
123 cv::flip(img, img,
false);
124 cv::flip(img, img,
true);
132 cv::resize(img, img_resized, new_size);
156 catch (cv::Exception &e)
162 catch (boost::system::system_error &e)
165 ROS_DEBUG(
"system_error exception: %s", e.what());
169 catch (std::exception &e)