forked from xtdrone/XTDrone
更新ORBSLAM2
This commit is contained in:
parent
785283c029
commit
53895d43bc
|
@ -1,7 +1,7 @@
|
|||
subscribers:
|
||||
|
||||
camera_reading:
|
||||
topic: /iris_0/stereo/camera/left/image_raw
|
||||
topic: /iris_0/stereo_camera/left/image_raw
|
||||
queue_size: 1
|
||||
|
||||
actions:
|
||||
|
|
|
@ -0,0 +1,70 @@
|
|||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 554.254691191187
|
||||
Camera.fy: 554.254691191187
|
||||
Camera.cx: 320.5
|
||||
Camera.cy: 240.5
|
||||
|
||||
Camera.k1: 0.00000001
|
||||
Camera.k2: 0.00000001
|
||||
Camera.p1: 0.00000001
|
||||
Camera.p2: 0.00000001
|
||||
Camera.k3: 0.00000001
|
||||
|
||||
Camera.width: 640
|
||||
Camera.height: 480
|
||||
|
||||
# Camera frames per second
|
||||
Camera.fps: 20
|
||||
|
||||
# IR projector baseline times fx (aprox.)
|
||||
Camera.bf: 111
|
||||
|
||||
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
|
||||
Camera.RGB: 1
|
||||
|
||||
# Close/Far threshold. Baseline times.
|
||||
ThDepth: 2
|
||||
|
||||
# Deptmap values factor
|
||||
DepthMapFactor: 25.5
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# ORB Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# ORB Extractor: Number of features per image
|
||||
ORBextractor.nFeatures: 1000
|
||||
|
||||
# ORB Extractor: Scale factor between levels in the scale pyramid
|
||||
ORBextractor.scaleFactor: 1.2
|
||||
|
||||
# ORB Extractor: Number of levels in the scale pyramid
|
||||
ORBextractor.nLevels: 8
|
||||
|
||||
# ORB Extractor: Fast threshold
|
||||
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
|
||||
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
|
||||
# You can lower these values if your images have low contrast
|
||||
ORBextractor.iniThFAST: 20
|
||||
ORBextractor.minThFAST: 7
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Viewer Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
Viewer.KeyFrameSize: 0.05
|
||||
Viewer.KeyFrameLineWidth: 1
|
||||
Viewer.GraphLineWidth: 0.9
|
||||
Viewer.PointSize:2
|
||||
Viewer.CameraSize: 0.08
|
||||
Viewer.CameraLineWidth: 3
|
||||
Viewer.ViewpointX: 0
|
||||
Viewer.ViewpointY: -0.7
|
||||
Viewer.ViewpointZ: -1.8
|
||||
Viewer.ViewpointF: 500
|
||||
|
|
@ -21,7 +21,9 @@
|
|||
#include "ViewerAR.h"
|
||||
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <mutex>
|
||||
#include <thread>
|
||||
#include <cstdlib>
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/**
|
||||
* This file is part of ORB-SLAM2.
|
||||
*
|
||||
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
|
||||
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
|
||||
* For more information see <https://github.com/raulmur/ORB_SLAM2>
|
||||
*
|
||||
* ORB-SLAM2 is free software: you can redistribute it and/or modify
|
||||
|
@ -110,6 +110,4 @@ void ImageGrabber::GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const senso
|
|||
}
|
||||
|
||||
mpSLAM->TrackRGBD(cv_ptrRGB->image,cv_ptrD->image,cv_ptrRGB->header.stamp.toSec());
|
||||
}
|
||||
|
||||
|
||||
}
|
|
@ -117,11 +117,12 @@ int main(int argc, char **argv)
|
|||
|
||||
ros::NodeHandle nh;
|
||||
|
||||
ros::Publisher pose_pub = nh.advertise<geometry_msgs::PoseStamped>("/mavros/vision_pose/pose", 100);
|
||||
//ros::Publisher pose_pub = nh.advertise<geometry_msgs::PoseStamped>("/orbslamv2/vision_pose/pose", 100);
|
||||
ros::Publisher pose_pub = nh.advertise<geometry_msgs::PoseStamped>("/iris_0/mavros/vision_pose/pose", 100);
|
||||
igb.SetPub(&pose_pub);
|
||||
|
||||
message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/gi/simulation/left/image_raw", 1);
|
||||
message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "/gi/simulation/right/image_raw", 1);
|
||||
message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/iris_0/stereo_camera/left/image_raw", 1);
|
||||
message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "/iris_0/stereo_camera/right/image_raw", 1);
|
||||
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> sync_pol;
|
||||
message_filters::Synchronizer<sync_pol> sync(sync_pol(10), left_sub,right_sub);
|
||||
sync.registerCallback(boost::bind(&ImageGrabber::GrabStereo,&igb,_1,_2));
|
||||
|
|
|
@ -10,16 +10,16 @@ Camera.fy: 376.0
|
|||
Camera.cx: 376.0
|
||||
Camera.cy: 240.0
|
||||
|
||||
Camera.k1: 0.0
|
||||
Camera.k2: 0.0
|
||||
Camera.p1: 0.0
|
||||
Camera.p2: 0.0
|
||||
Camera.k1: -0.01
|
||||
Camera.k2: 0.004
|
||||
Camera.p1: 5e-5
|
||||
Camera.p2: -1e-4
|
||||
|
||||
Camera.width: 752
|
||||
Camera.height: 480
|
||||
|
||||
# Camera frames per second
|
||||
Camera.fps: 17.0
|
||||
Camera.fps: 7
|
||||
|
||||
# stereo baseline times fx
|
||||
Camera.bf: 45.12
|
||||
|
@ -28,7 +28,7 @@ Camera.bf: 45.12
|
|||
Camera.RGB: 1
|
||||
|
||||
# Close/Far threshold. Baseline times.
|
||||
ThDepth: 35
|
||||
ThDepth: 48
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Stereo Rectification. Only if you need to pre-rectify the images.
|
||||
|
@ -40,7 +40,7 @@ LEFT.D: !!opencv-matrix
|
|||
rows: 1
|
||||
cols: 5
|
||||
dt: d
|
||||
data:[0, 0, 0, 0, 0.0]
|
||||
data: [-0.01, 0.004, 5e-5, -1e-4, 0.0]
|
||||
LEFT.K: !!opencv-matrix
|
||||
rows: 3
|
||||
cols: 3
|
||||
|
@ -55,7 +55,7 @@ LEFT.P: !!opencv-matrix
|
|||
rows: 3
|
||||
cols: 4
|
||||
dt: d
|
||||
data: [376.0, 0, 376.0, 0, 0, 376.0, 240.0, 0, 0, 0, 1, 0]
|
||||
data: [376.0, 0, 376.0, 0, 0, 376.0, 240.0, 0, 0, 0, 1, 0]
|
||||
|
||||
RIGHT.height: 480
|
||||
RIGHT.width: 752
|
||||
|
@ -63,7 +63,7 @@ RIGHT.D: !!opencv-matrix
|
|||
rows: 1
|
||||
cols: 5
|
||||
dt: d
|
||||
data:[0, 0, 0, 0, 0.0]
|
||||
data: [-0.01, 0.004, 5e-5, -1e-4, 0.0]
|
||||
RIGHT.K: !!opencv-matrix
|
||||
rows: 3
|
||||
cols: 3
|
||||
|
|
|
@ -0,0 +1 @@
|
|||
rosbag record /orbslam2/vision_pose/pose /vins_estimator/camera_pose
|
|
@ -0,0 +1 @@
|
|||
rosrun ORB_SLAM2 Stereo Vocabulary/ORBvoc.txt Examples/Stereo/EuRoC.yaml true
|
|
@ -0,0 +1 @@
|
|||
rosrun ORB_SLAM2 RGBD Vocabulary/ORBvoc.txt Examples/RGB-D/px4_sitl.yaml
|
Loading…
Reference in New Issue