add bgr888
This commit is contained in:
parent
26d95ec0ac
commit
6d961203be
|
@ -304,8 +304,8 @@ enum class Format : std::uint32_t {
|
|||
GREY = MYNTEYE_FOURCC('G', 'R', 'E', 'Y'),
|
||||
/** YUV 4:2:2, 16 bits per pixel */
|
||||
YUYV = MYNTEYE_FOURCC('Y', 'U', 'Y', 'V'),
|
||||
/** RGB 8:8:8, 24 bits per pixel */
|
||||
RGB888 = MYNTEYE_FOURCC('R', 'G', 'B', '3'),
|
||||
/** BGR 8:8:8, 24 bits per pixel */
|
||||
BGR888 = MYNTEYE_FOURCC('B', 'G', 'R', '3'),
|
||||
/** Last guard */
|
||||
LAST
|
||||
};
|
||||
|
|
|
@ -25,7 +25,7 @@ int main(int argc, char *argv[]) {
|
|||
if (!api)
|
||||
return 1;
|
||||
api->SetStreamRequest(
|
||||
Resolution::RES_1280x400, Format::RGB888, FrameRate::RATE_20_FPS);
|
||||
Resolution::RES_1280x400, Format::BGR888, FrameRate::RATE_20_FPS);
|
||||
// api->SetOptionValue(Option::FRAME_RATE, 25);
|
||||
// api->SetOptionValue(Option::IMU_FREQUENCY, 500);
|
||||
api->SetOptionValue(Option::IR_CONTROL, 80);
|
||||
|
|
|
@ -52,7 +52,7 @@ int main(int argc, char *argv[]) {
|
|||
|
||||
std::size_t left_count = 0;
|
||||
device->SetStreamRequest(
|
||||
Resolution::RES_1280x400, Format::RGB888, FrameRate::RATE_30_FPS);
|
||||
Resolution::RES_1280x400, Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
device->SetStreamCallback(
|
||||
Stream::LEFT, [&left_count](const device::StreamData &data) {
|
||||
CHECK_NOTNULL(data.img);
|
||||
|
@ -135,13 +135,15 @@ int main(int argc, char *argv[]) {
|
|||
cv::cvtColor(left_img, left_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::cvtColor(right_img, right_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_data.frame->format() == Format::RGB888) {
|
||||
} else if (left_data.frame->format() == Format::BGR888) {
|
||||
cv::Mat left_img(
|
||||
left_data.frame->height(), left_data.frame->width(), CV_8UC3,
|
||||
left_data.frame->data());
|
||||
cv::Mat right_img(
|
||||
right_data.frame->height(), right_data.frame->width(), CV_8UC3,
|
||||
right_data.frame->data());
|
||||
cv::cvtColor(left_img, left_img, CV_BGRA2RGBA);
|
||||
cv::cvtColor(right_img, right_img, CV_BGRA2RGBA);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else {
|
||||
return -1;
|
||||
|
|
|
@ -108,7 +108,7 @@ int main(int argc, char *argv[]) {
|
|||
const auto frame_empty = [&frame]() { return frame == nullptr; };
|
||||
|
||||
uvc::set_device_mode(
|
||||
*device, 1280, 400, static_cast<int>(Format::RGB888), 20,
|
||||
*device, 1280, 400, static_cast<int>(Format::BGR888), 20,
|
||||
[&mtx, &cv, &frame, &frame_ready](
|
||||
const void *data, std::function<void()> continuation) {
|
||||
// reinterpret_cast<const std::uint8_t *>(data);
|
||||
|
@ -144,7 +144,7 @@ int main(int argc, char *argv[]) {
|
|||
|
||||
// only lastest frame is valid
|
||||
cv::Mat img(400, 1280, CV_8UC3, const_cast<void *>(frame->data));
|
||||
// cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::cvtColor(img, img, CV_BGRA2RGBA);
|
||||
cv::imshow("frame", img);
|
||||
|
||||
frame = nullptr;
|
||||
|
|
|
@ -45,8 +45,10 @@ cv::Mat frame2mat(const std::shared_ptr<device::Frame> &frame) {
|
|||
cv::Mat img(frame->height(), frame->width(), CV_8UC2, frame->data());
|
||||
cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
||||
return img;
|
||||
} else if (frame->format() == Format::RGB888) {
|
||||
return cv::Mat(frame->height(), frame->width(), CV_8UC3, frame->data());
|
||||
} else if (frame->format() == Format::BGR888) {
|
||||
cv::Mat img(frame->height(), frame->width(), CV_8UC3, frame->data());
|
||||
cv::cvtColor(img, img, CV_BGRA2RGBA);
|
||||
return img;
|
||||
} else {
|
||||
return cv::Mat(frame->height(), frame->width(), CV_8UC1, frame->data());
|
||||
}
|
||||
|
|
|
@ -33,17 +33,19 @@ const std::map<Model, std::map<Capabilities, StreamRequests>>
|
|||
{Model::STANDARD,
|
||||
{{Capabilities::STEREO, {{480, 752, Format::YUYV, 25}}},
|
||||
{Capabilities::STEREO_COLOR,
|
||||
{{1280, 400, Format::YUYV, 20},
|
||||
{1280, 400, Format::YUYV, 30},
|
||||
{1280, 400, Format::YUYV, 60},
|
||||
{2560, 800, Format::YUYV, 10},
|
||||
{2560, 800, Format::YUYV, 20},
|
||||
{2560, 800, Format::YUYV, 30},
|
||||
{1280, 400, Format::RGB888, 20},
|
||||
{1280, 400, Format::RGB888, 30},
|
||||
{1280, 400, Format::RGB888, 60},
|
||||
{2560, 800, Format::RGB888, 10},
|
||||
{2560, 800, Format::RGB888, 20},
|
||||
{2560, 800, Format::RGB888, 30}}}}}};
|
||||
{// {1280, 400, Format::YUYV, 10},
|
||||
// {1280, 400, Format::YUYV, 20},
|
||||
// {1280, 400, Format::YUYV, 30},
|
||||
// {1280, 400, Format::YUYV, 60},
|
||||
// {2560, 800, Format::YUYV, 10},
|
||||
// {2560, 800, Format::YUYV, 20},
|
||||
// {2560, 800, Format::YUYV, 30},
|
||||
{1280, 400, Format::BGR888, 10},
|
||||
{1280, 400, Format::BGR888, 20},
|
||||
{1280, 400, Format::BGR888, 30},
|
||||
{1280, 400, Format::BGR888, 60},
|
||||
{2560, 800, Format::BGR888, 10},
|
||||
{2560, 800, Format::BGR888, 20},
|
||||
{2560, 800, Format::BGR888, 30}}}}}};
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
|
|
@ -79,7 +79,7 @@ bool unpack_left_img_pixels(
|
|||
CHECK_NOTNULL(frame);
|
||||
CHECK_EQ(request.format, frame->format());
|
||||
auto data_new = reinterpret_cast<const std::uint8_t *>(data);
|
||||
if (request.format == Format::YUYV || request.format == Format::RGB888) {
|
||||
if (request.format == Format::YUYV || request.format == Format::BGR888) {
|
||||
std::size_t n = request.format == Format::YUYV ? 2 : 3;
|
||||
std::size_t w = frame->width() * n;
|
||||
std::size_t h = frame->height();
|
||||
|
@ -105,7 +105,7 @@ bool unpack_right_img_pixels(
|
|||
CHECK_NOTNULL(frame);
|
||||
CHECK_EQ(request.format, frame->format());
|
||||
auto data_new = reinterpret_cast<const std::uint8_t *>(data);
|
||||
if (request.format == Format::YUYV || request.format == Format::RGB888) {
|
||||
if (request.format == Format::YUYV || request.format == Format::BGR888) {
|
||||
std::size_t n = request.format == Format::YUYV ? 2 : 3;
|
||||
std::size_t w = frame->width() * n;
|
||||
std::size_t h = frame->height();
|
||||
|
|
|
@ -167,7 +167,7 @@ std::size_t bytes_per_pixel(const Format &value) {
|
|||
return 1;
|
||||
case Format::YUYV:
|
||||
return 2;
|
||||
case Format::RGB888:
|
||||
case Format::BGR888:
|
||||
return 3;
|
||||
default:
|
||||
LOG(FATAL) << "Unknown format";
|
||||
|
|
|
@ -64,16 +64,36 @@ void Dataset::SaveStreamData(
|
|||
std::stringstream ss;
|
||||
ss << writer->outdir << OS_SEP << std::dec
|
||||
<< std::setw(IMAGE_FILENAME_WIDTH) << std::setfill('0') << seq << ".png";
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC2, data.frame->data());
|
||||
cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::imwrite(ss.str(), img);
|
||||
if (data.frame->format() == Format::GREY) {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC1,
|
||||
data.frame->data());
|
||||
cv::imwrite(ss.str(), img);
|
||||
} else if (data.frame->format() == Format::YUYV) {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC2,
|
||||
data.frame->data());
|
||||
cv::cvtColor(img, img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::imwrite(ss.str(), img);
|
||||
} else if (data.frame->format() == Format::BGR888) {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC3,
|
||||
data.frame->data());
|
||||
cv::cvtColor(img, img, CV_BGRA2RGBA);
|
||||
cv::imwrite(ss.str(), img);
|
||||
} else {
|
||||
cv::Mat img(
|
||||
data.frame->height(), data.frame->width(), CV_8UC1,
|
||||
data.frame->data());
|
||||
cv::imwrite(ss.str(), img);
|
||||
}
|
||||
}
|
||||
++stream_counts_[stream];
|
||||
}
|
||||
|
||||
void Dataset::SaveMotionData(const device::MotionData &data) {
|
||||
auto &&writer = GetMotionWriter();
|
||||
// auto seq = data.imu->serial_number;
|
||||
auto seq = motion_count_;
|
||||
if (data.imu->flag == 1 || data.imu->flag == 2) {
|
||||
writer->ofs << seq << ", " << data.imu->timestamp << ", "
|
||||
|
@ -83,6 +103,13 @@ void Dataset::SaveMotionData(const device::MotionData &data) {
|
|||
<< data.imu->temperature << std::endl;
|
||||
++motion_count_;
|
||||
}
|
||||
/*
|
||||
if(motion_count_ != seq) {
|
||||
LOG(INFO) << "motion_count_ != seq !" << " motion_count_: " << motion_count_
|
||||
<< " seq: " << seq;
|
||||
motion_count_ = seq;
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
Dataset::writer_t Dataset::GetStreamWriter(const Stream &stream) {
|
||||
|
|
|
@ -31,6 +31,8 @@ int main(int argc, char *argv[]) {
|
|||
auto &&device = device::select();
|
||||
if (!device)
|
||||
return 1;
|
||||
device->SetStreamRequest(
|
||||
Resolution::RES_1280x400, Format::BGR888, FrameRate::RATE_30_FPS);
|
||||
/*
|
||||
{ // auto-exposure
|
||||
device->SetOptionValue(Option::EXPOSURE_MODE, 0);
|
||||
|
@ -79,16 +81,40 @@ int main(int argc, char *argv[]) {
|
|||
|
||||
auto &&left_frame = left_datas.back().frame;
|
||||
auto &&right_frame = right_datas.back().frame;
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC2, left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC2,
|
||||
right_frame->data());
|
||||
|
||||
cv::Mat img;
|
||||
cv::cvtColor(left_img, left_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::cvtColor(right_img, right_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
|
||||
if (left_frame->format() == Format::GREY) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC1,
|
||||
left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC1,
|
||||
right_frame->data());
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_frame->format() == Format::YUYV) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC2,
|
||||
left_frame->data());
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC2,
|
||||
right_frame->data());
|
||||
cv::cvtColor(left_img, left_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::cvtColor(right_img, right_img, cv::COLOR_YUV2BGR_YUY2);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else if (left_frame->format() == Format::BGR888) {
|
||||
cv::Mat left_img(
|
||||
left_frame->height(), left_frame->width(), CV_8UC3,
|
||||
left_frame->data());
|
||||
cv::cvtColor(left_img, left_img, CV_BGRA2RGBA);
|
||||
cv::Mat right_img(
|
||||
right_frame->height(), right_frame->width(), CV_8UC3,
|
||||
right_frame->data());
|
||||
cv::cvtColor(right_img, right_img, CV_BGRA2RGBA);
|
||||
cv::hconcat(left_img, right_img, img);
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
cv::imshow("frame", img);
|
||||
|
||||
{ // save
|
||||
|
|
|
@ -532,6 +532,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
|||
}
|
||||
|
||||
api_ = API::Create(device);
|
||||
api_->SetStreamRequest(
|
||||
Resolution::RES_1280x400, Format::BGR888, FrameRate::RATE_20_FPS);
|
||||
}
|
||||
|
||||
sensor_msgs::CameraInfoPtr getCameraInfo(const Stream &stream) {
|
||||
|
|
Loading…
Reference in New Issue
Block a user