源碼見github : https://github.com/ethz-asl/ethzasl_ptam
今天安裝ptam想試一下效果,結果發現相機打開會出現幻影的情況.如下圖所示. 通過瀏覽 github 其中的issue ,發現是ptam
ros上接口是隻支持灰度圖片.(猜測圖片幻影也許就是因爲三通道圖片造成的). 所以需要改變其中關於圖像的的ros接口. 所以我在
中間做了一個圖像格式轉換節點.. 其中利用到了opencv 的 cvtColor . 接口程序如後面說明:(ROS圖像格式與opencv圖像格式的相互轉換.))
mark: 當時該usb_cam_node的驅動程序,直接取灰度圖像格式,出錯了,mark 之.
==> 記得之前跑單目視覺slam: Monoslam scenelib2 by Davison
的mono-slam 相機也有這樣問題出現..後面再試試看.
注意:ptam 的launch 接口支持的相機模型參數是非針孔相機模型,需要按照它的校正程序運行....
// img_tran 節點程序
#include <ros/ros.h>
#include <opencv2/opencv.hpp>
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
//#include "../image_convert/image_converter.h"
#include "ros/ros.h"
#include "std_msgs/String.h"
ros::Publisher image_pub ;
void chatterCallback(const sensor_msgs::ImageConstPtr& msg)
{
cv_bridge::CvImagePtr cv_ptr;
cv_ptr = cv_bridge::toCvCopy(msg,sensor_msgs::image_encodings::BGR8);
// cv_ptr->image.copyTo(cv_camera_);
cv::Mat image_gray;
cv::cvtColor(cv_ptr->image, image_gray,CV_BGR2GRAY);//灰度化
cv_bridge::CvImage cvi;
sensor_msgs::Image ros_img;
ros::Time time=ros::Time::now();
cvi.header.stamp = time;
cvi.header.frame_id = "image";
cvi.encoding = "mono8";
cvi.image = image_gray;
cvi.toImageMsg(ros_img);
image_pub.publish(cvi.toImageMsg());
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "img_tran");
ros::NodeHandle n;
ros::Subscriber sub = n.subscribe("/usb_cam/image_raw", 1000, chatterCallback);
image_pub = n.advertise<sensor_msgs::Image>("/mono_image", 1000);
ros::spin();
return 0;
}
相機啓動文件.
<launch>
<!--node pkg="rviz" type="rviz" name="rviz"
args="-d $(find usb_cam)/launch/camera.rviz"/-->
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" respawn="false" output="log">
<param name="video_device" type="string" value="/dev/video1"/>
<param name="camera_frame_id" type="string" value="usb_cam"/>
<param name="framerate" type="int" value="50"/>
<param name="io_method" type="string" value="mmap"/>
<param name="image_width" type="int" value="640"/>
<param name="image_height" type="int" value="480"/>
<param name="pixel_format" type="string" value="yuyv"/>
</node>
<node name="img_tran" pkg="ar_localization" type="img_tran" respawn="false" output="log">
</node>
</launch>
ptam 啓動文件.. 圖像接口.
<launch>
<node name="ptam" pkg="ptam" type="ptam" clear_params="true" output="screen">
<remap from="image" to="$(optenv IMAGE /mono_image)" />
<remap from="pose" to="pose"/>
<rosparam file="$(find ptam)/PtamFixParams.yaml"/>
</node>
</launch>
相機參數文件
gui: True
ImageSizeX: 640
ImageSizeY: 480
ARBuffer_width: 1200
ARBuffer_height: 900
WiggleScale: 0.1
BundleMEstimator: Tukey
TrackerMEstimator: Tukey
MinTukeySigma: 0.4
CandidateMinSTScore: 70
Calibrator_BlurSigma: 1.0
Calibrator_MeanGate: 10
Calibrator_MinCornersForGrabbedImage: 20
Calibrator_Optimize: 0
Calibrator_Show: 0
Calibrator_NoDistortion: 0
CameraCalibrator_MaxStepDistFraction: 0.3
CameraCalibrator_CornerPatchSize: 20
GLWindowMenu_Enable: True
GLWindowMenu_mgvnMenuItemWidth: 90
GLWindowMenu_mgvnMenuTextOffset: 20
InitLevel: 1
MaxKFDistWiggleMult: 1
MaxPatchesPerFrame: 300
MaxKF: 15
parent_frame: world
TrackingQualityFoundPixels: 50
UseKFPixelDist: True
NoLevelZeroMapPoints: True
FASTMethod: OAST16
MaxStereoInitLoops: 4
AutoInitPixel: 20
# --- bluefox - low distort lens ---
Cam_fx: 0.795574
Cam_fy: 1.25149
Cam_cx: 0.50417
Cam_cy: 0.51687
Cam_s: 0.482014
# -----------------------------------