项目地址
相关问题
仅供学习与交流之用,因滥用造成的任何后果与作者无关。
项目中APK和源码可以在Meizu MX2(见下图),Nox模拟器上正常运行,Android M及以上请检查相机和SD卡权限,不回复任何关于某些设备无法运行的留言或邮件,请谅解。
##准备工作
配置Android Studio 2.2+OpenCV 3.2+Cmake
tr1/unordered_map' file not found
,可能是因为ndk版本过高导致,可使用老版本(如r14b r12b)进行编译,下载地址SLAM_AR_Demo_OBJ_MiniVoc.apk
依赖库有:
Eigen3好像定义全在头文件里面,因此只需要包含头文件就可以了,g2o还需要进行链接
g2o作为一个静态链接库和ORB_SLAM2进行链接
cmake_minimum_required(VERSION 3.6)
set(CMAKE_VERBOSE_MAKEFILE on)
set(libs "${CMAKE_SOURCE_DIR}/src/main/jniLibs")
include_directories(${CMAKE_SOURCE_DIR}/src/main/cpp/opencv/include)
add_library(libopencv_java3 SHARED IMPORTED )
set_target_properties(libopencv_java3 PROPERTIES
IMPORTED_LOCATION "${libs}/${ANDROID_ABI}/libopencv_java3.so")
add_library(libopencv_java SHARED IMPORTED )
set_target_properties(libopencv_java PROPERTIES
IMPORTED_LOCATION "${libs}/${ANDROID_ABI}/libopencv_java.so")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=gnu++11 -fexceptions -frtti")
ADD_LIBRARY(g2o
src/main/cpp/Thirdparty/g2o/g2o/types/types_sba.h
src/main/cpp/Thirdparty/g2o/g2o/types/types_six_dof_expmap.h
src/main/cpp/Thirdparty/g2o/g2o/types/types_sba.cpp
src/main/cpp/Thirdparty/g2o/g2o/types/types_six_dof_expmap.cpp
src/main/cpp/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.cpp
src/main/cpp/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h
src/main/cpp/Thirdparty/g2o/g2o/types/se3quat.h
src/main/cpp/Thirdparty/g2o/g2o/types/se3_ops.h
src/main/cpp/Thirdparty/g2o/g2o/types/se3_ops.hpp
src/main/cpp/Thirdparty/g2o/g2o/core/base_edge.h
src/main/cpp/Thirdparty/g2o/g2o/core/base_binary_edge.h
src/main/cpp/Thirdparty/g2o/g2o/core/hyper_graph_action.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/base_binary_edge.hpp
src/main/cpp/Thirdparty/g2o/g2o/core/hyper_graph_action.h
src/main/cpp/Thirdparty/g2o/g2o/core/base_multi_edge.h
src/main/cpp/Thirdparty/g2o/g2o/core/hyper_graph.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/base_multi_edge.hpp
src/main/cpp/Thirdparty/g2o/g2o/core/hyper_graph.h
src/main/cpp/Thirdparty/g2o/g2o/core/base_unary_edge.h
src/main/cpp/Thirdparty/g2o/g2o/core/linear_solver.h
src/main/cpp/Thirdparty/g2o/g2o/core/base_unary_edge.hpp
src/main/cpp/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/base_vertex.h
src/main/cpp/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.h
src/main/cpp/Thirdparty/g2o/g2o/core/base_vertex.hpp
src/main/cpp/Thirdparty/g2o/g2o/core/matrix_structure.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/batch_stats.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/matrix_structure.h
src/main/cpp/Thirdparty/g2o/g2o/core/batch_stats.h
src/main/cpp/Thirdparty/g2o/g2o/core/openmp_mutex.h
src/main/cpp/Thirdparty/g2o/g2o/core/block_solver.h
src/main/cpp/Thirdparty/g2o/g2o/core/block_solver.hpp
src/main/cpp/Thirdparty/g2o/g2o/core/parameter.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/parameter.h
src/main/cpp/Thirdparty/g2o/g2o/core/cache.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/cache.h
src/main/cpp/Thirdparty/g2o/g2o/core/optimizable_graph.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/optimizable_graph.h
src/main/cpp/Thirdparty/g2o/g2o/core/solver.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/solver.h
src/main/cpp/Thirdparty/g2o/g2o/core/creators.h
src/main/cpp/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/estimate_propagator.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.h
src/main/cpp/Thirdparty/g2o/g2o/core/estimate_propagator.h
src/main/cpp/Thirdparty/g2o/g2o/core/factory.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/optimization_algorithm_property.h
src/main/cpp/Thirdparty/g2o/g2o/core/factory.h
src/main/cpp/Thirdparty/g2o/g2o/core/sparse_block_matrix.h
src/main/cpp/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/sparse_block_matrix.hpp
src/main/cpp/Thirdparty/g2o/g2o/core/sparse_optimizer.h
src/main/cpp/Thirdparty/g2o/g2o/core/hyper_dijkstra.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/hyper_dijkstra.h
src/main/cpp/Thirdparty/g2o/g2o/core/parameter_container.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/parameter_container.h
src/main/cpp/Thirdparty/g2o/g2o/core/optimization_algorithm.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/optimization_algorithm.h
src/main/cpp/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.h
src/main/cpp/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h
src/main/cpp/Thirdparty/g2o/g2o/core/jacobian_workspace.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/jacobian_workspace.h
src/main/cpp/Thirdparty/g2o/g2o/core/robust_kernel.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/robust_kernel.h
src/main/cpp/Thirdparty/g2o/g2o/core/robust_kernel_factory.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/robust_kernel_factory.h
src/main/cpp/Thirdparty/g2o/g2o/core/robust_kernel_impl.cpp
src/main/cpp/Thirdparty/g2o/g2o/core/robust_kernel_impl.h
src/main/cpp/Thirdparty/g2o/g2o/stuff/string_tools.h
src/main/cpp/Thirdparty/g2o/g2o/stuff/color_macros.h
src/main/cpp/Thirdparty/g2o/g2o/stuff/macros.h
src/main/cpp/Thirdparty/g2o/g2o/stuff/timeutil.cpp
src/main/cpp/Thirdparty/g2o/g2o/stuff/misc.h
src/main/cpp/Thirdparty/g2o/g2o/stuff/timeutil.h
src/main/cpp/Thirdparty/g2o/g2o/stuff/os_specific.c
src/main/cpp/Thirdparty/g2o/g2o/stuff/os_specific.h
src/main/cpp/Thirdparty/g2o/g2o/stuff/string_tools.cpp
src/main/cpp/Thirdparty/g2o/g2o/stuff/property.cpp
src/main/cpp/Thirdparty/g2o/g2o/stuff/property.h
)
include_directories(
src/main/cpp
src/main/cpp/include
src/main/cpp/Thirdparty
src/main/cpp/Thirdparty/g2o
)
add_library(ORB_SLAM2
src/main/cpp/include/System.h
src/main/cpp/include/Tracking.h
src/main/cpp/include/LocalMapping.h
src/main/cpp/include/LoopClosing.h
src/main/cpp/include/ORBextractor.h
src/main/cpp/include/ORBmatcher.h
src/main/cpp/include/FrameDrawer.h
src/main/cpp/include/Converter.h
src/main/cpp/include/MapPoint.h
src/main/cpp/include/KeyFrame.h
src/main/cpp/include/Map.h
src/main/cpp/include/Optimizer.h
src/main/cpp/include/PnPsolver.h
src/main/cpp/include/Frame.h
src/main/cpp/include/KeyFrameDatabase.h
src/main/cpp/include/Sim3Solver.h
src/main/cpp/include/Initializer.h
src/main/cpp/include/Common.h
src/main/cpp/src/System.cc
src/main/cpp/src/Tracking.cc
src/main/cpp/src/LocalMapping.cc
src/main/cpp/src/LoopClosing.cc
src/main/cpp/src/ORBextractor.cc
src/main/cpp/src/ORBmatcher.cc
src/main/cpp/src/FrameDrawer.cc
src/main/cpp/src/Converter.cc
src/main/cpp/src/MapPoint.cc
src/main/cpp/src/KeyFrame.cc
src/main/cpp/src/Map.cc
src/main/cpp/src/Optimizer.cc
src/main/cpp/src/PnPsolver.cc
src/main/cpp/src/Frame.cc
src/main/cpp/src/KeyFrameDatabase.cc
src/main/cpp/src/Sim3Solver.cc
src/main/cpp/src/Initializer.cc
############DBow2############
src/main/cpp/Thirdparty/DBoW2/DBoW2/BowVector.h
src/main/cpp/Thirdparty/DBoW2/DBoW2/FORB.h
src/main/cpp/Thirdparty/DBoW2/DBoW2/FClass.h
src/main/cpp/Thirdparty/DBoW2/DBoW2/FeatureVector.h
src/main/cpp/Thirdparty/DBoW2/DBoW2/ScoringObject.h
src/main/cpp/Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h
src/main/cpp/Thirdparty/DBoW2/DUtils/Random.h
src/main/cpp/Thirdparty/DBoW2/DBoW2/BowVector.cpp
src/main/cpp/Thirdparty/DBoW2/DBoW2/FORB.cpp
src/main/cpp/Thirdparty/DBoW2/DBoW2/FeatureVector.cpp
src/main/cpp/Thirdparty/DBoW2/DBoW2/ScoringObject.cpp
src/main/cpp/Thirdparty/DBoW2/DUtils/Random.cpp
)
add_library(
SLAM
SHARED
src/main/cpp/native-lib.cpp
)
find_library( # Sets the name of the path variable.
log-lib
# Specifies the name of the NDK library that
# you want CMake to locate.
log)
target_link_libraries(SLAM
libopencv_java3 libopencv_java
${log-lib}
ORB_SLAM2
g2o
)
相机参数还没有标定,毕竟安卓机型号实在太杂了,Vocabulary我使用二进制读入优化方案(参考项目的Issues)
因为C++并不方便读取assets中和raw里面的文件,所以先保存到sd卡
class ExtractModelTask extends AsyncTask<Void,Void,Boolean>{
Context context;
public ExtractModelTask(Context context) {
this.context = context;
}
@Override
protected Boolean doInBackground(Void... params) {
ZipHelper.saveFile(context,Environment.getExternalStorageDirectory().getPath()+"/SLAM","CameraSettings.yaml","CameraSettings.yaml");
ZipHelper.saveFile(context,Environment.getExternalStorageDirectory().getPath()+"/SLAM","config.txt","config.txt");
ZipHelper.saveFile(context,Environment.getExternalStorageDirectory().getPath()+"/SLAM","ORBvoc.txt.arm.bin","ORBvoc.txt.arm.bin");
return true;
}
@Override
protected void onPostExecute(Boolean aBoolean) {
super.onPostExecute(aBoolean);
Intent intent=new Intent(ModelActivity.this,MainActivity.class);
startActivity(intent);
finish();
}
}
保存文件的代码如下:
public static void saveFile(Context context,String outputPath,String fileName,String inputPath){
File file = new File(outputPath, fileName);
try
{
if (!file.exists()) {
File fileParentDir = file.getParentFile();
if (!fileParentDir.exists()) {
fileParentDir.mkdirs();
}
file.createNewFile();
}else return;
InputStream in = context.getResources().getAssets().open(inputPath);
OutputStream out = new FileOutputStream(file);
byte buffer[] = new byte[1024];
int realLength;
while ((realLength = in.read(buffer)) > 0) {
out.write(buffer, 0, realLength);
}
in.close();
out.close();
}catch (IOException e)
{
e.printStackTrace();
}
}
#include
#include
#include
#include "include/System.h"
#include "Common.h"
#include "ORBVocabulary.h"
extern "C" {
std::string modelPath;
ORB_SLAM2::System *slamSys;
double timeStamp;
long getCurrentTime() {
struct timeval tv;
gettimeofday(&tv,NULL);
return tv.tv_sec * 1000 + tv.tv_usec / 1000;
}
void addTextToImage(const string &s, cv::Mat &im, const int r, const int g, const int b)
{
int l = 10;
cv::putText(im,s,cv::Point(l,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8);
cv::putText(im,s,cv::Point(l-1,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8);
cv::putText(im,s,cv::Point(l+1,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8);
cv::putText(im,s,cv::Point(l-1,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8);
cv::putText(im,s,cv::Point(l,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8);
cv::putText(im,s,cv::Point(l+1,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8);
cv::putText(im,s,cv::Point(l-1,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8);
cv::putText(im,s,cv::Point(l,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8);
cv::putText(im,s,cv::Point(l+1,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8);
cv::putText(im,s,cv::Point(l,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(r,g,b),2,8);
}
void printStatus(const int &status, cv::Mat &im)
{
switch(status) {
case 1: {addTextToImage("SLAM NOT INITIALIZED",im,255,0,0); break;}
case 2: {addTextToImage("SLAM ON",im,0,255,0); break;}
case 3: {addTextToImage("SLAM LOST",im,255,0,0); break;}
}
}
void drawTrackedPoints(const std::vector &vKeys, const std::vector &vMPs, cv::Mat &im)
{
const int N = vKeys.size();
for(int i=0; iTrackMonocular(image,timeStamp);
int status = slamSys->GetTrackingState();
vector vMPs = slamSys->GetTrackedMapPoints();
vector vKeys = slamSys->GetTrackedKeyPointsUn();
printStatus(status,outputImage);
drawTrackedPoints(vKeys,vMPs,outputImage);
}
JNIEXPORT void JNICALL
Java_com_martin_ads_orb_1slam2_1android_MainActivity_nativeProcessFrame(JNIEnv *env,
jobject instance,
jlong matAddrGr,
jlong matAddrRgba) {
cv::Mat &mGr = *(cv::Mat *) matAddrGr;
cv::Mat &mRgba = *(cv::Mat *) matAddrRgba;
processImage(mGr,mRgba);
}
JNIEXPORT void JNICALL
Java_com_martin_ads_orb_1slam2_1android_MainActivity_initSLAM(JNIEnv *env, jobject instance,
jstring path_) {
const char *path = env->GetStringUTFChars(path_, 0);
modelPath=path;
env->ReleaseStringUTFChars(path_, path);
ifstream in;
in.open(modelPath+"config.txt");
string vocName,settingName;
getline(in,vocName);
getline(in,settingName);
vocName=modelPath+vocName;
settingName=modelPath+settingName;
timeStamp=0;
slamSys=new ORB_SLAM2::System(vocName,settingName,ORB_SLAM2::System::MONOCULAR);
}
}
代码修改自OpenCV的demo
package com.martin.ads.orb_slam2_android;
import android.app.Activity;
import android.hardware.Camera;
import android.os.Bundle;
import android.os.Environment;
import android.util.Log;
import android.view.View;
import android.view.WindowManager;
import android.widget.TextView;
import org.opencv.android.CameraBridgeViewBase;
import org.opencv.android.JavaCameraView;
import org.opencv.android.OpenCVLoader;
import org.opencv.core.CvType;
import org.opencv.core.Mat;
public class MainActivity extends Activity implements CameraBridgeViewBase.CvCameraViewListener2 {
private static final String TAG = "MainActivity";
private Mat mRgba;
private Mat mIntermediateMat;
private Mat mGray;
private CameraBridgeViewBase mOpenCvCameraView;
private boolean initFinished;
private FPSUpdater fpsUpdater;
private TextView fpsText;
private int cursor;
// Used to load the 'native-lib' library on application startup.
static {
System.loadLibrary("opencv_java3");
System.loadLibrary("opencv_java");
System.loadLibrary("SLAM");
}
@Override
protected void onCreate(Bundle savedInstanceState) {
super.onCreate(savedInstanceState);
setContentView(R.layout.activity_main);
getWindow().addFlags(WindowManager.LayoutParams.FLAG_KEEP_SCREEN_ON);
mOpenCvCameraView = (CameraBridgeViewBase) findViewById(R.id.tutorial2_activity_surface_view);
mOpenCvCameraView.setVisibility(CameraBridgeViewBase.VISIBLE);
mOpenCvCameraView.setCvCameraViewListener(this);
mOpenCvCameraView.setClickable(true);
mOpenCvCameraView.setOnClickListener(new View.OnClickListener() {
@Override
public void onClick(View v) {
Camera camera=((JavaCameraView)mOpenCvCameraView).getCamera();
if (camera!=null) camera.autoFocus(null);
}
});
initFinished=false;
fpsText= (TextView) findViewById(R.id.fps_text);
fpsUpdater=new FPSUpdater() {
@Override
public void update(int fps) {
fpsText.setText("FPS: "+fps);
}
};
cursor=0;
}
@Override
public void onPause()
{
super.onPause();
if (mOpenCvCameraView != null)
mOpenCvCameraView.disableView();
}
@Override
public void onResume()
{
super.onResume();
Log.d(TAG, "OpenCV library found inside package. Using it!");
mOpenCvCameraView.enableView();
if (!initFinished) {
initSLAM(Environment.getExternalStorageDirectory().getPath()+"/SLAM/");
initFinished=true;
}
}
public void onDestroy() {
super.onDestroy();
if (mOpenCvCameraView != null)
mOpenCvCameraView.disableView();
}
public void onCameraViewStarted(int width, int height) {
mRgba = new Mat(height, width, CvType.CV_8UC4);
mIntermediateMat = new Mat(height, width, CvType.CV_8UC4);
mGray = new Mat(height, width, CvType.CV_8UC1);
}
public void onCameraViewStopped() {
mRgba.release();
mGray.release();
mIntermediateMat.release();
}
public Mat onCameraFrame(CameraBridgeViewBase.CvCameraViewFrame inputFrame) {
mRgba = inputFrame.rgba();
mGray = inputFrame.gray();
cursor=(cursor+1)%11;
if(cursor==1){
long currentTime=System.currentTimeMillis();
nativeProcessFrame(mGray.getNativeObjAddr(), mRgba.getNativeObjAddr());
final int fps=(int) (1000.0f/(System.currentTimeMillis()-currentTime));
runOnUiThread(new Runnable() {
@Override
public void run() {
fpsUpdater.update(fps);
}
});
}else nativeProcessFrame(mGray.getNativeObjAddr(), mRgba.getNativeObjAddr());
return mRgba;
}
public native void nativeProcessFrame(long matAddrGr, long matAddrRgba);
public native void initSLAM(String path);
}
在Samsung Exynos 4412(四核,2012年的老CPU了)上,分辨率640x480,能达到每秒4-7FPS,可以通过减小Vocabulary,减小特征点数来进行简单优化
项目地址(SEO)