Skip to content

Commit

Permalink
Merge pull request #77 from ros-drivers/correct_default_camera_info
Browse files Browse the repository at this point in the history
Noticed the default camera info was actually wrong, corrected
  • Loading branch information
awesomebytes authored Oct 26, 2020
2 parents 31d60f2 + 666b07d commit d3d9045
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions src/video_stream.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,16 +88,16 @@ virtual sensor_msgs::CameraInfo get_default_camera_info_from_image(sensor_msgs::
// Don't let distorsion matrix be empty
cam_info_msg.D.resize(5, 0.0);
// Give a reasonable default intrinsic camera matrix
cam_info_msg.K = boost::assign::list_of(1.0) (0.0) (img->width/2.0)
(0.0) (1.0) (img->height/2.0)
cam_info_msg.K = boost::assign::list_of(img->width/2.0) (0.0) (img->width/2.0)
(0.0) (img->height/2.0) (img->height/2.0)
(0.0) (0.0) (1.0);
// Give a reasonable default rectification matrix
cam_info_msg.R = boost::assign::list_of (1.0) (0.0) (0.0)
(0.0) (1.0) (0.0)
(0.0) (0.0) (1.0);
// Give a reasonable default projection matrix
cam_info_msg.P = boost::assign::list_of (1.0) (0.0) (img->width/2.0) (0.0)
(0.0) (1.0) (img->height/2.0) (0.0)
cam_info_msg.P = boost::assign::list_of (img->width/2.0) (0.0) (img->width/2.0) (0.0)
(0.0) (img->height/2.0) (img->height/2.0) (0.0)
(0.0) (0.0) (1.0) (0.0);
return cam_info_msg;
}
Expand Down

0 comments on commit d3d9045

Please sign in to comment.