Program Listing for File common.hpp
↰ Return to documentation for file (/tmp/ws/src/demos/intra_process_demo/include/image_pipeline/common.hpp
)
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef IMAGE_PIPELINE__COMMON_HPP_
#define IMAGE_PIPELINE__COMMON_HPP_
#ifdef _WIN32
#include <process.h>
#define GETPID _getpid
#else
#include <unistd.h>
#define GETPID getpid
#endif
#include <chrono>
#include <string>
#include "opencv2/opencv.hpp"
#include "builtin_interfaces/msg/time.hpp"
int
encoding2mat_type(const std::string & encoding)
{
if (encoding == "mono8") {
return CV_8UC1;
} else if (encoding == "bgr8") {
return CV_8UC3;
} else if (encoding == "mono16") {
return CV_16SC1;
} else if (encoding == "rgba8") {
return CV_8UC4;
}
throw std::runtime_error("Unsupported mat type");
}
std::string
mat_type2encoding(int mat_type)
{
switch (mat_type) {
case CV_8UC1:
return "mono8";
case CV_8UC3:
return "bgr8";
case CV_16SC1:
return "mono16";
case CV_8UC4:
return "rgba8";
default:
throw std::runtime_error("Unsupported encoding type");
}
}
void set_now(builtin_interfaces::msg::Time & time)
{
std::chrono::nanoseconds now = std::chrono::high_resolution_clock::now().time_since_epoch();
if (now <= std::chrono::nanoseconds(0)) {
time.sec = time.nanosec = 0;
} else {
time.sec = static_cast<builtin_interfaces::msg::Time::_sec_type>(now.count() / 1000000000);
time.nanosec = now.count() % 1000000000;
}
}
void
draw_on_image(cv::Mat & image, const std::string & text, int height)
{
cv::Mat c_mat = image;
cv::putText(
c_mat,
text.c_str(),
cv::Point(10, height),
cv::FONT_HERSHEY_SIMPLEX,
0.3,
cv::Scalar(0, 255, 0));
}
#endif // IMAGE_PIPELINE__COMMON_HPP_