Skip to content

Commit

Permalink
Bug fix in FPS enumeration and ReadMe Update
Browse files Browse the repository at this point in the history
  • Loading branch information
Ramsonjehu committed Jan 24, 2020
1 parent 14ca090 commit d800cb4
Show file tree
Hide file tree
Showing 4 changed files with 56 additions and 27 deletions.
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ It also provides UI for changing V4l2 controls and to switch Color space/Compres
### Supported Color space/Compression:

* UYVY
* YUYV
* MJPG
* Y8
* Y12
Expand Down
10 changes: 9 additions & 1 deletion source/ecam_v4l2/src/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -320,7 +320,7 @@ namespace ecam_v4l2
image->data.resize(2 * frmt.stream_fmt.fmt.pix.width * frmt.stream_fmt.fmt.pix.height);
memcpy(&image->data[0],buffers[buffer.index].start,2*frmt.stream_fmt.fmt.pix.width*frmt.stream_fmt.fmt.pix.height);

}else if(frmt.stream_fmt.fmt.pix.pixelformat==V4L2_PIX_FMT_UYVY){
}else if(frmt.stream_fmt.fmt.pix.pixelformat==V4L2_PIX_FMT_UYVY ||frmt.stream_fmt.fmt.pix.pixelformat==V4L2_PIX_FMT_YUYV){

image->data.resize(2 * frmt.stream_fmt.fmt.pix.width * frmt.stream_fmt.fmt.pix.height);
memcpy(&image->data[0],buffers[buffer.index].start,2*frmt.stream_fmt.fmt.pix.width*frmt.stream_fmt.fmt.pix.height);
Expand Down Expand Up @@ -371,6 +371,11 @@ namespace ecam_v4l2
image->format = "uyvy";
image->data.reserve(2 * frmt.stream_fmt.fmt.pix.height * frmt.stream_fmt.fmt.pix.width);

}else if(frmt.stream_fmt.fmt.pix.pixelformat==V4L2_PIX_FMT_YUYV){

image->format = "yuyv";
image->data.reserve(2 * frmt.stream_fmt.fmt.pix.height * frmt.stream_fmt.fmt.pix.width);

}else if(frmt.stream_fmt.fmt.pix.pixelformat==V4L2_PIX_FMT_Y12){

image->format = "mono12";
Expand Down Expand Up @@ -524,6 +529,9 @@ namespace ecam_v4l2
case V4L2_PIX_FMT_UYVY:
*pixelformat = "UYVY";
break;
case V4L2_PIX_FMT_YUYV:
*pixelformat = "YUYV";
break;
case V4L2_PIX_FMT_GREY:
*pixelformat = "GREY";
break;
Expand Down
3 changes: 3 additions & 0 deletions source/rqt_cam/src/rqt_cam/controls.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,7 @@ namespace rqt_cam{
int Controls::enum_format(int type,std::string pix_fmt,int width,int height)
{
int index;
char dummy_char;
ros::NodeHandle node_handle;
ros::ServiceClient enum_format_client = node_handle.serviceClient<rqt_cam::enum_format>("EnumerateFormat");
rqt_cam::enum_format fmt_msg;
Expand All @@ -166,6 +167,8 @@ namespace rqt_cam{
for (index=0 ;index< fmt_msg.response.str.size(); index++){
resolutions.push_back(fmt_msg.response.str[index]);
}
std::istringstream temp1_stream(resolutions[0]);
temp1_stream >>width >> dummy_char >> height; // Getting currently enumerated height and width.
}else {
ROS_ERROR("Failed to call service Format_setting");
break;
Expand Down
69 changes: 43 additions & 26 deletions source/rqt_cam/src/rqt_cam/image_view.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -647,33 +647,50 @@ namespace rqt_cam {
************************************************************************************************************/
void ImageView::callbackImage(const rqt_cam::image::ConstPtr& msg)
{
if(msg->format=="uyvy"){
cv::Mat mat_src = cv::Mat(msg->height, msg->width, CV_8UC2,(void*)&msg->data[0]);
cv::cvtColor(mat_src, conversion_mat_, cv::COLOR_YUV2RGB_UYVY);
}else if(msg->format=="mjpg"){
cv::Mat Bgr_data;
imdecode(cv::Mat(1, msg->length, CV_8U, (void*)&msg->data[0]),cv::IMREAD_COLOR, &Bgr_data);
cv::cvtColor(Bgr_data,conversion_mat_, cv::COLOR_BGR2RGB);
}else if(msg->format=="mono8"){
cv::Mat gray8;
cv::Mat(msg->height, msg->width, CV_8UC1, (void*)&msg->data[0]).convertTo(gray8, CV_8U);
cv::cvtColor(gray8,conversion_mat_, cv::COLOR_GRAY2BGR);

}else if(msg->format=="mono16"){
cv::Mat gray8;
ConvertY16toY8((uint16_t*)&msg->data[0],msg->height,msg->width, gray8);
cv::cvtColor(gray8,conversion_mat_, cv::COLOR_GRAY2BGR);
}else if(msg->format=="mono12"){
cv::Mat gray8;
ConvertY12toY8((uint8_t*)&msg->data[0],msg->height,msg->width, gray8);
cv::cvtColor(gray8,conversion_mat_, cv::COLOR_GRAY2BGR);
try{

if(msg->format=="uyvy"){
cv::Mat mat_src = cv::Mat(msg->height, msg->width, CV_8UC2,(void*)&msg->data[0]);
cv::cvtColor(mat_src, conversion_mat_, cv::COLOR_YUV2RGB_UYVY);
}else if (msg->format=="yuyv") {
cv::Mat mat_src = cv::Mat(msg->height, msg->width, CV_8UC2,(void*)&msg->data[0]);
cv::cvtColor(mat_src, conversion_mat_, cv::COLOR_YUV2RGB_YUYV);
}else if(msg->format=="mjpg"){
cv::Mat Bgr_data;
// Checking whether mjpeg header is valid.
if( ((uint8_t*)&msg->data[0])[0] == 0xFF && ((uint8_t*)&msg->data[0])[1] == 0xD8){
imdecode(cv::Mat(1, msg->length, CV_8U, (void*)&msg->data[0]),cv::IMREAD_COLOR, &Bgr_data);
cv::cvtColor(Bgr_data,conversion_mat_, cv::COLOR_BGR2RGB);
}else{
return;
}
}else if(msg->format=="mono8"){
cv::Mat gray8;
cv::Mat(msg->height, msg->width, CV_8UC1, (void*)&msg->data[0]).convertTo(gray8, CV_8U);
cv::cvtColor(gray8,conversion_mat_, cv::COLOR_GRAY2BGR);

}else if(msg->format=="mono16"){
cv::Mat gray8;
ConvertY16toY8((uint16_t*)&msg->data[0],msg->height,msg->width, gray8);
cv::cvtColor(gray8,conversion_mat_, cv::COLOR_GRAY2BGR);
}else if(msg->format=="mono12"){
cv::Mat gray8;
ConvertY12toY8((uint8_t*)&msg->data[0],msg->height,msg->width, gray8);
cv::cvtColor(gray8,conversion_mat_, cv::COLOR_GRAY2BGR);
}
// image must be copied since it uses the conversion_mat_ for storage which is asynchronously overwritten in the next callback invocation
QImage image(conversion_mat_.data,msg->width,msg->height, 3*msg->width, QImage::Format_RGB888);
ui_.image_frame->setImage(image);
if(save_img){
save_img=false;
save_image(&msg->data[0],msg->format,msg->length,msg->width,msg->height);
}
}
// image must be copied since it uses the conversion_mat_ for storage which is asynchronously overwritten in the next callback invocation
QImage image(conversion_mat_.data,msg->width,msg->height, 3*msg->width, QImage::Format_RGB888);
ui_.image_frame->setImage(image);
if(save_img){
save_img=false;
save_image(&msg->data[0],msg->format,msg->length,msg->width,msg->height);
catch(cv::Exception& e)
{
qWarning("ImageView.callback_image() while trying to convert image to 'rgb8' an exception was thrown (%s)", e.what());
ui_.image_frame->setImage(QImage());
return;
}
}

Expand Down

0 comments on commit d800cb4

Please sign in to comment.