> I'm having trouble figuring out how to set the camera matrix (K). The > CameraInfo.msg says: > > # Intrinsic camera matrix for the raw (distorted) images > # Projects 3D points in the camera coordinate frame to 2D pixel > # coordinates using the focal lengths (fx, fy) and principal point > # (cx, cy): > # [fx 0 cx] > # K = [ 0 fy cy] > # [ 0 0 1] > > float64[9] K # 3x3 row-major matrix > > I don't understand how to obtain this information from the dc1394 interface. It is probably not available in a generic way. > If it's not available, then I suppose fx, fy, cx and cy would have to > be parameters defined for each camera. How does the user determine > them? Are there reasonable defaults to use when these data are not > available? It would be useful to display the images in rviz (which > actually does display, but with an error and with the camera window > covering the upper left of the rviz window). > > How do the PR2 cameras solve this problem? Are the lenses just known > for each model number? We use the camera_calibration package. It looks at a stream of images containing a checker board with known dimensions, and produces calibration information. It then uses SetCameraInfo to store this information on the camera. We have had some discussions on the fact that not all cameras will be able to store their camera_info. Probably the easiest way to deal with this is to have the camera driver take a file as a parameter. At startup it will load its camera_info from that file (if there is an error it would use the all-zero camera_info). If SetCameraInfo is called, it overwrites that file with the new camera_info, and starts publishing that instead. The thought would be to write a class that looks something like this: class CameraInfoFileManager { public: // Registers the SetCameraInfo service and loads the camera info from the file. CameraInfoFileManager(ros::NodeHandle nh, const std::string &cameraInfoFile); // Returns the current camera_info sensor_msgs::CameraInfo GetCameraInfo(); }; You would then call GetCameraInfo() before publishing each image to find out what camera_info to publish. This class should probably live in camera_calibration_parsers (which it could use for loading/storing the file). We'll get to it eventually, but if you write something like this up before then, I can take care of pushing it into the right place.