feat:更改为ros启动
parent
0c3c948156
commit
efb5505fe2
|
@ -18,15 +18,15 @@ Examples/Monocular-Inertial/mono_inertial_tum_vi
|
|||
Examples/Stereo-Inertial/stereo_inertial_euroc
|
||||
Examples/Stereo-Inertial/stereo_inertial_tum_vi
|
||||
|
||||
Examples/ROS/ORB_SLAM3/Mono
|
||||
Examples/ROS/ORB_SLAM3/Mono_Inertial
|
||||
Examples/ROS/ORB_SLAM3/MonoAR
|
||||
Examples/ROS/ORB_SLAM3/RGBD
|
||||
Examples/ROS/ORB_SLAM3/Stereo
|
||||
Examples/ROS/ORB_SLAM3/Stereo_Inertial
|
||||
Examples/ROS/orb_slam3/Mono
|
||||
Examples/ROS/orb_slam3/Mono_Inertial
|
||||
Examples/ROS/orb_slam3/MonoAR
|
||||
Examples/ROS/orb_slam3/RGBD
|
||||
Examples/ROS/orb_slam3/Stereo
|
||||
Examples/ROS/orb_slam3/Stereo_Inertial
|
||||
|
||||
Examples/ROS/ORB_SLAM3/CMakeLists.txt.user
|
||||
Examples/ROS/ORB_SLAM3/build/
|
||||
Examples/ROS/orb_slam3/CMakeLists.txt.user
|
||||
Examples/ROS/orb_slam3/build/
|
||||
|
||||
Examples_old/RGB-D/rgbd_tum_old
|
||||
|
||||
|
|
|
@ -109,7 +109,8 @@ include/GeometricTools.h
|
|||
include/TwoViewReconstruction.h
|
||||
include/SerializationUtils.h
|
||||
include/Config.h
|
||||
include/Settings.h)
|
||||
include/Settings.h
|
||||
)
|
||||
|
||||
add_subdirectory(Thirdparty/g2o)
|
||||
|
||||
|
|
|
@ -1,94 +0,0 @@
|
|||
/**
|
||||
* This file is part of ORB-SLAM3
|
||||
*
|
||||
* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
|
||||
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
|
||||
*
|
||||
* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
|
||||
* License as published by the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
|
||||
* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along with ORB-SLAM3.
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
#include<iostream>
|
||||
#include<algorithm>
|
||||
#include<fstream>
|
||||
#include<chrono>
|
||||
|
||||
#include<ros/ros.h>
|
||||
#include <cv_bridge/cv_bridge.h>
|
||||
|
||||
#include<opencv2/core/core.hpp>
|
||||
|
||||
#include"../../../include/System.h"
|
||||
|
||||
using namespace std;
|
||||
|
||||
class ImageGrabber
|
||||
{
|
||||
public:
|
||||
ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){}
|
||||
|
||||
void GrabImage(const sensor_msgs::ImageConstPtr& msg);
|
||||
|
||||
ORB_SLAM3::System* mpSLAM;
|
||||
};
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "Mono");
|
||||
ros::start();
|
||||
|
||||
if(argc != 3)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Mono path_to_vocabulary path_to_settings" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Create SLAM system. It initializes all system threads and gets ready to process frames.
|
||||
ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true);
|
||||
|
||||
ImageGrabber igb(&SLAM);
|
||||
|
||||
ros::NodeHandle nodeHandler;
|
||||
ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb);
|
||||
|
||||
ros::spin();
|
||||
|
||||
// Stop all threads
|
||||
SLAM.Shutdown();
|
||||
|
||||
// Save camera trajectory
|
||||
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
|
||||
|
||||
ros::shutdown();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg)
|
||||
{
|
||||
// Copy the ros image message to cv::Mat.
|
||||
cv_bridge::CvImageConstPtr cv_ptr;
|
||||
try
|
||||
{
|
||||
cv_ptr = cv_bridge::toCvShare(msg);
|
||||
}
|
||||
catch (cv_bridge::Exception& e)
|
||||
{
|
||||
ROS_ERROR("cv_bridge exception: %s", e.what());
|
||||
return;
|
||||
}
|
||||
|
||||
mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
|
||||
}
|
||||
|
||||
|
|
@ -1,4 +1,4 @@
|
|||
cmake_minimum_required(VERSION 2.4.6)
|
||||
cmake_minimum_required(VERSION 3.15)
|
||||
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
|
||||
|
||||
rosbuild_init()
|
||||
|
@ -11,25 +11,26 @@ MESSAGE("Build type: " ${ROS_BUILD_TYPE})
|
|||
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
|
||||
|
||||
add_definitions(-w)
|
||||
# Check C++11 or C++0x support
|
||||
include(CheckCXXCompilerFlag)
|
||||
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
|
||||
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
|
||||
if(COMPILER_SUPPORTS_CXX14)
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
|
||||
add_definitions(-DCOMPILEDWITHC11)
|
||||
message(STATUS "Using flag -std=c++14.")
|
||||
elseif(COMPILER_SUPPORTS_CXX0X)
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
|
||||
add_definitions(-DCOMPILEDWITHC0X)
|
||||
message(STATUS "Using flag -std=c++0x.")
|
||||
else()
|
||||
message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
|
||||
endif()
|
||||
|
||||
LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
cv_bridge
|
||||
image_transport
|
||||
)
|
||||
|
||||
# 要保证整个工程的opencv版本一致,包括dbow,源码以及ros相关的
|
||||
# 3 4 都可以正常运行
|
||||
find_package(OpenCV 4.2)
|
||||
|
@ -40,13 +41,22 @@ find_package(OpenCV 4.2)
|
|||
find_package(Eigen3 3.1.0 REQUIRED)
|
||||
find_package(Pangolin REQUIRED)
|
||||
|
||||
catkin_package(
|
||||
INCLUDE_DIRS include
|
||||
LIBRARIES ${PROJECT_NAME}
|
||||
CATKIN_DEPENDS roscpp cv_bridge image_transport
|
||||
DEPENDS OpenCV EIGEN3 Pangolin
|
||||
)
|
||||
|
||||
include_directories(
|
||||
${PROJECT_SOURCE_DIR}
|
||||
${PROJECT_SOURCE_DIR}/../../../
|
||||
${PROJECT_SOURCE_DIR}/../../../include
|
||||
${PROJECT_SOURCE_DIR}/../../../include/CameraModels
|
||||
${PROJECT_SOURCE_DIR}/../../../Thirdparty/Sophus
|
||||
${Pangolin_INCLUDE_DIRS}
|
||||
include
|
||||
${catkin_INCLUDE_DIRS}
|
||||
${PROJECT_SOURCE_DIR}
|
||||
${PROJECT_SOURCE_DIR}/../../../
|
||||
${PROJECT_SOURCE_DIR}/../../../include
|
||||
${PROJECT_SOURCE_DIR}/../../../include/CameraModels
|
||||
${PROJECT_SOURCE_DIR}/../../../Thirdparty/Sophus
|
||||
${Pangolin_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
set(LIBS
|
||||
|
@ -60,13 +70,20 @@ ${PROJECT_SOURCE_DIR}/../../../lib/libORB_SLAM3.so
|
|||
)
|
||||
|
||||
# Node for monocular camera
|
||||
rosbuild_add_executable(Mono
|
||||
src/ros_mono.cc
|
||||
add_executable(Mono src/ros_mono.cc)
|
||||
target_link_libraries(Mono
|
||||
${LIBS}
|
||||
${catkin_LIBRARIES}
|
||||
)
|
||||
|
||||
target_link_libraries(Mono
|
||||
${LIBS}
|
||||
)
|
||||
## Node for monocular camera
|
||||
#rosbuild_add_executable(Mono
|
||||
#src/ros_mono.cc
|
||||
#)
|
||||
#
|
||||
#target_link_libraries(Mono
|
||||
#${LIBS}
|
||||
#)
|
||||
|
||||
# Node for monocular camera (Augmented Reality Demo)
|
||||
# 由于里面代码没有将cv::mat 改成 SOPUS的暂时注释掉,不然会报错
|
||||
|
@ -81,37 +98,37 @@ ${LIBS}
|
|||
# )
|
||||
|
||||
# Node for stereo camera
|
||||
rosbuild_add_executable(Stereo
|
||||
src/ros_stereo.cc
|
||||
)
|
||||
|
||||
target_link_libraries(Stereo
|
||||
${LIBS}
|
||||
)
|
||||
|
||||
# Node for RGB-D camera
|
||||
rosbuild_add_executable(RGBD
|
||||
src/ros_rgbd.cc
|
||||
)
|
||||
|
||||
target_link_libraries(RGBD
|
||||
${LIBS}
|
||||
)
|
||||
|
||||
# Node for monocular-inertial camera
|
||||
rosbuild_add_executable(Mono_Inertial
|
||||
src/ros_mono_inertial.cc
|
||||
)
|
||||
|
||||
target_link_libraries(Mono_Inertial
|
||||
${LIBS}
|
||||
)
|
||||
|
||||
# Node for stereo-inertial camera
|
||||
rosbuild_add_executable(Stereo_Inertial
|
||||
src/ros_stereo_inertial.cc
|
||||
)
|
||||
|
||||
target_link_libraries(Stereo_Inertial
|
||||
${LIBS}
|
||||
)
|
||||
#rosbuild_add_executable(Stereo
|
||||
#src/ros_stereo.cc
|
||||
#)
|
||||
#
|
||||
#target_link_libraries(Stereo
|
||||
#${LIBS}
|
||||
#)
|
||||
#
|
||||
## Node for RGB-D camera
|
||||
#rosbuild_add_executable(RGBD
|
||||
#src/ros_rgbd.cc
|
||||
#)
|
||||
#
|
||||
#target_link_libraries(RGBD
|
||||
#${LIBS}
|
||||
#)
|
||||
#
|
||||
## Node for monocular-inertial camera
|
||||
#rosbuild_add_executable(Mono_Inertial
|
||||
#src/ros_mono_inertial.cc
|
||||
#)
|
||||
#
|
||||
#target_link_libraries(Mono_Inertial
|
||||
#${LIBS}
|
||||
#)
|
||||
#
|
||||
## Node for stereo-inertial camera
|
||||
#rosbuild_add_executable(Stereo_Inertial
|
||||
#src/ros_stereo_inertial.cc
|
||||
#)
|
||||
#
|
||||
#target_link_libraries(Stereo_Inertial
|
||||
#${LIBS}
|
||||
#)
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,32 @@
|
|||
// 确保只包含一次头文件
|
||||
#pragma once
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <sensor_msgs/Image.h>
|
||||
#include "../../../../include/System.h" // 确保路径正确
|
||||
|
||||
namespace autolabor
|
||||
{
|
||||
class ImageGrabber
|
||||
{
|
||||
public:
|
||||
ImageGrabber(ORB_SLAM3::System* pSLAM);
|
||||
void GrabImage(const sensor_msgs::ImageConstPtr& msg);
|
||||
|
||||
private:
|
||||
ORB_SLAM3::System* mpSLAM;
|
||||
};
|
||||
|
||||
class OrbSlam3Node
|
||||
{
|
||||
public:
|
||||
OrbSlam3Node();
|
||||
~OrbSlam3Node();
|
||||
|
||||
void run();
|
||||
|
||||
private:
|
||||
std::string vocabulary_path_, settings_path_, image_topic_, traj_file_;
|
||||
};
|
||||
|
||||
}
|
|
@ -0,0 +1,25 @@
|
|||
<launch>
|
||||
|
||||
<!-- 相机节点 -->
|
||||
<node pkg="cv_camera" type="cv_camera_node" name="camera" output="screen">
|
||||
<param name="flip_image" value="false" />
|
||||
<param name="device_path" value="/dev/v4l/by-path/platform-3610000.xhci-usb-0:2.3:1.0-video-index0" />
|
||||
<param name="image_width" value="1280" />
|
||||
<param name="image_height" value="720" />
|
||||
<param name="rate" value="30"/>
|
||||
<param name="camera_info_url" value="file://$(find cv_camera)/calibrationdata/1280x720.yaml"/>
|
||||
<param name="rescale_camera_info" value="false"/>
|
||||
</node>
|
||||
|
||||
|
||||
<!-- ORBSLAM3节点 -->
|
||||
<node name="orb_slam3_mono" pkg="orb_slam3" type="Mono" output="screen">
|
||||
<param name="image_topic" value="/camera/image_raw"/> <!-- 定义相机话题 -->
|
||||
<param name="config_file" value="$(find orb_slam3)/config/camera1280.yaml"/> <!-- 定义ORB_SLAM3的配置文件路径 -->
|
||||
<param name="vocab_file" value="$(find orb_slam3)/Vocabulary/ORBvoc.txt"/> <!-- 定义ORB_SLAM3的词典文件路径 -->
|
||||
<param name="traj_file" value="KeyFrameTrajectory.txt"/> <!-- 定义轨迹文件路径 -->
|
||||
</node>
|
||||
|
||||
|
||||
|
||||
</launch>
|
|
@ -1,6 +1,6 @@
|
|||
<package>
|
||||
<description brief="ORB_SLAM3">
|
||||
ORB_SLAM3
|
||||
<description brief="orb_slam3">
|
||||
orb_slam3
|
||||
</description>
|
||||
<author>Carlos Campos, Richard Elvira, Juan J. Gomez, Jose M.M. Montiel, Juan D. Tardos</author>
|
||||
<license>GPLv3</license>
|
|
@ -0,0 +1,22 @@
|
|||
<package format="2">
|
||||
<name>orb_slam3</name>
|
||||
<version>0.0.1</version>
|
||||
<description>The description of my package</description>
|
||||
|
||||
<maintainer email="autolabor@autolabor.com.cn">Autolabor</maintainer>
|
||||
<license>BSD</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<depend>roscpp</depend>
|
||||
<depend>std_msgs</depend>
|
||||
<depend>sensor_msgs</depend>
|
||||
<depend>cv_bridge</depend>
|
||||
<depend>image_transport</depend>
|
||||
<depend>eigen_conversions</depend>
|
||||
<depend>tf</depend>
|
||||
|
||||
<export>
|
||||
<!-- Other tools can go here -->
|
||||
</export>
|
||||
</package>
|
|
@ -59,7 +59,7 @@ int main(int argc, char **argv)
|
|||
|
||||
if(argc != 3)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Mono path_to_vocabulary path_to_settings" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 Mono path_to_vocabulary path_to_settings" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
|
@ -0,0 +1,94 @@
|
|||
/**
|
||||
* This file is part of ORB-SLAM3
|
||||
*
|
||||
* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
|
||||
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
|
||||
*
|
||||
* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
|
||||
* License as published by the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
|
||||
* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along with ORB-SLAM3.
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
#include "ros_mono.h"
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <chrono>
|
||||
#include <cv_bridge/cv_bridge.h>
|
||||
#include <opencv2/core/core.hpp>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace autolabor
|
||||
{
|
||||
ImageGrabber::ImageGrabber(ORB_SLAM3::System* pSLAM) : mpSLAM(pSLAM) {}
|
||||
|
||||
void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg)
|
||||
{
|
||||
// Copy the ros image message to cv::Mat.
|
||||
cv_bridge::CvImageConstPtr cv_ptr;
|
||||
try
|
||||
{
|
||||
cv_ptr = cv_bridge::toCvShare(msg);
|
||||
}
|
||||
catch (cv_bridge::Exception& e)
|
||||
{
|
||||
ROS_ERROR("cv_bridge exception: %s", e.what());
|
||||
return;
|
||||
}
|
||||
|
||||
mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
|
||||
}
|
||||
|
||||
OrbSlam3Node::OrbSlam3Node() {
|
||||
ROS_INFO("ORBSLAM3 is running...");
|
||||
}
|
||||
|
||||
OrbSlam3Node::~OrbSlam3Node(){}
|
||||
|
||||
void OrbSlam3Node::run()
|
||||
{
|
||||
ros::NodeHandle nh;
|
||||
ros::NodeHandle private_nh("~");
|
||||
|
||||
private_nh.param<std::string>("vocab_file", vocabulary_path_, "");
|
||||
private_nh.param<std::string>("config_file", settings_path_, "");
|
||||
private_nh.param<std::string>("image_topic", image_topic_, "/camera/image_raw");
|
||||
private_nh.param<std::string>("traj_file", traj_file_, "KeyFrameTrajectory.txt");
|
||||
|
||||
if (vocabulary_path_.empty() || settings_path_.empty())
|
||||
{
|
||||
ROS_ERROR("Missing vocab_file or config_file parameters.");
|
||||
ros::shutdown();
|
||||
return;
|
||||
}
|
||||
|
||||
ORB_SLAM3::System SLAM(vocabulary_path_, settings_path_, ORB_SLAM3::System::MONOCULAR, true);
|
||||
ImageGrabber igb(&SLAM);
|
||||
|
||||
ros::Subscriber sub = nh.subscribe(image_topic_, 1, &ImageGrabber::GrabImage, &igb);
|
||||
|
||||
ros::spin();
|
||||
|
||||
SLAM.Shutdown();
|
||||
SLAM.SaveKeyFrameTrajectoryTUM(traj_file_);
|
||||
|
||||
ros::shutdown();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "orb_slam3");
|
||||
autolabor::OrbSlam3Node node;
|
||||
node.run();
|
||||
return 0;
|
||||
}
|
|
@ -75,7 +75,7 @@ int main(int argc, char **argv)
|
|||
bool bEqual = false;
|
||||
if(argc < 3 || argc > 4)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Mono_Inertial path_to_vocabulary path_to_settings [do_equalize]" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 Mono_Inertial path_to_vocabulary path_to_settings [do_equalize]" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
|
@ -51,7 +51,7 @@ int main(int argc, char **argv)
|
|||
|
||||
if(argc != 3)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 RGBD path_to_vocabulary path_to_settings" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 RGBD path_to_vocabulary path_to_settings" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
|
@ -53,7 +53,7 @@ int main(int argc, char **argv)
|
|||
|
||||
if(argc != 4)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Stereo path_to_vocabulary path_to_settings do_rectify" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 Stereo path_to_vocabulary path_to_settings do_rectify" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
|
@ -79,7 +79,7 @@ int main(int argc, char **argv)
|
|||
bool bEqual = false;
|
||||
if(argc < 4 || argc > 5)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Stereo_Inertial path_to_vocabulary path_to_settings do_rectify [do_equalize]" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 Stereo_Inertial path_to_vocabulary path_to_settings do_rectify [do_equalize]" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
|
@ -188,7 +188,7 @@ int main(int argc, char **argv)
|
|||
|
||||
while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni])
|
||||
{
|
||||
// vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[first_imu],vGyro[first_imu],vTimestampsImu[first_imu]));
|
||||
// vImuMeas.push_back(orb_slam3::IMU::Point(vAcc[first_imu],vGyro[first_imu],vTimestampsImu[first_imu]));
|
||||
vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z,
|
||||
vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
|
||||
vTimestampsImu[seq][first_imu[seq]]));
|
||||
|
|
|
@ -59,7 +59,7 @@ int main(int argc, char **argv)
|
|||
|
||||
if(argc != 3)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Mono path_to_vocabulary path_to_settings" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 Mono path_to_vocabulary path_to_settings" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -48,7 +48,7 @@ int main(int argc, char **argv)
|
|||
|
||||
if(argc != 3)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Mono path_to_vocabulary path_to_settings" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 Mono path_to_vocabulary path_to_settings" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -75,7 +75,7 @@ int main(int argc, char **argv)
|
|||
bool bEqual = false;
|
||||
if(argc < 3 || argc > 4)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Mono_Inertial path_to_vocabulary path_to_settings [do_equalize]" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 Mono_Inertial path_to_vocabulary path_to_settings [do_equalize]" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -51,7 +51,7 @@ int main(int argc, char **argv)
|
|||
|
||||
if(argc != 3)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 RGBD path_to_vocabulary path_to_settings" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 RGBD path_to_vocabulary path_to_settings" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -53,7 +53,7 @@ int main(int argc, char **argv)
|
|||
|
||||
if(argc != 4)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Stereo path_to_vocabulary path_to_settings do_rectify" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 Stereo path_to_vocabulary path_to_settings do_rectify" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -79,7 +79,7 @@ int main(int argc, char **argv)
|
|||
bool bEqual = false;
|
||||
if(argc < 4 || argc > 5)
|
||||
{
|
||||
cerr << endl << "Usage: rosrun ORB_SLAM3 Stereo_Inertial path_to_vocabulary path_to_settings do_rectify [do_equalize]" << endl;
|
||||
cerr << endl << "Usage: rosrun orb_slam3 Stereo_Inertial path_to_vocabulary path_to_settings do_rectify [do_equalize]" << endl;
|
||||
ros::shutdown();
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -188,7 +188,7 @@ int main(int argc, char **argv)
|
|||
|
||||
while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni])
|
||||
{
|
||||
// vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[first_imu],vGyro[first_imu],vTimestampsImu[first_imu]));
|
||||
// vImuMeas.push_back(orb_slam3::IMU::Point(vAcc[first_imu],vGyro[first_imu],vTimestampsImu[first_imu]));
|
||||
vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z,
|
||||
vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
|
||||
vTimestampsImu[seq][first_imu[seq]]));
|
||||
|
|
|
@ -169,6 +169,6 @@ protected:
|
|||
|
||||
}; // class Atlas
|
||||
|
||||
} // namespace ORB_SLAM3
|
||||
} // namespace orb_slam3
|
||||
|
||||
#endif // ATLAS_H
|
||||
|
|
|
@ -203,6 +203,6 @@ protected:
|
|||
|
||||
};
|
||||
|
||||
} //namespace ORB_SLAM3
|
||||
} //namespace orb_slam3
|
||||
|
||||
#endif // MAP_H
|
||||
|
|
|
@ -101,6 +101,6 @@ public:
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
|
||||
};
|
||||
|
||||
} //namespace ORB_SLAM3
|
||||
} //namespace orb_slam3
|
||||
|
||||
#endif // OPTIMIZER_H
|
||||
|
|
|
@ -161,6 +161,6 @@ void serializeVectorKeyPoints(Archive& ar, const std::vector<cv::KeyPoint>& vKP,
|
|||
}
|
||||
}
|
||||
|
||||
} // namespace ORB_SLAM3
|
||||
} // namespace orb_slam3
|
||||
|
||||
#endif // SERIALIZATION_UTILS_H
|
||||
|
|
|
@ -452,4 +452,4 @@ map<long unsigned int, KeyFrame *> Atlas::GetAtlasKeyframes()
|
|||
return mpIdKFs;
|
||||
}
|
||||
|
||||
} // namespace ORB_SLAM3
|
||||
} // namespace orb_slam3
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include <boost/serialization/export.hpp>
|
||||
|
||||
// BOOST_CLASS_EXPORT_IMPLEMENT(ORB_SLAM3::KannalaBrandt8)
|
||||
// BOOST_CLASS_EXPORT_IMPLEMENT(orb_slam3::KannalaBrandt8)
|
||||
|
||||
namespace ORB_SLAM3
|
||||
{
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include <boost/serialization/export.hpp>
|
||||
|
||||
// BOOST_CLASS_EXPORT_IMPLEMENT(ORB_SLAM3::Pinhole)
|
||||
// BOOST_CLASS_EXPORT_IMPLEMENT(orb_slam3::Pinhole)
|
||||
|
||||
namespace ORB_SLAM3
|
||||
{
|
||||
|
|
|
@ -1742,4 +1742,4 @@ void MLPnPsolver::mlpnpJacs(const point_t &pt, const Eigen::Vector3d &nullspace_
|
|||
jacs(1, 4) = s2 * t65 - t14 * t101 * t167 * t212 * (1.0 / 2.0);
|
||||
jacs(1, 5) = s3 * t65 - t14 * t101 * t167 * t216 * (1.0 / 2.0);
|
||||
}
|
||||
} // End namespace ORB_SLAM3
|
||||
} // End namespace orb_slam3
|
||||
|
|
|
@ -541,4 +541,4 @@ void Map::PostLoad(KeyFrameDatabase *pKFDB, ORBVocabulary *pORBVoc /*, map<long
|
|||
mvpBackupMapPoints.clear();
|
||||
}
|
||||
|
||||
} // namespace ORB_SLAM3
|
||||
} // namespace orb_slam3
|
||||
|
|
|
@ -984,7 +984,7 @@ void System::SaveTrajectoryEuRoC(const string &filename, Map* pMap)
|
|||
|
||||
// For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag
|
||||
// which is true when tracking failed (lbL).
|
||||
list<ORB_SLAM3::KeyFrame*>::iterator lRit = mpTracker->mlpReferences.begin();
|
||||
list<orb_slam3::KeyFrame*>::iterator lRit = mpTracker->mlpReferences.begin();
|
||||
list<double>::iterator lT = mpTracker->mlFrameTimes.begin();
|
||||
list<bool>::iterator lbL = mpTracker->mlbLost.begin();
|
||||
|
||||
|
@ -1235,11 +1235,11 @@ void System::SaveKeyFrameTrajectoryEuRoC(const string &filename, Map* pMap)
|
|||
|
||||
// For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag
|
||||
// which is true when tracking failed (lbL).
|
||||
list<ORB_SLAM3::KeyFrame*>::iterator lRit = mpTracker->mlpReferences.begin();
|
||||
list<orb_slam3::KeyFrame*>::iterator lRit = mpTracker->mlpReferences.begin();
|
||||
list<double>::iterator lT = mpTracker->mlFrameTimes.begin();
|
||||
for(list<cv::Mat>::iterator lit=mpTracker->mlRelativeFramePoses.begin(), lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++)
|
||||
{
|
||||
ORB_SLAM3::KeyFrame* pKF = *lRit;
|
||||
orb_slam3::KeyFrame* pKF = *lRit;
|
||||
|
||||
cv::Mat Trw = cv::Mat::eye(4,4,CV_32F);
|
||||
|
||||
|
|
Loading…
Reference in New Issue