GithubHelp home page GithubHelp logo

sptam's Introduction

S-PTAM is a Stereo SLAM system able to compute the camera trajectory in real-time. It heavily exploits the parallel nature of the SLAM problem, separating the time-constrained pose estimation from less pressing matters such as map building and refinement tasks. On the other hand, the stereo setting allows to reconstruct a metric 3D map for each frame of stereo images, improving the accuracy of the mapping process with respect to monocular SLAM and avoiding the well-known bootstrapping problem. Also, the real scale of the environment is an essential feature for robots which have to interact with their surrounding workspace.

IMAGE ALT TEXT HERE
(Click the image to redirect to S-PTAM video)

Related Publications:

[1] Taihú Pire,Thomas Fischer, Gastón Castro, Pablo De Cristóforis, Javier Civera and Julio Jacobo Berlles. S-PTAM: Stereo Parallel Tracking and Mapping Robotics and Autonomous Systems, 2017.

[2] Taihú Pire, Thomas Fischer, Javier Civera, Pablo De Cristóforis and Julio Jacobo Berlles.
Stereo Parallel Tracking and Mapping for Robot Localization
Proc. of The International Conference on Intelligent Robots and Systems (IROS), Hamburg, Germany, 2015.

Table of Contents

License

S-PTAM is released under GPLv3 license.

For a closed-source version of S-PTAM for commercial purposes, please contact the authors.

If you use S-PTAM in an academic work, please cite:

@article{pire2017sptam,
          title = {{S-PTAM: Stereo Parallel Tracking and Mapping}},
          author = {Pire, Taih{\'u} and Fischer, Thomas and Castro, Gast{\'o}n and De Crist{\'o}foris, Pablo and Civera, Javier and Jacobo Berlles, Julio},
          journal = {Robotics and Autonomous Systems (RAS)},
          volume = {93},
          pages = {27 -- 42},
          year = {2017},
          issn = {0921-8890},
          doi = {10.1016/j.robot.2017.03.019}
}

@inproceedings{pire2015sptam,
          title={{Stereo Parallel Tracking and Mapping for robot localization}},
          author={Pire, Taih{\'u} and Fischer, Thomas and Civera, Javier and De Crist{\'o}foris, Pablo and Jacobo berlles, Julio},
          booktitle={Proc. of the International Conference on Intelligent Robots and Systems (IROS)},
          pages = {1373--1378},
          year={2015},
          month = {September},
          doi = {10.1109/IROS.2015.7353546}
}

Disclaimer

This site and the code provided here are under active development. Even though we try to only release working high quality code, this version might still contain some issues. Please use it with caution.

Dependencies

ROS

We have tested S-PTAM in Ubuntu 16.04 with ROS Kinetic.

To install ROS (Kinetic) use the following command:

sudo apt-get install ros-kinetic-desktop

SuiteSparse

Suitespare is a dependency, so it needs to be installed

sudo apt-get install libsuitesparse-dev

ros-utils

Install our ros-utils library from the source code provided in

git clone [email protected]:lrse/ros-utils.git

g2o

Install g2o library from the source code provided in

git clone [email protected]:RainerKuemmerle/g2o.git

Tested until commit 4b9c2f5b68d14ad479457b18c5a2a0bce1541a90

git checkout 4b9c2f5b68d14ad479457b18c5a2a0bce1541a90

mkdir build && cd build
cmake ..
make 
sudo make install

Loop Closure dependencies

Only required when USE_LOOPCLOSURE flag is defined.

DBoW2 vocabularies are available through a git submodule at the bow_voc directory

git submodule update --init --recursive

DLib

Install DLib library from source code

git clone [email protected]:dorian3d/DLib.git

Tested until commit 70089a38056e8aebd5a2ebacbcb67d3751433f32

git checkout 70089a38056e8aebd5a2ebacbcb67d3751433f32

DBoW2

Install DBoW2 library from source code

git clone [email protected]:dorian3d/DBoW2.git

Tested until commit 82401cad2cfe7aa28ee6f6afb01ce3ffa0f59b44

git checkout 82401cad2cfe7aa28ee6f6afb01ce3ffa0f59b44

DLoopDetector

Install DLoopDetector library from source code

git clone [email protected]:dorian3d/DLoopDetector.git

Tested until commit 8e62f8ae84d583d9ab67796f779272b0850571ce

git checkout 8e62f8ae84d583d9ab67796f779272b0850571ce

OpenGV

Install OpenGV library from source code

git clone [email protected]:laurentkneip/opengv.git

Tested until commit 2e2d21917fd2fb75f2134e6d5be7a2536cbc7eb1

git checkout 2e2d21917fd2fb75f2134e6d5be7a2536cbc7eb1

Installation

git clone [email protected]:lrse/sptam.git

ROS Package

ROS Compilation

catkin_make --pkg sptam -DCMAKE_BUILD_TYPE=RelWithDebInfo -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON

To activate Loop Closing capabilities (requires DBoW2 and OpenGV dependencies).

catkin_make --pkg sptam -DCMAKE_BUILD_TYPE=RelWithDebInfo -DUSE_LOOPCLOSURE=ON -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON

For more information about compilation flags see CMAKE flags section.

Tutorials

We provide some examples of how to run S-PTAM with the most popular stereo datasets

KITTI dataset

  1. Download the KITTI rosbag kitti_00.bag provided in KITTI rosbag files

  2. Uncompress the dataset

    rosbag decompress kitti_00.bag

  3. Set use_sim_time ros variable true

    rosparam set use_sim_time true

  4. Play the dataset

    rosbag play --clock kitti_00.bag

    (When S-PTAM run with the flag SHOW_TRACKED_FRAMES=ON the performance is reduced notoriusly).

  5. Run sptam using the kitti.launch

    roslaunch sptam kitti.launch

EuRoc MAV dataset

  1. Download the EuRoc rosbag Machine Hall 01 provided in EuRoc MAV Web Page

  2. Add left and right camera_info messages in the rosbag

    In S-PTAM package we provide a script euroc_add_camera_info.py to add left and right sensor_msgs/CameraInfo messages to the EuRoc MAV rosbags.

    python sptam_directory/scripts/euroc_add_camera_info.py MH_01_easy.bag /mav0/cam0/sensor.yaml /mav0/cam1/sensor.yaml

  3. Set use_sim_time ros variable true

    rosparam set use_sim_time true

  4. Play the dataset

    rosbag play --clock MH_01_easy_with_camera_info.bag -s 50

  5. Run sptam using the euroc.launch

    roslaunch sptam euroc.launch

MIT Stata Center dataset

  1. Download the MIT Stata Center rosbag 2012-01-27-07-37-01.bag provided in MIT Stata Center Web Page

  2. Set use_sim_time ros variable true

    rosparam set use_sim_time true

  3. Play the dataset

    rosbag play --clock 2012-01-27-07-37-01.bag -s 302.5 -u 87

    (Here we are running the part 3 of the sequence where ground-truth was provided that is why the bag file start from a different timestamp)

  4. Run sptam using the mit.launch

    roslaunch sptam mit.launch

Indoor Level 7 S-Block dataset

  1. Download the Level7 rosbag level07_20_05_12_trunc.bag (3747 Frame Subset) provided in Indoor Level 7 S-Block Dataset Web Page

  2. Set use_sim_time ros variable true

    rosparam set use_sim_time true

  3. Play the dataset

    rosbag play --clock level7_truncated.bag

  4. Run sptam using the level7.launch

    roslaunch sptam level7.launch

Node Information

Subscribed Topics

Camera topics should provide undistorted and stereo-rectified images. Consider using the image_proc node.

/stereo/left/image_rect (sensor_msgs/Image)
          Undistorted and stereo-rectified image stream from the left camera.

/stereo/left/camera_info (sensor_msgs/CameraInfo)
          Left camera metadata.

/stereo/right/image_rect (sensor_msgs/Image)
          Undistorted and stereo-rectified image stream from the right camera.

/stereo/right/camera_info (sensor_msgs/CameraInfo)
          Right camera metadata.

Published Topics

global_map (sensor_msgs/PointCloud2)
          Global sparse mapped point cloud used for tracking.

local_map (sensor_msgs/PointCloud2)
          Local map which contains points that are highly probable to be observed by the current camera.

tracked_map (sensor_msgs/PointCloud2)
          Points tracked by the current camera.

keyframes (nav_msgs/Path)
          All the keyframes generated along the whole trajectory.

local_keyframes (nav_msgs/Path)
          Keyframes used to obtain the local map (local_map).

camera_pose (geometry_msgs::PoseWithCovarianceStamped)
          Current camera pose computed after tracking.

ROS Parameters

~use_prediction (bool, default: false)
          Replace decay velocity motion model by a pose prediction that will be read from the TF tree. If using this, please make sure you have also set the correct prediction_frame option.

~approximate_sync: (bool, default: false)
          Whether to use approximate synchronization for stereo frames. Set to true if the left and right Cameras do not produce identical synchronized timestamps for a matching pair of frames.

~publish_transform: (bool, default: true)
          Whether to publish the transformation associated to the newly computed camera pose to the TF tree.

~publish_on_fail: (bool, default: false)
          Whether to publish pose and tf updates when the tracking fails.

~prediction_frame (string, default: "odom")
          Reference frame for predictions in the TF tree. If use_prediction option is enabled, some source outside of the S-PTAM node is required to publish the transformation between prediction_frame and camera_frame.

~base_frame: (string, default: "base_link")
          Reference frame for the robot. This is the frame whose pose will be published on the /robot/pose topic and the TF tree (if tf publication is enabled).

~camera_frame: (string, default: "camera")
          Reference frame for the left camera, used to get left camera pose from tf.

~map_frame: (string, default: "map")
          Name for the published map frame.

~reference_frame: (string, default: "base_link")
          This is the frame that the map frame will be aligned to when initializing S-PTAM. In other word, the initial pose of the reference_frame defines the map origin.

Involved Coordinates Systems

Example of common used coordinate systems. Here, reference_frame follows the base_frame axis representation.

The camera correction computed by S-PTAM is applied between the map_frame and the base_frame (pink doted line).

The camera correction computed by S-PTAM is applied between the map_frame and the prediction_frame (pink doted line).

CMAKE flags

SINGLE_THREAD=([ON|OFF], default: OFF)
          Make to S-PTAM runs tracking and mapping tasks in single thread mode, this is, tracking and mapping runs in only one thread. This options could be useful for debugging. Set it OFF to improve S-PTAM performance.

SHOW_TRACKED_FRAMES=([ON|OFF], default: OFF)
          Show the tracked frames by S-PTAM. Set it OFF to improve S-PTAM performance.

SHOW_PROFILING=([ON|OFF], default: OFF)
          Create a log file of S-PTAM. This log file can be used to depure S-PTAM. Set it OFF to improve S-PTAM performance.

PARALLELIZE=([ON|OFF], default: ON)
          Make to S-PTAM uses parallelize code when is possible. Set it ON to improve S-PTAM performance.

USE_LOOPCLOSURE=([ON|OFF], default: OFF)
          Activates loop closing capabilities of S-PTAM. Requires DBoW2 and OpenGV dependencies. Set it OFF to use S-PTAM without loop detection.

S-PTAM Parameters

~FeatureDetector/Name: (string, default: "GFTT")
          Follows OpenCV convention.

~DescriptorExtractor/Name: (string, default: "BRIEF")
          Follows OpenCV convention.

~DescriptorMatcher/Name: 'BruteForce-Hamming'
          Follows OpenCV convention.

~DescriptorMatcher/crossCheck: false
          Follows OpenCV convention.

~MatchingCellSize: (int, default: 15)
          To match the map points with images features, each frame is divided in squares cells of fixed size. MatchingCellSize define the size of each cell.

~MatchingNeighborhood: (int, default: 2)
         Cells' neighborhood around the point.

~MatchingDistance: (double, default: 25.0)
          Descriptor distance. Use a non-fractional value when hamming distance is used. Use Fractional value when L1/L2 norm is used.

~EpipolarDistance: (double, default: 0.0)
          Distance in rows from the epipolar line used to find stereo matches.

~FrustumNearPlaneDist: (double, default: 0.1)
          Frustum (Field of View) near plane.

~FrustumFarPlaneDist: (double, default: 1000.0)
          Frustum (Field of View) far plane.

~BundleAdjustmentActiveKeyframes: (int, default: 10)
          Number of keyframes to be adjusted by the local bundle adjustment (LBA) in the local mapping.

~minimumTrackedPointsRatio: (int, default: 0.9)
          Ratio of tracked points that the current frame should have with respect to the closest keyframe to be selected as a keyframe used by the keyframe selection strategy.

Standalone

In standalone directory, we include an example of code that does not use ROS framework (but it still depends of some ROS libraries). It can be useful for debugging or for those who are not familiar with ROS.

Compilation

On standalone directory do:

  1. mkdir build

  2. cd build

  3. cmake .. -DCMAKE_BUILD_TYPE=Release -DSHOW_TRACKED_FRAMES=ON -DUSE_LOOPCLOSURE=ON -DSHOW_PROFILING=ON

Run

Download the KITTI gray scale stereo images from KITTI dataset

./sptam-stereo ../../sptam/configurationFiles/kitti.yaml ../../sptam/configurationFiles/kitti_cam_00_to_02_13_to_21.yaml <KITTI_dataset_path>/00/image_0/ <KITTI_dataset_path>/00/image_1/ dir --timestamps <KITTI_dataset_path>/00/times.txt

Note: in order to use the Loop Closure module in standalone version, you must indicate the vocabulary location path in kitti.yaml configuration file.

sptam's People

Contributors

aswinthomas avatar isidroas avatar taihup avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

sptam's Issues

kitti rosbag doesn't exist

Hi, I'm new using S-PTAM. I installed and tested it using mit and EuRoc Mav Datasets. However I'd like to test it using kitti datset but rosbag isn't available. Could you give me some advice, please? I've seen some scripts to convert kiiti dataset to rosbag but I don't know if that is the right way (or which one could work). Moreover I have a dataset that was taken with our stereo camera system and I'd like to test it too, but I don't know how to set a .launch file for our dataset, could you give me some advice, please?

Thaks a lot for your help!

SPtam crashing during runtime

Configuration:
OS: Ubuntu 14.04
ROS distro: Indigo
Camera:Logitech c270
Camera Driver: uvc_camera
Laptop processor: corei7

I was trying to run sptam on my webcam pair to get odometry data.
While running the launch file I get this warning recursively . There is no window opened till I move the camera.

sidd@sidd-K55VM:~/catkin_ws$ roslaunch sptam lau.launch
... logging to /home/sidd/.ros/log/b87c8c84-f9c9-11e5-bb92-94dbc9b19dba/roslaunch-sidd-K55VM-10100.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://sidd-K55VM:44428/

SUMMARY
========

PARAMETERS
 * /left_decimator/height: 860
 * /left_decimator/width: 1177
 * /left_decimator/x_offset: 52
 * /left_decimator/y_offset: 51
 * /right_decimator/height: 860
 * /right_decimator/width: 1177
 * /right_decimator/x_offset: 52
 * /right_decimator/y_offset: 51
 * /rosdistro: indigo
 * /rosversion: 1.11.16
 * /sptam/DescriptorExtractor/BytesLength: 32
 * /sptam/DescriptorExtractor/Name: BRIEF
 * /sptam/DescriptorMatcher/Name: BruteForce-Hamming
 * /sptam/DescriptorMatcher/crossCheck: False
 * /sptam/EpipolarDistance: 0
 * /sptam/FeatureDetector/Name: GFTT
 * /sptam/FeatureDetector/minDistance: 15.0
 * /sptam/FeatureDetector/nfeatures: 1000
 * /sptam/FeatureDetector/qualityLevel: 0.01
 * /sptam/FeatureDetector/useHarrisDetector: False
 * /sptam/FramesBetweenKeyFrames: 0
 * /sptam/FrustumFarPlaneDist: 10000
 * /sptam/FrustumNearPlaneDist: 0.1
 * /sptam/KeyFrameDistance: 0
 * /sptam/MatchingCellSize: 30
 * /sptam/MatchingDistance: 25
 * /sptam/MatchingNeighborhood: 1
 * /sptam/approximate_sync: True
 * /sptam/baseline: 0.071
 * /sptam/camera_frame: camera_1
 * /sptam/camera_matrix: cv::Mat
 * /sptam/cols: 3
 * /sptam/data: [718.856, 0, 607....
 * /sptam/dt: d
 * /sptam/image_height: 480
 * /sptam/image_width: 640
 * /sptam/odom_frame: odom_combined
 * /sptam/rows: 3
 * /sptam/use_odometry: False

NODES
/stereo/
    stereo_image_proc (stereo_image_proc/stereo_image_proc)
  /
    camera_broadcaster (tf/static_transform_publisher)
    left_decimator (nodelet/nodelet)
    right_decimator (nodelet/nodelet)
    sptam (sptam/sptam_node)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[stereo/stereo_image_proc-1]: started with pid [10118]
process[left_decimator-2]: started with pid [10119]
process[right_decimator-3]: started with pid [10120]
process[camera_broadcaster-4]: started with pid [10121]
process[sptam-5]: started with pid [10138]
[ INFO] [1459708372.712452032]: S-PTAM node running...
detector: GFTT
  minDistance: 15
  nfeatures: 1000
  qualityLevel: 0.01
  useHarrisDetector: 0
extractor: BRIEF
matcher: BruteForce-Hamming
  crossCheck: 0
[ INFO] [1459708373.133859507]: sptam node initialized
[ INFO] [1459708374.761461761]: dt: 0
[ INFO] [1459708374.761563392]: init calib
[ INFO] [1459708374.761623424]: tx: -368.944 fx: 805.413 baseline: -0.458081
[ INFO] [1459708374.761892478]: baseline: 0.386787
[ INFO] [1459708374.787497848]: Trying to intialize map...
No matches found for triangulation
[ INFO] [1459708374.820623114]: dt: 0
[ INFO] [1459708374.838212296]: Trying to intialize map...
No matches found for triangulation
[ INFO] [1459708374.891819060]: dt: 0
[ INFO] [1459708374.913047833]: Trying to intialize map...
No matches found for triangulation
.
.
.

Not sure if my calibration files are right.

Distance between 2 camera is 7cm. I tried to enter it in calibration file but I think it doesn't load it.
The following command was added in launch file.

cam_yaml.txt

my_yaml.txt

This is the launch file vaguely based on level7.launch
lau_launch.txt

When I move my camera during runtime it opens a window and start identifying and tracking features. And node data can be visualized in rviz by subscribing to pose. Not sure if it was proper movement of pose as it moves the pointer somewhat according to my motion.
Terminal shows the following.

[ INFO] [1459711365.654362880]: Trying to intialize map...
[ INFO] [1459711365.696182493]: dt: 0
[ INFO] [1459711365.730848287]: Trying to intialize map...
Points initialized from stereo: 11
[ INFO] [1459711365.760036317]: dt: 0
init done 
opengl support available 


WARNING: Not enough points for tracking.

 Adding key-frame.
1.45973e+09 tk trackingtotal: 0.235
Se agrega/n 1 KeyFrame al mapa.
BA Local: kf adj: 1 kf fix: 1 points: 7
EJECUTANDO BA LOCAL:

[ INFO] [1459711365.995880619]: dt: 0
DESPUES DE BA LOCAL

BA LOCAL CONVERGIO
mediciones borradas por el BA: 4


WARNING: Not enough points for tracking.

This window is opened while camera is in motion and crashes when I stop the motion.
screenshot from 2016-04-04 00 44 01

The error on terminal when it crashes

BA LOCAL CONVERGIO
sptam_node: /home/sidd/catkin_ws/src/sptam/src/sptam/thirdparty/MEstimator.hpp:79: static double Tukey::FindSigmaSquared(std::vector<double>&): Assertion `vdErrorSquared.size() > 0' failed.
[ INFO] [1459711530.416988060]: dt: 0
[sptam-5] process has died [pid 19897, exit code -6, cmd /home/sidd/catkin_ws/devel/lib/sptam/sptam_node /robot/pose:=/odom __name:=sptam __log:=/home/sidd/.ros/log/b87c8c84-f9c9-11e5-bb92-94dbc9b19dba/sptam-5.log].
log file: /home/sidd/.ros/log/b87c8c84-f9c9-11e5-bb92-94dbc9b19dba/sptam-5*.log

Have to press ctrl+c to end the process.
This is the log file.
roslaunch_log.txt

This is the error in log file.

[roslaunch.pmon][INFO] 2016-04-04 00:42:02,694: registrations completed <ProcessMonitor(ProcessMonitor-1, started daemon 140200667428608)>
[roslaunch.parent][INFO] 2016-04-04 00:42:02,694: ... roslaunch parent running, waiting for process exit
[roslaunch][INFO] 2016-04-04 00:42:02,694: spin
[roslaunch][ERROR] 2016-04-04 00:42:42,132: [sptam-5] process has died [pid 11786, exit code -6, cmd /home/sidd/catkin_ws/devel/lib/sptam/sptam_node /robot/pose:=/odom __name:=sptam __log:=/home/sidd/.ros/log/b87c8c84-f9c9-11e5-bb92-94dbc9b19dba/sptam-5.log].
log file: /home/sidd/.ros/log/b87c8c84-f9c9-11e5-bb92-94dbc9b19dba/sptam-5*.log
[roslaunch.pmon][INFO] 2016-04-04 00:42:42,133: ProcessMonitor.unregister[sptam-5] starting

I can't seem to figure out why I am getting this error.
Thanks in advance.

Build error in Hydro

Hi, @taihup,

My test machine is Ubuntu 12.04, ROS Hydro.

After running command: catkin_make --pkg sptam -DSHOW_TRACKED_FRAMES=ON
It failed in building as follows:

Running command: "make -j2 -l2" in "/root/catkin_ws/build/sptam"

Scanning dependencies of target sptam
[ 0%] [ 10%] Building CXX object sptam/src/sptam/CMakeFiles/sptam.dir/Camera.cpp.o
Building CXX object sptam/src/sptam/CMakeFiles/sptam.dir/MapMaker.cpp.o
cc1plus: error: unrecognized command line option ‘-std=c++11’
make[2]: *** [sptam/src/sptam/CMakeFiles/sptam.dir/Camera.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
cc1plus: error: unrecognized command line option ‘-std=c++11’
make[2]: *** [sptam/src/sptam/CMakeFiles/sptam.dir/MapMaker.cpp.o] Error 1
make[1]: *** [sptam/src/sptam/CMakeFiles/sptam.dir/all] Error 2
make: *** [all] Error 2
Invoking "make" failed

Is it necessary to install it using ROS Indigo? Or there are some way to fix ‘-std=c++11’ error?

Thanks ~

Milton

SPTAM using base_link as reference frame doesn't publish

Hi,
SPTAM works perfectly well when I use left_camera as my reference frame but when I change the reference frame to base_link it doesn't publish anything. I'm using Kitti dataset.
The Launch code:

<launch>

  <!-- Set use_sim_time true for datasets-->
  <param name="use_sim_time" value="true" />

  <!-- static_transform_publisher x y z yaw pitch roll frame_id child_frame_id -->
  <!-- This transform was used set only to test if everything works
       when using something different than the camera as a reference frame.
       If enabled, take care to also fix the transform below. -->
  <node pkg="tf2_ros" type="static_transform_publisher" name="camera_broadcaster" args="1 0 0.5 -1.57 0 -1.57 base_link left_camera" />

  <!-- 'start' frame is the starting pose of the camera
       When 'base_link' is set as the reference frame,
       take care to set this transformation to the same as the previous one -->
  <node pkg="tf2_ros" type="static_transform_publisher" name="start_broadcaster" args="1 0 0.5 -1.57 0 -1.57 start map" />

  <!-- S-PTAM pose path publisher. Used for visualization. -->
  <node pkg="ros_utils" type="pose_to_path" name="sptam_path">
    <remap from="pose" to="sptam/robot/pose" />
    <remap from="path" to="sptam/robot/path" />
  </node>

  <!-- Nodelet Manager -->
  <!--<node pkg="nodelet" type="nodelet" name="nodelet_manager"  args="manager" output="screen" clear_params="true"/>-->

  <!-- Choose between Nodelet and Node S-PTAM -->
  <node pkg="sptam" type="sptam_node" name="sptam" output="screen" >
<!--  <node pkg="nodelet" type="nodelet" name="sptam" args="load sptam/sptam_nodelet nodelet_manager" output="screen" clear_params="true" >-->

    <!-- Read S-PTAM parameters file -->
    <rosparam command="load" file="$(find sptam)/configurationFiles/kitti.yaml" />
    <param name="LoopDetectorVocabulary" value="$(find sptam)/bow_voc/DBoW2/brief_mit_malaga_vocabulary.yml.gz" />

    <param name="use_prediction" value="false" />
    <param name="approximate_sync" value="false" />
    <param name="publish_transform" value="true" />
    <param name="publish_on_fail" value="true" />

    <!--param name="prediction_frame" value="odom" /-->
    <param name="base_frame" value="base_link" />
    <param name="camera_frame" value="left_camera" />
    <param name="map_frame" value="map" />
    <param name="reference_frame" value="base_link" />

    <remap from="/stereo/left/image_rect" to="/kitti_stereo/left/image_rect" />
    <remap from="/stereo/right/image_rect" to="/kitti_stereo/right/image_rect" />
    <remap from="/stereo/left/camera_info"  to="/kitti_stereo/left/camera_info" />
    <remap from="/stereo/right/camera_info"  to="/kitti_stereo/right/camera_info" />

  </node>

</launch>

Thanks.

not find a package DBoW2

Hi, I would like to use your program and I encounter some problems.

I got an error below
Selected BUILD_TYPE: Release
-- Found Intel TBB
-- Enabling parallel code
-- Setting OpenCV threads to: -1
-- Using CATKIN_DEVEL_PREFIX: /home/heesu/sptam/build/devel
-- Using CMAKE_PREFIX_PATH: /opt/ros/kinetic
-- This workspace overlays: /opt/ros/kinetic
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/heesu/sptam/build/test_results
-- Found gtest sources under '/usr/src/gtest': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.7.8
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Boost version: 1.58.0
-- Found the following Boost libraries:
-- thread
-- system
-- regex
-- chrono
-- date_time
-- atomic
CMake Error at src/sptam/CMakeLists.txt:16 (find_package):
By not providing "FindDBoW2.cmake" in CMAKE_MODULE_PATH this project has
asked CMake to find a package configuration file provided by "DBoW2", but
CMake did not find one.

Could not find a package configuration file provided by "DBoW2" with any of
the following names:

DBoW2Config.cmake
dbow2-config.cmake

Add the installation prefix of "DBoW2" to CMAKE_PREFIX_PATH or set
"DBoW2_DIR" to a directory containing one of the above files. If "DBoW2"
provides a separate development package or SDK, be sure it has been
installed.

CMake Error: The following variables are used in this project, but they are set to NOTFOUND.
Please set them or make sure they are set and tested correctly in the CMake files:
CHOLMOD_INCLUDE_DIR
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
CSPARSE_INCLUDE_DIR
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
G2O_INCLUDE_DIR
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam
used as include directory in directory /home/heesu/sptam/src/sptam

-- Configuring incomplete, errors occurred!
See also "/home/heesu/sptam/build/CMakeFiles/CMakeOutput.log".
See also "/home/heesu/sptam/build/CMakeFiles/CMakeError.log".

I believe I sucessfully download DBo2W.
Do you have any idea to solve the problem?

error in launching node and ROS path

ERROR: cannot launch node of type [ros_utils/pose_to_path]: ros_utils
ROS path [0]=/opt/ros/indigo/share/ros
ROS path [1]=/home/mobilerobot/catkin_ws/src
ROS path [2]=/opt/ros/indigo/share
ROS path [3]=/opt/ros/indigo/stacks

Even though i am able to run kitti.launch file, i am getting above error.

KITTI dataset

Good Evening Everyone, I am trying to use KITTI dataset on sptam, I could not download the KITTI rosbag [kitti_00.bag], I generated the bag from a sequence of KITTI dataset using BagFromImages package(ROS package to generate a rosbag from a collection of images. Would it not have consequences on the result?

Building standalone

Hi,

Thank you for open-sourcing your code. I am trying to build S-PTAM on Ubuntu 16.04 without ROS. I've installed all the dependencies and tried to build standalone using the instructions given in the readme. However, to do so, we need to build sptam as given in the CMakeLists.txt as:

_target_link_libraries(sptam-stereo sptam frameGenerator ${X11_LIBRARIES} boost_program_options ${THREAD_LIBS})_

When I try to build sptam, after I run make, I get the following output. Can you please tell me how to go about this? Specifically, will I need to run ROS or can I get the standalone version running without ROS?

Scanning dependencies of target test_set_union Scanning dependencies of target frameGenerator Scanning dependencies of target test_CovisibilityGraph [ 2%] Building CXX object src/tests/sptam/utils/set_union/CMakeFiles/test_set_union.dir/test_set_union.cpp.o [ 4%] Building CXX object src/standAlone/CMakeFiles/frameGenerator.dir/FrameGenerator/FileSequenceFrameGenerator.cpp.o [ 8%] Building CXX object src/standAlone/CMakeFiles/frameGenerator.dir/FrameGenerator/VideoFileFrameGenerator.cpp.o [ 8%] Building CXX object src/standAlone/CMakeFiles/frameGenerator.dir/FrameGenerator/ListOfFilesFrameGenerator.cpp.o [ 12%] Building CXX object src/tests/sptam/CovisibilityGraph/CMakeFiles/test_CovisibilityGraph.dir/test_CovisibilityGraph.cpp.o [ 12%] Building CXX object src/tests/sptam/CovisibilityGraph/CMakeFiles/test_CovisibilityGraph.dir/__/__/__/sptam/utils/CovisibilityGraph.cpp.o [ 14%] Building CXX object src/sptam/CMakeFiles/sptam.dir/MotionModel.cpp.o [ 16%] Building CXX object src/sptam/CMakeFiles/sptam.dir/CameraPose.cpp.o [ 18%] Building CXX object src/sptam/CMakeFiles/sptam.dir/Frame.cpp.o [ 20%] Building CXX object src/sptam/CMakeFiles/sptam.dir/FeatureExtractorThread.cpp.o [ 22%] Linking CXX static library libframeGenerator.a [ 24%] Linking CXX executable test_set_union [ 24%] Built target frameGenerator [ 26%] Building CXX object src/sptam/CMakeFiles/sptam.dir/g2o_driver.cpp.o /usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocaltesting::TestPartResultReporterInterface*::~ThreadLocal()':
gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEED2Ev[_ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEED5Ev]+0x25): undefined reference to pthread_getspecific' gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEED2Ev[_ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEED5Ev]+0x3a): undefined reference to pthread_key_delete'
/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocal<std::vector<testing::internal::TraceInfo, std::allocator<testing::internal::TraceInfo> > >::~ThreadLocal()': gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEED2Ev[_ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEED5Ev]+0x25): undefined reference to pthread_getspecific'
gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEED2Ev[_ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEED5Ev]+0x3a): undefined reference to pthread_key_delete' /usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocal<std::vector<testing::internal::TraceInfo, std::allocatortesting::internal::TraceInfo > >::GetOrCreateValue() const':
gtest-all.cc:(.text._ZNK7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE16GetOrCreateValueEv[_ZNK7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE16GetOrCreateValueEv]+0x27): undefined reference to pthread_getspecific' gtest-all.cc:(.text._ZNK7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE16GetOrCreateValueEv[_ZNK7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE16GetOrCreateValueEv]+0x8b): undefined reference to pthread_setspecific'
/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocal<testing::TestPartResultReporterInterface*>::CreateKey()': gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE9CreateKeyEv[_ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE9CreateKeyEv]+0x25): undefined reference to pthread_key_create'
/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocal<std::vector<testing::internal::TraceInfo, std::allocator<testing::internal::TraceInfo> > >::CreateKey()': gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE9CreateKeyEv[_ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE9CreateKeyEv]+0x25): undefined reference to pthread_key_create'
/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocal<testing::TestPartResultReporterInterface*>::GetOrCreateValue() const': gtest-all.cc:(.text._ZNK7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE16GetOrCreateValueEv[_ZNK7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE16GetOrCreateValueEv]+0x25): undefined reference to pthread_getspecific'
gtest-all.cc:(.text._ZNK7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE16GetOrCreateValueEv[_ZNK7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE16GetOrCreateValueEv]+0x89): undefined reference to pthread_setspecific' collect2: error: ld returned 1 exit status src/tests/sptam/utils/set_union/CMakeFiles/test_set_union.dir/build.make:94: recipe for target 'src/tests/sptam/utils/set_union/test_set_union' failed make[2]: *** [src/tests/sptam/utils/set_union/test_set_union] Error 1 CMakeFiles/Makefile2:197: recipe for target 'src/tests/sptam/utils/set_union/CMakeFiles/test_set_union.dir/all' failed make[1]: *** [src/tests/sptam/utils/set_union/CMakeFiles/test_set_union.dir/all] Error 2 make[1]: *** Waiting for unfinished jobs.... [ 28%] Building CXX object src/sptam/CMakeFiles/sptam.dir/BundleDriver.cpp.o [ 30%] Building CXX object src/sptam/CMakeFiles/sptam.dir/sptam.cpp.o [ 32%] Building CXX object src/sptam/CMakeFiles/sptam.dir/RowMatcher.cpp.o [ 34%] Linking CXX executable test_CovisibilityGraph /usr/bin/ld: /usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib/libgtest.a(gtest-all.cc.o): undefined reference to symbol 'pthread_key_delete@@GLIBC_2.2.5' //lib/x86_64-linux-gnu/libpthread.so.0: error adding symbols: DSO missing from command line collect2: error: ld returned 1 exit status src/tests/sptam/CovisibilityGraph/CMakeFiles/test_CovisibilityGraph.dir/build.make:121: recipe for target 'src/tests/sptam/CovisibilityGraph/test_CovisibilityGraph' failed make[2]: *** [src/tests/sptam/CovisibilityGraph/test_CovisibilityGraph] Error 1 CMakeFiles/Makefile2:252: recipe for target 'src/tests/sptam/CovisibilityGraph/CMakeFiles/test_CovisibilityGraph.dir/all' failed make[1]: *** [src/tests/sptam/CovisibilityGraph/CMakeFiles/test_CovisibilityGraph.dir/all] Error 2 [ 36%] Building CXX object src/sptam/CMakeFiles/sptam.dir/MapMakerThread.cpp.o [ 38%] Building CXX object src/sptam/CMakeFiles/sptam.dir/tracker_g2o.cpp.o [ 40%] Building CXX object src/sptam/CMakeFiles/sptam.dir/MapMaker.cpp.o [ 42%] Building CXX object src/sptam/CMakeFiles/sptam.dir/match_to_points.cpp.o [ 44%] Building CXX object src/sptam/CMakeFiles/sptam.dir/types_sba_extension.cpp.o [ 46%] Building CXX object src/sptam/CMakeFiles/sptam.dir/Measurement.cpp.o [ 48%] Building CXX object src/sptam/CMakeFiles/sptam.dir/Camera.cpp.o [ 50%] Building CXX object src/sptam/CMakeFiles/sptam.dir/FrustumCulling.cpp.o [ 52%] Building CXX object src/sptam/CMakeFiles/sptam.dir/TrackerViewStereo.cpp.o [ 54%] Building CXX object src/sptam/CMakeFiles/sptam.dir/StereoGraph.cpp.o [ 56%] Building CXX object src/sptam/CMakeFiles/sptam.dir/StereoFrame.cpp.o [ 58%] Building CXX object src/sptam/CMakeFiles/sptam.dir/MapPoint.cpp.o [ 60%] Building CXX object src/sptam/CMakeFiles/sptam.dir/ImageFeatures.cpp.o [ 62%] Building CXX object src/sptam/CMakeFiles/sptam.dir/utils/projection_derivatives.cpp.o [ 64%] Building CXX object src/sptam/CMakeFiles/sptam.dir/utils/timer.cpp.o [ 66%] Building CXX object src/sptam/CMakeFiles/sptam.dir/utils/CovisibilityGraph.cpp.o [ 68%] Building CXX object src/sptam/CMakeFiles/sptam.dir/utils/pose_covariance.cpp.o [ 70%] Building CXX object src/sptam/CMakeFiles/sptam.dir/utils/draw/Draw.cpp.o [ 72%] Building CXX object src/sptam/CMakeFiles/sptam.dir/utils/log/Logger.cpp.o [ 74%] Building CXX object src/sptam/CMakeFiles/sptam.dir/loopclosing/LoopClosing.cpp.o [ 76%] Building CXX object src/sptam/CMakeFiles/sptam.dir/loopclosing/SmoothEstimatePropagator.cpp.o [ 78%] Building CXX object src/sptam/CMakeFiles/sptam.dir/loopclosing/StereoMatcher.cpp.o [ 80%] Building CXX object src/sptam/CMakeFiles/sptam.dir/loopclosing/PoseEstimator.cpp.o [ 82%] Building CXX object src/sptam/CMakeFiles/sptam.dir/loopclosing/detectors/DLDLoopDetector.cpp.o [ 84%] Building CXX object src/sptam/CMakeFiles/sptam.dir/loopclosing/detectors/FBRISK.cpp.o [ 86%] Linking CXX shared library libsptam.so [ 88%] Built target sptam Makefile:94: recipe for target 'all' failed make: *** [all] Error 2

Error Running S-PTAM with kitti_00.bag

Hi, I'm trying to run S-PTAM usign kitti_00.bag and I got two errors, could you help me to fix them, please? Thanks a lot in advanced!

acfr@acfr-protea:~/catkin_ws/src/sptam-master/launch$ roslaunch sptam kitti.launch
... logging to /home/acfr/.ros/log/97f88d3c-063d-11e8-be02-b8ca3a8203b2/roslaunch-acfr-protea-25878.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://acfr-protea:44969/

SUMMARY

PARAMETERS

  • /rosdistro: kinetic
  • /rosversion: 1.12.12
  • /sptam/BundleAdjustmentActiveKeyframes: 10
  • /sptam/DescriptorExtractor/Name: BRIEF
  • /sptam/DescriptorExtractor/bytes: 32
  • /sptam/DescriptorMatcher/Name: BruteForce-Hamming
  • /sptam/DescriptorMatcher/crossCheck: False
  • /sptam/EpipolarDistance: 0
  • /sptam/FeatureDetector/Name: GFTT
  • /sptam/FeatureDetector/minDistance: 15.0
  • /sptam/FeatureDetector/nfeatures: 1000
  • /sptam/FeatureDetector/qualityLevel: 0.01
  • /sptam/FeatureDetector/useHarrisDetector: False
  • /sptam/FrustumFarPlaneDist: 10000.0
  • /sptam/FrustumNearPlaneDist: 0.1
  • /sptam/LoopDetectorVocabulary: /home/acfr/catkin...
  • /sptam/MatchingCellSize: 15
  • /sptam/MatchingDistance: 25
  • /sptam/MatchingNeighborhood: 2
  • /sptam/approximate_sync: False
  • /sptam/base_frame: left_camera
  • /sptam/camera_frame: left_camera
  • /sptam/minimumTrackedPointsRatio: 0.9
  • /sptam/publish_on_fail: True
  • /sptam/publish_transform: True
  • /sptam/reference_frame: left_camera
  • /sptam/use_prediction: False
  • /use_sim_time: True

NODES
/
sptam (sptam/sptam_node)
sptam_path (ros_utils/pose_to_path)
start_broadcaster (tf2_ros/static_transform_publisher)

ROS_MASTER_URI=http://localhost:11311

process[start_broadcaster-1]: started with pid [25896]
process[sptam_path-2]: started with pid [25897]
process[sptam-3]: started with pid [25915]
[ERROR] [1517372240.668652511]: Skipped loading plugin with error: XML Document '/opt/ros/kinetic/share/gmapping/nodelet_plugins.xml' has no Root Element. This likely means the XML is malformed or missing..
[ INFO] [1517372240.901949235]: Initializing nodelet with 8 worker threads.
crossCheck: 0
OpenCV: threads set to -1
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
bytes: 32
use_orientation: 0
bytes: 32
use_orientation: 0
[ INFO] [1517372243.114725293]: Loop Detector initializing, loading vocabulary
[ INFO] [1517372253.590275289]: S-PTAM stereo node initialized.
[ INFO] [1517372259.097301988]: init calib
[ INFO] [1517372259.097467046]: baseline: 0.537166
[ INFO] [1517372259.131948513]: Map initialized with 83 points.
[sptam-3] process has died [pid 25915, exit code -11, cmd /home/acfr/catkin_ws/devel/lib/sptam/sptam_node /stereo/left/image_rect:=/kitti_stereo/left/image_rect /stereo/right/image_rect:=/kitti_stereo/right/image_rect /stereo/left/camera_info:=/kitti_stereo/left/camera_info /stereo/right/camera_info:=/kitti_stereo/right/camera_info __name:=sptam __log:=/home/acfr/.ros/log/97f88d3c-063d-11e8-be02-b8ca3a8203b2/sptam-3.log].
log file: /home/acfr/.ros/log/97f88d3c-063d-11e8-be02-b8ca3a8203b2/sptam-3*.log

Not enough points for tracking with MIT dataset

I am trying out the MIT dataset as per the README but I am seeing warnings. Not sure if this is to do with this particular dataset. If anyone has tried out the dataset and has had success please let me know.

Instructions used:

rosparam set use_sim_time true
rosbag play --clock 2012-01-27-07-37-01.bag -s 302.5 -u 87
roslaunch sptam mit.launch

Console output:

Initializing nodelet with 8 worker threads.
  crossCheck: 0
OpenCV: threads set to -1
  nfeatures: 1000
  qualityLevel: 0.01
  minDistance: 15
  blockSize: 3
  useHarrisDetector: 0
  k: 0.04
  nfeatures: 1000
  qualityLevel: 0.01
  minDistance: 15
  blockSize: 3
  useHarrisDetector: 0
  k: 0.04
  bytes: 32
  use_orientation: 0
  bytes: 32
  use_orientation: 0
S-PTAM stereo node initialized.
Frames wide_stereo_gazebo_l_stereo_camera_optical_frame or base_link doesn't currently exist, waiting and retrying..
Could not obtain transform from wide_stereo_gazebo_l_stereo_camera_optical_frame to odom_combined. Error was Lookup would require extrapolation into the past.  Requested time 1327678924.387576634 but the earliest data is at time 1327678924.395886380, when looking up transform from frame [wide_stereo_gazebo_l_stereo_camera_optical_frame] to frame [odom_combined]

Could not get prediction map->wide_stereo_gazebo_l_stereo_camera_optical_frame. Using last known pose instead.
init calib
baseline: 0.0900571
Trying to intialize map...
Map initialized with 43 points.
Transform from wide_stereo_gazebo_l_stereo_camera_optical_frame to odom_combined was unavailable for the time requested (1327678924.437274979). Using nearest at time 1327678924.417576634 instead (0.-19698345).
Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points

rviz default configuration

I do not have so much experience in rviz with SLAM, so would it be possible to share the rviz configuration with different datasets? I tried several parameters with the cloud, but it looks very different comparing with the video on your Youtube site.

Assertion `intrinsicLeft == intrinsicRight' failed.

Hi, I'm trying to run S-PTAM with my own stereo calibrated and rectified data set but I'm getting this error and I really don't know what is wrong.
Thanks a lot for your help!

acfr@acfr-protea:~/catkin_ws/src/sptam-master/launch$ roslaunch sptam acfr.launch
... logging to /home/acfr/.ros/log/9acf877a-478f-11e8-ac7c-b8ca3a8203b2/roslaunch-acfr-protea-27477.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://acfr-protea:34237/

SUMMARY

PARAMETERS

  • /rosdistro: kinetic
  • /rosversion: 1.12.13
  • /sptam/BundleAdjustmentActiveKeyframes: 10
  • /sptam/DescriptorExtractor/Name: BRIEF
  • /sptam/DescriptorExtractor/bytes: 32
  • /sptam/DescriptorMatcher/Name: BruteForce-Hamming
  • /sptam/DescriptorMatcher/crossCheck: False
  • /sptam/EpipolarDistance: 0
  • /sptam/FeatureDetector/Name: GFTT
  • /sptam/FeatureDetector/minDistance: 15.0
  • /sptam/FeatureDetector/nfeatures: 2000
  • /sptam/FeatureDetector/qualityLevel: 0.01
  • /sptam/FeatureDetector/useHarrisDetector: False
  • /sptam/FrustumFarPlaneDist: 10000.0
  • /sptam/FrustumNearPlaneDist: 0.1
  • /sptam/LoopDetectorVocabulary: /home/acfr/catkin...
  • /sptam/MatchingCellSize: 15
  • /sptam/MatchingDistance: 25
  • /sptam/MatchingNeighborhood: 2
  • /sptam/approximate_sync: False
  • /sptam/base_frame: left_camera
  • /sptam/camera_frame: left_camera
  • /sptam/minimumTrackedPointsRatio: 0.9
  • /sptam/publish_on_fail: True
  • /sptam/publish_transform: True
  • /sptam/reference_frame: left_camera
  • /sptam/use_prediction: False
  • /use_sim_time: True

NODES
/stereo/
stereo_image_proc (stereo_image_proc/stereo_image_proc)
/
sptam (sptam/sptam_node)
sptam_path (ros_utils/pose_to_path)

ROS_MASTER_URI=http://localhost:11311

process[stereo/stereo_image_proc-1]: started with pid [27495]
process[sptam_path-2]: started with pid [27501]
process[sptam-3]: started with pid [27514]
[ INFO] [1524554287.204671234]: Initializing nodelet with 8 worker threads.
crossCheck: 0
OpenCV: threads set to -1
nfeatures: 2000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
nfeatures: 2000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
bytes: 32
use_orientation: 0
bytes: 32
use_orientation: 0
[ INFO] [1524554287.529219088]: Loop Detector initializing, loading vocabulary
[ INFO] [1524554296.426749743]: S-PTAM stereo node initialized.
[ INFO] [1524554297.009502797]: init calib
sptam_node: /home/acfr/catkin_ws/src/sptam-master/src/ros/stereo_driver.cpp:317: void sptam::stereo_driver::loadCameraCalibration(const CameraInfoConstPtr&, const CameraInfoConstPtr&): Assertion `intrinsicLeft == intrinsicRight' failed.
[sptam-3] process has died [pid 27514, exit code -6, cmd /home/acfr/catkin_ws/devel/lib/sptam/sptam_node /stereo/left/image_rect:=/stereo/left/image_rect /stereo/right/image_rect:=/stereo/right/image_rect /stereo/left/camera_info:=/gmsl/B3/camera_info /stereo/right/camera_info:=/gmsl/B2/camera_info robot/pose:=odom __name:=sptam __log:=/home/acfr/.ros/log/9acf877a-478f-11e8-ac7c-b8ca3a8203b2/sptam-3.log].
log file: /home/acfr/.ros/log/9acf877a-478f-11e8-ac7c-b8ca3a8203b2/sptam-3*.log

Disable GTest?

Is there any way to compile this without the Google Test Dependancy?

configurationfiles for local dataset

How to set .yaml configuration file for local dataset. I am using bubblebee2 of 640 x 480 pixels.
For the beginner case, i took kitti.yaml as a configuration file for my local dataset also. But, it failed as it was not able to 'initialise the map'.

KITTI Bag Files

Hi,

I can not download kitti rosbag files that you provide its link in the Readme.md (fs01.cifasis-conicet.gov.ar:90/~pire/datasets/KITTI/bags/).
Is it possible to provide a new way to download it?
Thank you.

Please HELP me::::::when-->“catkin_make --pkg sptam -DCMAKE_BUILD_TYPE=RelWithDebInfo -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON”

Every Step !I have fixed all the err or bug before “catkin_make.......”

I recieve the ERR (it seems like very EZ about grammer !!),,when I run "sudo "catkin_make --pkg sptam -DCMAKE_BUILD_TYPE=RelWithDebInfo -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON"

ERR :
[ 34%] Building CXX object sptam/src/sptam/CMakeFiles/sptam.dir/RowMatcher.cpp.o
[ 36%] Building CXX object sptam/src/sptam/CMakeFiles/sptam.dir/StereoFrame.cpp.o
Scanning dependencies of target sptam_ros
[ 38%] Building CXX object sptam/src/ros/CMakeFiles/sptam_ros.dir/stereo_driver.cpp.o
[ 40%] Building CXX object sptam/src/sptam/CMakeFiles/sptam.dir/StereoGraph.cpp.o
[ 42%] Building CXX object sptam/src/sptam/CMakeFiles/sptam.dir/TrackerViewStereo.cpp.o
[ 44%] Building CXX object sptam/src/sptam/CMakeFiles/sptam.dir/g2o_driver.cpp.o
[ 46%] Building CXX object sptam/src/ros/CMakeFiles/sptam_ros.dir/base_driver.cpp.o
In file included from /home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:3:0:
/home/shm/sptam_ws/src/sptam/src/sptam/types_sba_extension.hpp:43:84: error: ‘VertexSBAPointXYZ’ was not declared in this scope
class G2O_TYPES_SBA_API EdgeProjectP2MCRight : public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexCam>
^
/home/shm/sptam_ws/src/sptam/src/sptam/types_sba_extension.hpp:43:112: error: template argument 3 is invalid
class G2O_TYPES_SBA_API EdgeProjectP2MCRight : public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexCam>
^
/home/shm/sptam_ws/src/sptam/src/sptam/types_sba_extension.hpp: In member function ‘void g2o::EdgeProjectP2MCRight::computeError()’:
/home/shm/sptam_ws/src/sptam/src/sptam/types_sba_extension.hpp:55:13: error: ‘VertexSBAPointXYZ’ does not name a type
const VertexSBAPointXYZ point = static_cast<const VertexSBAPointXYZ>(_vertices[0]);
^
/home/shm/sptam_ws/src/sptam/src/sptam/types_sba_extension.hpp:56:60: error: ‘_vertices’ was not declared in this scope
const VertexCam cam = static_cast<const VertexCam>(_vertices[1]);
^
/home/shm/sptam_ws/src/sptam/src/sptam/types_sba_extension.hpp:61:22: error: ‘point’ was not declared in this scope
pt.head<3>() = point->estimate();
^
/home/shm/sptam_ws/src/sptam/src/sptam/types_sba_extension.hpp:85:7: error: ‘_error’ was not declared in this scope
_error = perr - _measurement;
^
/home/shm/sptam_ws/src/sptam/src/sptam/types_sba_extension.hpp:85:23: error: ‘_measurement’ was not declared in this scope
_error = perr - _measurement;
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp: In member function ‘G2ODriver::Vertex* G2ODriver::AddVertex(const MapPoint&, bool, bool, G2ODriver::VertexData*)’:
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:103:3: error: ‘VertexSBAPointXYZ’ is not a member of ‘g2o’
g2o::VertexSBAPointXYZ* v_p = new g2o::VertexSBAPointXYZ();
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:103:27: error: ‘v_p’ was not declared in this scope
g2o::VertexSBAPointXYZ* v_p = new g2o::VertexSBAPointXYZ();
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:103:37: error: expected type-specifier
g2o::VertexSBAPointXYZ* v_p = new g2o::VertexSBAPointXYZ();
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp: In static member function ‘static Eigen::Vector3d G2ODriver::GetPoint(g2o::HyperGraph::Vertex&)’:
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:153:3: error: ‘VertexSBAPointXYZ’ is not a member of ‘g2o’
g2o::VertexSBAPointXYZ& point_vertex = dynamic_castg2o::VertexSBAPointXYZ&( vertex );
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:153:27: error: ‘point_vertex’ was not declared in this scope
g2o::VertexSBAPointXYZ& point_vertex = dynamic_castg2o::VertexSBAPointXYZ&( vertex );
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:153:60: error: ‘VertexSBAPointXYZ’ in namespace ‘g2o’ does not name a type
g2o::VertexSBAPointXYZ& point_vertex = dynamic_castg2o::VertexSBAPointXYZ&( vertex );
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:153:77: error: expected ‘>’ before ‘&’ token
g2o::VertexSBAPointXYZ& point_vertex = dynamic_castg2o::VertexSBAPointXYZ&( vertex );
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:153:77: error: expected ‘(’ before ‘&’ token
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:153:78: error: expected primary-expression before ‘>’ token
g2o::VertexSBAPointXYZ& point_vertex = dynamic_castg2o::VertexSBAPointXYZ&( vertex );
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:153:89: error: expected ‘)’ before ‘;’ token
g2o::VertexSBAPointXYZ& point_vertex = dynamic_castg2o::VertexSBAPointXYZ&( vertex );
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp: In member function ‘G2ODriver::Edge* G2ODriver::BuildMonoEdgeRight(const std::vector&)’:
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:196:6: error: ‘class g2o::EdgeProjectP2MCRight’ has no member named ‘setMeasurement’
e->setMeasurement( Eigen::Vector2d(projection[0], projection[1]) );
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:197:6: error: ‘class g2o::EdgeProjectP2MCRight’ has no member named ‘information’
e->information() = Eigen::Matrix2d::Identity();
^
/home/shm/sptam_ws/src/sptam/src/sptam/g2o_driver.cpp:198:10: error: cannot convert ‘g2o::EdgeProjectP2MCRight*’ to ‘G2ODriver::Edge* {aka g2o::OptimizableGraph::Edge*}’ in return
return e;
^
At global scope:
cc1plus: warning: unrecognized command line option ‘-Wno-int-in-bool-context’
sptam/src/sptam/CMakeFiles/sptam.dir/build.make:283: recipe for target 'sptam/src/sptam/CMakeFiles/sptam.dir/g2o_driver.cpp.o' failed
make[2]: *** [sptam/src/sptam/CMakeFiles/sptam.dir/g2o_driver.cpp.o] Error 1
CMakeFiles/Makefile2:3180: recipe for target 'sptam/src/sptam/CMakeFiles/sptam.dir/all' failed
make[1]: *** [sptam/src/sptam/CMakeFiles/sptam.dir/all] Error 2
make[1]: *** 正在等待未完成的任务....
[ 48%] Building CXX object sptam/src/ros/CMakeFiles/sptam_ros.dir/utils/tf_utils.cpp.o
[ 51%] Building CXX object sptam/src/ros/CMakeFiles/sptam_ros.dir/utils/opencv_parsers.cpp.o
[ 53%] Linking CXX shared library /home/shm/sptam_ws/devel/lib/libsptam_ros.so
[ 53%] Built target sptam_ros
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j2 -l2" failed
shm@shm-virtual-machine:~/sptam_ws$ ^C

symbol lookup error when running $ roslaunch sptam mit.launch

jacky@jacky-VirtualBox:~/catkin_ws$ roslaunch sptam mit.launch
... logging to /home/jacky/.ros/log/d605cdc2-af00-11e7-bf14-080027aa2191/roslaunch-jacky-VirtualBox-8824.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://jacky-VirtualBox:43345/

SUMMARY

PARAMETERS

  • /rosdistro: kinetic
  • /rosversion: 1.12.7
  • /sptam/BundleAdjustmentActiveKeyframes: 10
  • /sptam/DescriptorExtractor/Name: BRIEF
  • /sptam/DescriptorExtractor/bytes: 32
  • /sptam/DescriptorMatcher/Name: BruteForce-Hamming
  • /sptam/DescriptorMatcher/crossCheck: False
  • /sptam/EpipolarDistance: 0
  • /sptam/FeatureDetector/Name: GFTT
  • /sptam/FeatureDetector/minDistance: 15.0
  • /sptam/FeatureDetector/nfeatures: 1000
  • /sptam/FeatureDetector/qualityLevel: 0.01
  • /sptam/FeatureDetector/useHarrisDetector: False
  • /sptam/FrustumFarPlaneDist: 10000.0
  • /sptam/FrustumNearPlaneDist: 0.1
  • /sptam/LoopDetectorVocabulary: /home/jacky/catki...
  • /sptam/MatchingCellSize: 30
  • /sptam/MatchingDistance: 25
  • /sptam/MatchingNeighborhood: 2
  • /sptam/approximate_sync: False
  • /sptam/camera_frame: wide_stereo_gazeb...
  • /sptam/minimumTrackedPointsRatio: 0.9
  • /sptam/prediction_frame: odom_combined
  • /sptam/publish_on_fail: True
  • /sptam/use_prediction: True
  • /use_sim_time: True

NODES
/wide_stereo/
stereo_image_proc (stereo_image_proc/stereo_image_proc)
/
sptam (sptam/sptam_node)
sptam_path (ros_utils/pose_to_path)

auto-starting new master
process[master]: started with pid [8835]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to d605cdc2-af00-11e7-bf14-080027aa2191
process[rosout-1]: started with pid [8848]
started core service [/rosout]
process[wide_stereo/stereo_image_proc-2]: started with pid [8860]
process[sptam_path-3]: started with pid [8873]
process[sptam-4]: started with pid [8903]
[ INFO] [1507780379.423925682]: Initializing nodelet with 1 worker threads.
crossCheck: 0
/home/jacky/catkin_ws/devel/lib/sptam/sptam_node: symbol lookup error: /home/jacky/catkin_ws/devel/lib/libsptam.so: undefined symbol: _ZN3g2o30OptimizationAlgorithmLevenbergC1ESt10unique_ptrINS_6SolverESt14default_deleteIS2_EE
[sptam-4] process has died [pid 8903, exit code 127, cmd /home/jacky/catkin_ws/devel/lib/sptam/sptam_node /imu/data:=/torso_lift_imu/data /stereo/left/image_features:=/wide_stereo/left/image_features /stereo/right/image_features:=/wide_stereo/right/image_features /stereo/left/image_rect:=/wide_stereo/left/image_rect_color /stereo/right/image_rect:=/wide_stereo/right/image_rect_color /stereo/left/camera_info:=/wide_stereo/left/camera_info /stereo/right/camera_info:=/wide_stereo/right/camera_info robot/pose:=odom __name:=sptam __log:=/home/jacky/.ros/log/d605cdc2-af00-11e7-bf14-080027aa2191/sptam-4.log].
log file: /home/jacky/.ros/log/d605cdc2-af00-11e7-bf14-080027aa2191/sptam-4*.log

Running KITTI sequences on standalone

Hi,

I am trying to run the standalone version of S-PTAM on an Ubuntu 16.04. I followed the directions given in the README.md to build sptam and then run the standalone file. However, I encounter a segmentation fault on the second frame of the KITTI odometery sequences (00-02). The following is the output from the program

detector: GFTT
nfeatures: 1000
qualityLevel: 0.010000
minDistance: 15.000000
blockSize: 3
useHarrisDetector: 0
k: 0.040000
detector: GFTT
nfeatures: 1000
qualityLevel: 0.010000
minDistance: 15.000000
blockSize: 3
useHarrisDetector: 0
k: 0.040000
descriptor: BRIEF
bytes: 32
use_orientation: 0
descriptor: BRIEF
bytes: 32
use_orientation: 0
matcher: BruteForce-Hamming
OpenCV: threads set to -1
Parsing timestamps file /media/fawad/DATA/Kitti_dataset/sequences/00/times.txt
Loaded 4541 timestamps poses
WARNING tracking is slower than the camera feed by 0.398667 (s)
Segmentation fault (core dumped)

The function call graph that explains the crash better is as follows:

main -> SptamWrapper::Add -> SPTAM::track -> tracker_g2o::RefineCameraPose -> G2ODriver::AddVertex g2o_driver.cpp:125

Has anyone encountered this problem before? I look into it and it seems like sptam has some problems with its g2o library which causes the segmentation fault. I'll highly appreciate any help in this regard.

symbol lookup error: /home/ros/vslam/devel/lib/libsptam.so: undefined symbol

ros@ros-ubuntu:~/vslam$ roslaunch sptam kitti.launch
... logging to /home/ros/.ros/log/7615fe52-b75e-11e8-a10e-002324de281e/roslaunch-ros-ubuntu-13670.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://192.168.100.124:46473/

SUMMARY

PARAMETERS

  • /rosdistro: kinetic
  • /rosversion: 1.12.14
  • /sptam/BundleAdjustmentActiveKeyframes: 10
  • /sptam/DescriptorExtractor/Name: BRIEF
  • /sptam/DescriptorExtractor/bytes: 32
  • /sptam/DescriptorMatcher/Name: BruteForce-Hamming
  • /sptam/DescriptorMatcher/crossCheck: False
  • /sptam/EpipolarDistance: 0
  • /sptam/FeatureDetector/Name: GFTT
  • /sptam/FeatureDetector/minDistance: 15.0
  • /sptam/FeatureDetector/nfeatures: 1000
  • /sptam/FeatureDetector/qualityLevel: 0.01
  • /sptam/FeatureDetector/useHarrisDetector: False
  • /sptam/FrustumFarPlaneDist: 10000.0
  • /sptam/FrustumNearPlaneDist: 0.1
  • /sptam/LoopDetectorVocabulary: /home/ros/vslam/s...
  • /sptam/MatchingCellSize: 15
  • /sptam/MatchingDistance: 25
  • /sptam/MatchingNeighborhood: 2
  • /sptam/approximate_sync: False
  • /sptam/base_frame: camera_gray_left
  • /sptam/camera_frame: camera_gray_left
  • /sptam/map_frame: map
  • /sptam/minimumTrackedPointsRatio: 0.9
  • /sptam/prediction_frame: odom
  • /sptam/publish_on_fail: True
  • /sptam/publish_transform: True
  • /sptam/reference_frame: camera_gray_left
  • /sptam/use_prediction: False
  • /use_sim_time: True

NODES
/
sptam (sptam/sptam_node)
sptam_path (ros_utils/pose_to_path)
start_broadcaster (tf2_ros/static_transform_publisher)

ROS_MASTER_URI=http://192.168.100.124:11311

process[start_broadcaster-1]: started with pid [13688]
process[sptam_path-2]: started with pid [13689]
process[sptam-3]: started with pid [13704]
[ INFO] [1536855684.505911059]: Initializing nodelet with 4 worker threads.
crossCheck: 0
OpenCV: threads set to -1
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
bytes: 32
use_orientation: 0
bytes: 32
use_orientation: 0
[ INFO] [1536855684.572702099]: Loop Detector initializing, loading vocabulary
[ INFO] [1536855691.775018863, 1317013705.076373054]: S-PTAM stereo node initialized.
[ INFO] [1536855703.159725135, 1317013706.214797726]: init calib
[ INFO] [1536855703.160009472, 1317013706.214797726]: baseline: 0.537151
[ INFO] [1536855703.180599290, 1317013706.216826523]: Trying to intialize map...
[ INFO] [1536855703.196421446, 1317013706.218838018]: Map initialized with 111 points.
/home/ros/vslam/devel/lib/sptam/sptam_node: symbol lookup error: /home/ros/vslam/devel/lib/libsptam.so: undefined symbol: _ZN3g2o30OptimizationAlgorithmLevenbergC1ESt10unique_ptrINS_6SolverESt14default_deleteIS2_EE
[sptam-3] process has died [pid 13704, exit code 127, cmd /home/ros/vslam/devel/lib/sptam/sptam_node /stereo/left/image_rect:=/kitti/camera_gray_left/image_raw /stereo/right/image_rect:=/kitti/camera_gray_right/image_raw /stereo/left/camera_info:=/kitti/camera_gray_left/camera_info /stereo/right/camera_info:=/kitti/camera_gray_right/camera_info __name:=sptam __log:=/home/ros/.ros/log/7615fe52-b75e-11e8-a10e-002324de281e/sptam-3.log].
log file: /home/ros/.ros/log/7615fe52-b75e-11e8-a10e-002324de281e/sptam-3*.log
^C[sptam_path-2] killing on exit
[start_broadcaster-1] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done

[ERROR] [1563717737.344465687]: [registerPublisher] Failed to contact master at [localhost:11311]. Retrying...

I am sorry to bother you, it is my first time to use ros. I have finished to compile your code according to your instruction. When I run the "rosbag play --clock kitti_00.bag" in the terminal. I meet the following problem.

[ERROR] [1563718288.196069766]: [registerPublisher] Failed to contact master at [localhost:11311]. Retrying...

I have searched this problem on the Internet. But it doesn't work.
Can you help me? I will be thankful for your help.

ERROR: There is not any covisibility keyframes observing the tracked points

Hi @taihup
When I use my own camera to run sptam, the output is always like this:

[ WARN] [1529655500.726652359]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1529655500.767450854]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1529655500.806891177]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points

That is strange, and I cannot find any reason, could you help me to see how it happens, Thanks very much!

Make Error(CMake Error at sptam/src/sptam/CMakeLists.txt:15 (find_package): "DLib"

Hello everyone, making the sptam, I encoutered an error DLid

SUMMARY

PARAMETERS

  • /rosdistro: kinetic
  • /rosversion: 1.12.7
    NODES
    auto-starting new master
    process[master]: started with pid [4712]
    ROS_MASTER_URI=http://haidara-virtual-machine:11311/
    setting /run_id to 690c55cc-d05e-11e7-9d22-000c29fd0356
    process[rosout-1]: started with pid [4725]
    started core service [/rosout]

haidara@haidara-virtual-machine:~/catkin_ws$ catkin_make --pkg sptam -DCMAKE_BUILD_TYPE=RelWithDebInfo -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON
Base path: /home/haidara/catkin_ws
Source space: /home/haidara/catkin_ws/src
Build space: /home/haidara/catkin_ws/build
Devel space: /home/haidara/catkin_ws/devel
Install space: /home/haidara/catkin_ws/install

Running command: "cmake /home/haidara/catkin_ws/src -DCMAKE_BUILD_TYPE=RelWithDebInfo -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON -DCATKIN_DEVEL_PREFIX=/home/haidara/catkin_ws/devel -DCMAKE_INSTALL_PREFIX=/home/haidara/catkin_ws/install -G Unix Makefiles" in "/home/haidara/catkin_ws/build"

-- Using CATKIN_DEVEL_PREFIX: /home/haidara/catkin_ws/devel
-- Using CMAKE_PREFIX_PATH: /opt/ros/kinetic
-- This workspace overlays: /opt/ros/kinetic
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/haidara/catkin_ws/build/test_results
-- Found gtest sources under '/usr/src/gtest': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.7.6
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~ traversing 2 packages in topological order:
-- ~~ - ros_utils
-- ~~ - sptam
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'ros_utils'
-- ==> add_subdirectory(ros-utils)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- +++ processing catkin package: 'sptam'
-- ==> add_subdirectory(sptam)
Selected BUILD_TYPE: RelWithDebInfo
-- Found Intel TBB
-- Enabling parallel code
-- Setting OpenCV threads to: -1
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Boost version: 1.58.0
-- Found the following Boost libraries:
-- thread
-- system
-- regex
-- chrono
-- date_time
-- atomic
CMake Error at sptam/src/sptam/CMakeLists.txt:15 (find_package):
By not providing "FindDLib.cmake" in CMAKE_MODULE_PATH this project has
asked CMake to find a package configuration file provided by "DLib", but
CMake did not find one.

Could not find a package configuration file provided by "DLib" with any of
the following names:

DLibConfig.cmake
dlib-config.cmake

Add the installation prefix of "DLib" to CMAKE_PREFIX_PATH or set
"DLib_DIR" to a directory containing one of the above files. If "DLib"
provides a separate development package or SDK, be sure it has been
installed.

-- Configuring incomplete, errors occurred!
See also "/home/haidara/catkin_ws/build/CMakeFiles/CMakeOutput.log".
See also "/home/haidara/catkin_ws/build/CMakeFiles/CMakeError.log".
Invoking "cmake" failed

Thank you in advance for your answer.

rosplay kitti_04 error,need help

roslaunch sptam kitti.launch
... logging to /home/cvg/.ros/log/4323bc3c-e44d-11ea-a471-84ef18a6a32e/roslaunch-cvg-L-8280.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://cvg-L:35826/

SUMMARY

PARAMETERS

  • /rosdistro: kinetic
  • /rosversion: 1.12.14
  • /sptam/BundleAdjustmentActiveKeyframes: 10
  • /sptam/DescriptorExtractor/Name: BRIEF
  • /sptam/DescriptorExtractor/bytes: 32
  • /sptam/DescriptorMatcher/Name: BruteForce-Hamming
  • /sptam/DescriptorMatcher/crossCheck: False
  • /sptam/EpipolarDistance: 0
  • /sptam/FeatureDetector/Name: GFTT
  • /sptam/FeatureDetector/minDistance: 15.0
  • /sptam/FeatureDetector/nfeatures: 1000
  • /sptam/FeatureDetector/qualityLevel: 0.01
  • /sptam/FeatureDetector/useHarrisDetector: False
  • /sptam/FrustumFarPlaneDist: 10000.0
  • /sptam/FrustumNearPlaneDist: 0.1
  • /sptam/LoopDetectorVocabulary: /home/cvg/catkin_...
  • /sptam/MatchingCellSize: 15
  • /sptam/MatchingDistance: 25
  • /sptam/MatchingNeighborhood: 2
  • /sptam/approximate_sync: False
  • /sptam/base_frame: left_camera
  • /sptam/camera_frame: left_camera
  • /sptam/minimumTrackedPointsRatio: 0.9
  • /sptam/publish_on_fail: True
  • /sptam/publish_transform: True
  • /sptam/reference_frame: left_camera
  • /sptam/use_prediction: False
  • /use_sim_time: True

NODES
/
sptam (sptam/sptam_node)
sptam_path (ros_utils/pose_to_path)
start_broadcaster (tf2_ros/static_transform_publisher)

ROS_MASTER_URI=http://localhost:11311

process[start_broadcaster-1]: started with pid [8297]
process[sptam_path-2]: started with pid [8298]
process[sptam-3]: started with pid [8306]
[ INFO] [1598083334.440576321]: Initializing nodelet with 8 worker threads.
crossCheck: 0
OpenCV: threads set to -1
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
bytes: 32
use_orientation: 0
bytes: 32
use_orientation: 0
[ INFO] [1598083334.617317674]: S-PTAM stereo node initialized.
[ INFO] [1598083342.286254159, 1385799339.561438617]: init calib
[ INFO] [1598083342.286648398, 1385799339.561438617]: baseline: 0.537151
[ INFO] [1598083342.325401229, 1385799339.565474172]: Trying to intialize map...
[ INFO] [1598083342.346033684, 1385799339.567491247]: Map initialized with 137 points.
[sptam-3] process has died [pid 8306, exit code -11, cmd /home/cvg/catkin_ws/devel/lib/sptam/sptam_node /stereo/left/image_rect:=/kitti_stereo/left/image_rect /stereo/right/image_rect:=/kitti_stereo/right/image_rect /stereo/left/camera_info:=/kitti_stereo/left/camera_info /stereo/right/camera_info:=/kitti_stereo/right/camera_info __name:=sptam __log:=/home/cvg/.ros/log/4323bc3c-e44d-11ea-a471-84ef18a6a32e/sptam-3.log].
log file: /home/cvg/.ros/log/4323bc3c-e44d-11ea-a471-84ef18a6a32e/sptam-3*.log

I meet this problem , I am a new for ROS, could you help me with this problem, please?

File:'file:///home/lzb/catkin_ws2/src/sptam/src/sptam/loopclosing/detectors/DLDLoopDetector.cpp' Severity:'Error' Message:''DBoW2:: FBrief:: TDescriptor {aka class std:: BitSet < 256ul >}'has no member named'resize''

Dear, author When compiling sptam program according to readme, I encountered the following problems. I don't know how to solve them. I hope the author can give some suggestions. My compiler environment is Ubuntu 16.04 and ROS kinetic.

File:'file:///home/lzb/catkin_ws2/src/sptam/src/sptam/loopclosing/detectors/DLDLoopDetector.cpp'
Severity:'Error'
Message:''DBoW2:: FBrief:: TDescriptor {aka class std:: BitSet < 256ul >}'has no member named'resize''
At:'99,15'

error: ‘DBoW2::FBrief::TDescriptor {aka class std::bitset<256ul>}’ has no member named ‘resize’

Thanks for making your code open-source!

I managed to install all the packages needed, and after running either

catkin_make --pkg sptam -DCMAKE_BUILD_TYPE=RelWithDebInfo -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON

or

catkin_make --pkg sptam -DCMAKE_BUILD_TYPE=RelWithDebInfo -DUSE_LOOPCLOSURE=ON -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON

in the README file i am greeted with this message:

Running ROS Kinetic on Ubuntu 16.04. I will continue poking and prodding around to find a way around this and will post a solution if successful, but in the meantime any guidance is very much helpful and appreciated. Thank you!

Running command: "make -j8 -l8" in "/home/antreas/FYP/catkin_fyp_ws/build/sptam"

[ 2%] Linking CXX executable test_set_union
[ 4%] Linking CXX executable test_CovisibilityGraph
[ 14%] Built target sptam_ros
/usr/bin/ld: /usr/lib/libgtest.a(gtest-all.cc.o): undefined reference to symbol 'pthread_key_delete@@GLIBC_2.2.5'
//lib/x86_64-linux-gnu/libpthread.so.0: error adding symbols: DSO missing from command line
collect2: error: ld returned 1 exit status
sptam/src/tests/sptam/CovisibilityGraph/CMakeFiles/test_CovisibilityGraph.dir/build.make:123: recipe for target 'sptam/src/tests/sptam/CovisibilityGraph/test_CovisibilityGraph' failed
make[2]: *** [sptam/src/tests/sptam/CovisibilityGraph/test_CovisibilityGraph] Error 1
CMakeFiles/Makefile2:3242: recipe for target 'sptam/src/tests/sptam/CovisibilityGraph/CMakeFiles/test_CovisibilityGraph.dir/all' failed
make[1]: *** [sptam/src/tests/sptam/CovisibilityGraph/CMakeFiles/test_CovisibilityGraph.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
/usr/lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocal<testing::TestPartResultReporterInterface*>::~ThreadLocal()': gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEED2Ev[_ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEED5Ev]+0x25): undefined reference to pthread_getspecific'
gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEED2Ev[_ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEED5Ev]+0x3a): undefined reference to pthread_key_delete' /usr/lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocal<std::vector<testing::internal::TraceInfo, std::allocatortesting::internal::TraceInfo > >::~ThreadLocal()':
gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEED2Ev[_ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEED5Ev]+0x25): undefined reference to pthread_getspecific' gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEED2Ev[_ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEED5Ev]+0x3a): undefined reference to pthread_key_delete'
/usr/lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocal<std::vector<testing::internal::TraceInfo, std::allocator<testing::internal::TraceInfo> > >::GetOrCreateValue() const': gtest-all.cc:(.text._ZNK7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE16GetOrCreateValueEv[_ZNK7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE16GetOrCreateValueEv]+0x27): undefined reference to pthread_getspecific'
gtest-all.cc:(.text._ZNK7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE16GetOrCreateValueEv[_ZNK7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE16GetOrCreateValueEv]+0x8b): undefined reference to pthread_setspecific' /usr/lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocaltesting::TestPartResultReporterInterface*::CreateKey()':
gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE9CreateKeyEv[_ZN7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE9CreateKeyEv]+0x25): undefined reference to pthread_key_create' /usr/lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocal<std::vector<testing::internal::TraceInfo, std::allocatortesting::internal::TraceInfo > >::CreateKey()':
gtest-all.cc:(.text._ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE9CreateKeyEv[_ZN7testing8internal11ThreadLocalISt6vectorINS0_9TraceInfoESaIS3_EEE9CreateKeyEv]+0x25): undefined reference to pthread_key_create' /usr/lib/libgtest.a(gtest-all.cc.o): In function testing::internal::ThreadLocaltesting::TestPartResultReporterInterface*::GetOrCreateValue() const':
gtest-all.cc:(.text._ZNK7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE16GetOrCreateValueEv[_ZNK7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE16GetOrCreateValueEv]+0x25): undefined reference to pthread_getspecific' gtest-all.cc:(.text._ZNK7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE16GetOrCreateValueEv[_ZNK7testing8internal11ThreadLocalIPNS_31TestPartResultReporterInterfaceEE16GetOrCreateValueEv]+0x89): undefined reference to pthread_setspecific'
collect2: error: ld returned 1 exit status
sptam/src/tests/sptam/utils/set_union/CMakeFiles/test_set_union.dir/build.make:96: recipe for target 'sptam/src/tests/sptam/utils/set_union/test_set_union' failed
make[2]: *** [sptam/src/tests/sptam/utils/set_union/test_set_union] Error 1
CMakeFiles/Makefile2:3187: recipe for target 'sptam/src/tests/sptam/utils/set_union/CMakeFiles/test_set_union.dir/all' failed
make[1]: *** [sptam/src/tests/sptam/utils/set_union/CMakeFiles/test_set_union.dir/all] Error 2
[ 16%] Building CXX object sptam/src/sptam/CMakeFiles/sptam.dir/loopclosing/detectors/DLDLoopDetector.cpp.o
/home/antreas/FYP/catkin_fyp_ws/src/sptam/src/sptam/loopclosing/detectors/DLDLoopDetector.cpp: In member function ‘DetectionMatch DLDLoopDetector::detectloop(const SharedKeyFrame&) [with F = DBoW2::FBrief; sptam::Map::SharedKeyFrame = std::shared_ptr<CovisibilityGraph<StereoFrame, MapPoint, Measurement>::KeyFrame>]’:
/home/antreas/FYP/catkin_fyp_ws/src/sptam/src/sptam/loopclosing/detectors/DLDLoopDetector.cpp:99:15: error: ‘DBoW2::FBrief::TDescriptor {aka class std::bitset<256ul>}’ has no member named ‘resize’
bset_desc.resize(char_bset_desc.size());
^
At global scope:
cc1plus: warning: unrecognized command line option ‘-Wno-int-in-bool-context’
sptam/src/sptam/CMakeFiles/sptam.dir/build.make:854: recipe for target 'sptam/src/sptam/CMakeFiles/sptam.dir/loopclosing/detectors/DLDLoopDetector.cpp.o' failed
make[2]: *** [sptam/src/sptam/CMakeFiles/sptam.dir/loopclosing/detectors/DLDLoopDetector.cpp.o] Error 1
CMakeFiles/Makefile2:3075: recipe for target 'sptam/src/sptam/CMakeFiles/sptam.dir/all' failed
make[1]: *** [sptam/src/sptam/CMakeFiles/sptam.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j8 -l8" failed

Compiling in ROS Kinetic

Hi, do you have any information about what changes are needed for compilation in ROS Kinetic?.
Thanks!

Standalone

Hi~
I was running STANDALONE
I got tracked frames, but where can I see map results ?

Regards~,

Build error in ROS Indigo

Dear @taihup ,

I had followed the installed guide, however I came across the following error when building sptam in ROS indigo.

It seems the issues that PCL library and openni-dev are missing.
But I already followed the guide to install pcl:
$ apt-get install ros-indigo-pcl-ros

Could you suggest me how to fix it?

THX~
MB

root@ubuntu:~/catkin_ws# catkin_make --pkg sptam -DSHOW_TRACKED_FRAMES=ON
Base path: /root/catkin_ws
Source space: /root/catkin_ws/src
Build space: /root/catkin_ws/build
Devel space: /root/catkin_ws/devel
Install space: /root/catkin_ws/install

Running command: "cmake /root/catkin_ws/src -DSHOW_TRACKED_FRAMES=ON -DCATKIN_DEVEL_PREFIX=/root/catkin_ws/devel -DCMAKE_INSTALL_PREFIX=/root/catkin_ws/install -G Unix Makefiles" in "/root/catkin_ws/build"

-- Using CATKIN_DEVEL_PREFIX: /root/catkin_ws/devel
-- Using CMAKE_PREFIX_PATH: /root/catkin_ws/devel;/opt/ros/indigo
-- This workspace overlays: /root/catkin_ws/devel;/opt/ros/indigo
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /root/catkin_ws/build/test_results
-- Found gtest sources under '/usr/src/gtest': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.6.16
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~ traversing 1 packages in topological order:
-- ~~ - sptam
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'sptam'
-- ==> add_subdirectory(sptam)
-- Using these message generators: gencpp;genlisp;genpy
-- Boost version: 1.59.0
-- Found the following Boost libraries:
-- thread
-- system
-- regex
-- Boost version: 1.54.0
-- Found the following Boost libraries:
-- system
-- filesystem
-- thread
-- date_time
-- iostreams
-- serialization
-- checking for module 'openni-dev'
-- package 'openni-dev' not found
-- checking for module 'openni-dev'
-- package 'openni-dev' not found
-- checking for module 'openni-dev'
-- package 'openni-dev' not found
-- looking for PCL_COMMON
-- looking for PCL_OCTREE
-- looking for PCL_IO
-- looking for PCL_KDTREE
-- looking for PCL_SEARCH
-- looking for PCL_SAMPLE_CONSENSUS
-- looking for PCL_FILTERS
-- looking for PCL_FEATURES
-- looking for PCL_KEYPOINTS
-- looking for PCL_GEOMETRY
-- looking for PCL_SEGMENTATION
-- looking for PCL_VISUALIZATION
-- looking for PCL_OUTOFCORE
-- looking for PCL_REGISTRATION
-- looking for PCL_RECOGNITION
-- looking for PCL_SURFACE
-- looking for PCL_PEOPLE
-- looking for PCL_TRACKING
-- looking for PCL_APPS
CMake Error: The following variables are used in this project, but they are set to NOTFOUND.
Please set them or make sure they are set and tested correctly in the CMake files:
CHOLMOD_INCLUDE_DIR
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam/src/sptam
used as include directory in directory /root/catkin_ws/src/sptam/src/ros

-- Configuring incomplete, errors occurred!
See also "/root/catkin_ws/build/CMakeFiles/CMakeOutput.log".
See also "/root/catkin_ws/build/CMakeFiles/CMakeError.log".
Invoking "cmake" failed
root@ubuntu:~/catkin_ws#

S-PTAM hangs on "sptam node initialized"

Hello,
I would appreciate so much your help!
I successfully run your kitti and level7 datasets.
Now I am trying to run my own - playing video file .mp4 with both cameras. I am succesfully running nodes stereo/left/image_raw and camera_info and right nodes as well. Sucessfully running stereo_proc and having rect_images. Everything is just ready but when I run SPTAM it just hangs on "sptam node initialized" forever and nothing happens...Changing number of features, featuers quality, epipolar distance, nothing helps, can you suggest?
Thank you!

Error Running kitti.launch with kitti_01.bag

... logging to /home/efun/.ros/log/d04e5df8-a5a5-11e8-98a3-4cedfbcaaae4/roslaunch-efun-26211.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://localhost:35003/

SUMMARY

PARAMETERS

  • /rosdistro: kinetic
  • /rosversion: 1.12.13
  • /sptam/BundleAdjustmentActiveKeyframes: 10
  • /sptam/DescriptorExtractor/Name: BRIEF
  • /sptam/DescriptorExtractor/bytes: 32
  • /sptam/DescriptorMatcher/Name: BruteForce-Hamming
  • /sptam/DescriptorMatcher/crossCheck: False
  • /sptam/EpipolarDistance: 0
  • /sptam/FeatureDetector/Name: GFTT
  • /sptam/FeatureDetector/minDistance: 15.0
  • /sptam/FeatureDetector/nfeatures: 1000
  • /sptam/FeatureDetector/qualityLevel: 0.01
  • /sptam/FeatureDetector/useHarrisDetector: False
  • /sptam/FrustumFarPlaneDist: 10000.0
  • /sptam/FrustumNearPlaneDist: 0.1
  • /sptam/LoopDetectorVocabulary: /home/efun/catkin...
  • /sptam/MatchingCellSize: 15
  • /sptam/MatchingDistance: 25
  • /sptam/MatchingNeighborhood: 2
  • /sptam/approximate_sync: False
  • /sptam/base_frame: left_camera
  • /sptam/camera_frame: left_camera
  • /sptam/minimumTrackedPointsRatio: 0.9
  • /sptam/publish_on_fail: True
  • /sptam/publish_transform: True
  • /sptam/reference_frame: left_camera
  • /sptam/use_prediction: False
  • /use_sim_time: True

NODES
/
sptam (sptam/sptam_node)
sptam_path (ros_utils/pose_to_path)
start_broadcaster (tf2_ros/static_transform_publisher)

ROS_MASTER_URI=http://localhost:11311

process[start_broadcaster-1]: started with pid [26228]
process[sptam_path-2]: started with pid [26235]
process[sptam-3]: started with pid [26248]
[ INFO] [1534899226.980898860]: Initializing nodelet with 12 worker threads.
crossCheck: 0
OpenCV: threads set to -1
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
bytes: 32
use_orientation: 0
bytes: 32
use_orientation: 0
[ INFO] [1534899227.117075503]: S-PTAM stereo node initialized.
[ INFO] [1534899227.308119776, 1385798597.275167144]: init calib
[ INFO] [1534899227.308562666, 1385798597.275167144]: baseline: 0.537166
[ INFO] [1534899227.352500830, 1385798597.325656805]: Trying to intialize map...
[ INFO] [1534899227.362344444, 1385798597.335742839]: Map initialized with 61 points.
[ WARN] [1534899227.448437967, 1385798597.416596004]: Not enough points for tracking.
[ WARN] [1534899227.549903210, 1385798597.518844700]: Not enough points for tracking.
[ WARN] [1534899227.652603786, 1385798597.619818541]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899227.757493059, 1385798597.730895827]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899227.861465985, 1385798597.832033463]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899227.963549905, 1385798597.933671664]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899228.043840863, 1385798598.014559739]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899228.172265201, 1385798598.146099253]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899228.274452372, 1385798598.247198987]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899228.378589889, 1385798598.348147057]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899228.480684566, 1385798598.449195250]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899228.588424055, 1385798598.560424138]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899228.690725644, 1385798598.661514474]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899228.794051950, 1385798598.763016618]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899228.899101231, 1385798598.874177932]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.003824312, 1385798598.975271649]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.082420023, 1385798599.056040514]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.180803979, 1385798599.157483901]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.314867772, 1385798599.289054709]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.392381368, 1385798599.359861763]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.496572188, 1385798599.470865327]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.625864561, 1385798599.602596593]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.729981015, 1385798599.703611855]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.807452677, 1385798599.774369327]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899229.939548645, 1385798599.915924993]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899230.041654707, 1385798600.017228531]: Not enough points for tracking.
ERROR: There is not any covisibility keyframes observing the tracked points
[ WARN] [1534899230.142771535, 1385798600.118318340]: Not enough points for tracking.

Gtest error while doing catkin_make --pkg sptam -DCMAKE_BUILD_TYPE=RelWithDebInfo -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON

Hi, i am new in ROS and i tried to run your sptam slam. I followed all the instructions as readme indicate. but when I try to to catkin_make --pkg sptam -DCMAKE_BUILD_TYPE=RelWithDebInfo -DSINGLE_THREAD=OFF -DSHOW_TRACKED_FRAMES=ON -DSHOW_PROFILING=ON -DPARALLELIZE=ON, I get an error:
I am working in ubuntu 16 and ROS Kinetic.
Thanks in advance for your reply.


.....
-- Found Intel Thread Building Blocks (TBB) library: /usr/lib/x86_64-linux-gnu/libtbb.so, assuming SuiteSparseQR was compiled with TBB.
-- Found TBB_MALLOC library: /usr/lib/x86_64-linux-gnu/libtbbmalloc.so
-- Found Intel Thread Building Blocks (TBB) Malloc library: /usr/lib/x86_64-linux-gnu/libtbbmalloc.so
-- Found SUITESPARSE_CONFIG headers in: /usr/include/suitesparse
-- Found SUITESPARSE_CONFIG library: /usr/lib/x86_64-linux-gnu/libsuitesparseconfig.so;/usr/lib/x86_64-linux-gnu/librt.so
-- Found LIBRT library: /usr/lib/x86_64-linux-gnu/librt.so
-- Adding librt: /usr/lib/x86_64-linux-gnu/librt.so to SuiteSparse_config libraries (required on Linux & Unix [not OSX] if SuiteSparse is compiled with timing).
-- Did not find METIS library (optional SuiteSparse dependency)
CMake Error at /usr/share/cmake-3.5/Modules/FindPackageHandleStandardArgs.cmake:148 (message):
Could NOT find GTest (missing: GTEST_LIBRARY GTEST_MAIN_LIBRARY)
Call Stack (most recent call first):
/usr/share/cmake-3.5/Modules/FindPackageHandleStandardArgs.cmake:388 (_FPHSA_FAILURE_MESSAGE)
/usr/share/cmake-3.5/Modules/FindGTest.cmake:205 (FIND_PACKAGE_HANDLE_STANDARD_ARGS)
sptam/src/tests/CMakeLists.txt:4 (find_package)

-- Configuring incomplete, errors occurred!
See also "/home/kevinu/catkin_ws/build/CMakeFiles/CMakeOutput.log".
See also "/home/kevinu/catkin_ws/build/CMakeFiles/CMakeError.log".
Invoking "cmake" failed

What is Significance of profiling

Your have used logger .

But i don't see any log files after running code.

How to build code with profiling on ?

I have seen MAcro in code as SHOW_PROFILING

Gtest error while compilation

Hi,

I encountered this error while compiling sptam:
screenshot from 2018-05-17 10-03-56

I reinstalled gtest for a few times but failed to solve the issue.

Thanks in advance.

Not enough points to initialize map.

Hi, I am testing with my own bag (recorded by my zed camera)
In "aligned_vector points "
point size is always zero
I have tried the MIT Stata Center dataset and it works fine
by the way I am not using loop closure

this is what I got
... logging to /home/jacky/.ros/log/19749ac4-3265-11e8-a708-0800275b2bd8/roslaunch-jacky-VirtualBox-24302.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://jacky-VirtualBox:44671/

SUMMARY

PARAMETERS

  • /imagetransport1/approximate_sync: True
  • /imagetransport1/queue_size: 1000
  • /imagetransport2/approximate_sync: True
  • /imagetransport2/queue_size: 1000
  • /rosdistro: kinetic
  • /rosversion: 1.12.7
  • /sptam/BundleAdjustmentActiveKeyframes: 10
  • /sptam/DescriptorExtractor/Name: BRIEF
  • /sptam/DescriptorExtractor/bytes: 32
  • /sptam/DescriptorMatcher/Name: BruteForce-Hamming
  • /sptam/DescriptorMatcher/crossCheck: False
  • /sptam/EpipolarDistance: 0
  • /sptam/FeatureDetector/Name: GFTT
  • /sptam/FeatureDetector/minDistance: 15.0
  • /sptam/FeatureDetector/nfeatures: 1000
  • /sptam/FeatureDetector/qualityLevel: 0.01
  • /sptam/FeatureDetector/useHarrisDetector: False
  • /sptam/FrustumFarPlaneDist: 10000.0
  • /sptam/FrustumNearPlaneDist: 0.1
  • /sptam/LoopDetectorVocabulary: /home/jacky/catki...
  • /sptam/MatchingCellSize: 30
  • /sptam/MatchingDistance: 25
  • /sptam/MatchingNeighborhood: 2
  • /sptam/approximate_sync: True
  • /sptam/base_frame: left_camera
  • /sptam/camera_frame: left_camera
  • /sptam/minimumTrackedPointsRatio: 0.9
  • /sptam/publish_on_fail: True
  • /sptam/publish_transform: True
  • /sptam/queue_size: 1000
  • /sptam/reference_frame: left_camera
  • /sptam/use_prediction: False
  • /stereo/stereo_image_proc/approximate_sync: True
  • /stereo/stereo_image_proc/queue_size: 1000
  • /use_sim_time: True

NODES
/imagetransport2/
republish (image_transport/republish)
/stereo/
stereo_image_proc (stereo_image_proc/stereo_image_proc)
/imagetransport1/
republish (image_transport/republish)
/
camera_broadcaster (tf2_ros/static_transform_publisher)
sptam (sptam/sptam_node)
sptam_path (ros_utils/pose_to_path)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[imagetransport1/republish-1]: started with pid [24364]
process[imagetransport2/republish-2]: started with pid [24365]
process[stereo/stereo_image_proc-3]: started with pid [24367]
process[camera_broadcaster-4]: started with pid [24383]
process[sptam_path-5]: started with pid [24417]
process[sptam-6]: started with pid [24462]
[ INFO] [1522227799.398858325]: Initializing nodelet with 1 worker threads.
crossCheck: 0
OpenCV: threads set to -1
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
nfeatures: 1000
qualityLevel: 0.01
minDistance: 15
blockSize: 3
useHarrisDetector: 0
k: 0.04
bytes: 32
use_orientation: 0
bytes: 32
use_orientation: 0
[ INFO] [1522227802.802015569, 1514963975.211378596]: S-PTAM stereo node initialized.
[ INFO] [1522227807.322240749, 1514963976.115933562]: init calib
[ INFO] [1522227807.322738574, 1514963976.115933562]: baseline: 0.00012
[ INFO] [1522227807.812476321, 1514963976.212768105]: Trying to intialize map...
[ WARN] [1522227808.031914579, 1514963976.257170983]: Not enough points to initialize map.

last this is my rqt graph
https://imgur.com/a/b9XBk

Hope you can help me
Best regards

make error

When i make the sptam, I encoutered an error. I reinstall eigen several time, the problem still on.
please help me. thank you.

In file included from /usr/include/eigen3/Eigen/Core:341:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h:21:34: note: provided for ‘template struct Eigen::internal::assign_op’
template struct assign_op {
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:39:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Homogeneous.h:351:127: error: template argument 3 is invalid
struct Assignment<DstXprType, Homogeneous<ArgType,Vertical>, internal::assign_op<Scalar,typename ArgType::Scalar>, Dense2Dense>
^
/usr/local/include/eigen3/Eigen/src/Geometry/Homogeneous.h:368:115: error: wrong number of template arguments (2, should be 1)
struct Assignment<DstXprType, Homogeneous<ArgType,Horizontal>, internal::assign_op<Scalar,typename ArgType::Scalar>, Dense2Dense>
^
In file included from /usr/include/eigen3/Eigen/Core:341:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h:21:34: note: provided for ‘template struct Eigen::internal::assign_op’
template struct assign_op {
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:39:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Homogeneous.h:368:129: error: template argument 3 is invalid
struct Assignment<DstXprType, Homogeneous<ArgType,Horizontal>, internal::assign_op<Scalar,typename ArgType::Scalar>, Dense2Dense>
^
/usr/local/include/eigen3/Eigen/src/Geometry/Homogeneous.h:405:90: error: wrong number of template arguments (2, should be 1)
typedef CwiseBinaryOp<internal::scalar_sum_op<typename Lhs::Scalar,typename Rhs::Scalar>, const LinearProduct, const ConstantBlock> Xpr;
^
In file included from /usr/include/eigen3/Eigen/Core:296:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h:181:34: note: provided for ‘template struct Eigen::internal::scalar_sum_op’
template struct scalar_sum_op;
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:39:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Homogeneous.h:405:133: error: template argument 1 is invalid
typedef CwiseBinaryOp<internal::scalar_sum_op<typename Lhs::Scalar,typename Rhs::Scalar>, const LinearProduct, const ConstantBlock> Xpr;
^
/usr/local/include/eigen3/Eigen/src/Geometry/Homogeneous.h:458:90: error: wrong number of template arguments (2, should be 1)
typedef CwiseBinaryOp<internal::scalar_sum_op<typename Lhs::Scalar,typename Rhs::Scalar>, const LinearProduct, const ConstantBlock> Xpr;
^
In file included from /usr/include/eigen3/Eigen/Core:296:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h:181:34: note: provided for ‘template struct Eigen::internal::scalar_sum_op’
template struct scalar_sum_op;
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:39:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Homogeneous.h:458:133: error: template argument 1 is invalid
typedef CwiseBinaryOp<internal::scalar_sum_op<typename Lhs::Scalar,typename Rhs::Scalar>, const LinearProduct, const ConstantBlock> Xpr;
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:41:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Rotation2D.h: In member function ‘Eigen::Rotation2D::Scalar Eigen::Rotation2D::smallestPositiveAngle() const’:
/usr/local/include/eigen3/Eigen/src/Geometry/Rotation2D.h:85:18: error: ‘fmod’ is not a member of ‘Eigen::numext’
Scalar tmp = numext::fmod(m_angle,Scalar(2EIGEN_PI));
^
/usr/local/include/eigen3/Eigen/src/Geometry/Rotation2D.h:85:18: note: suggested alternatives:
In file included from /usr/include/features.h:367:0,
from /usr/include/x86_64-linux-gnu/c++/5/bits/os_defines.h:39,
from /usr/include/x86_64-linux-gnu/c++/5/bits/c++config.h:482,
from /usr/include/c++/5/new:39,
from /usr/include/eigen3/Eigen/Core:56,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/x86_64-linux-gnu/bits/mathcalls.h:187:1: note: ‘fmod’
__MATHCALL (fmod,, (Mdouble __x, Mdouble __y));
^
In file included from /usr/include/c++/5/complex:44:0,
from /usr/include/eigen3/Eigen/Core:70,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/c++/5/cmath:309:5: note: ‘std::fmod’
fmod(_Tp __x, _Up __y)
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:41:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Rotation2D.h: In member function ‘Eigen::Rotation2D::Scalar Eigen::Rotation2D::smallestAngle() const’:
/usr/local/include/eigen3/Eigen/src/Geometry/Rotation2D.h:91:18: error: ‘fmod’ is not a member of ‘Eigen::numext’
Scalar tmp = numext::fmod(m_angle,Scalar(2
EIGEN_PI));
^
/usr/local/include/eigen3/Eigen/src/Geometry/Rotation2D.h:91:18: note: suggested alternatives:
In file included from /usr/include/features.h:367:0,
from /usr/include/x86_64-linux-gnu/c++/5/bits/os_defines.h:39,
from /usr/include/x86_64-linux-gnu/c++/5/bits/c++config.h:482,
from /usr/include/c++/5/new:39,
from /usr/include/eigen3/Eigen/Core:56,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/x86_64-linux-gnu/bits/mathcalls.h:187:1: note: ‘fmod’
__MATHCALL (fmod,, (Mdouble __x, Mdouble __y));
^
In file included from /usr/include/c++/5/complex:44:0,
from /usr/include/eigen3/Eigen/Core:70,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/c++/5/cmath:309:5: note: ‘std::fmod’
fmod(_Tp __x, _Up __y)
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:42:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h: In member function ‘typename Eigen::internal::traits::Scalar Eigen::QuaternionBase::angularDistance(const Eigen::QuaternionBase&) const’:
/usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:709:45: error: ‘abs’ is not a member of ‘Eigen::numext’
return Scalar(2) * atan2( d.vec().norm(), numext::abs(d.w()) );
^
/usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:709:45: note: suggested alternatives:
In file included from /usr/include/c++/5/cstdlib:72:0,
from /usr/include/c++/5/ext/string_conversions.h:41,
from /usr/include/c++/5/bits/basic_string.h:5249,
from /usr/include/c++/5/string:52,
from /usr/include/c++/5/bits/locale_classes.h:40,
from /usr/include/c++/5/bits/ios_base.h:41,
from /usr/include/c++/5/ios:42,
from /usr/include/c++/5/istream:38,
from /usr/include/c++/5/sstream:38,
from /usr/include/c++/5/complex:45,
from /usr/include/eigen3/Eigen/Core:70,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/stdlib.h:774:12: note: ‘abs’
extern int abs (int __x) __THROW attribute ((const)) __wur;
^
In file included from /usr/include/eigen3/Eigen/Core:70:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/c++/5/complex:597:5: note: ‘std::abs’
abs(const complex<_Tp>& __z) { return __complex_abs(__z.__rep()); }
^
In file included from /usr/include/eigen3/Eigen/Core:441:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:58:36: note: ‘Eigen::abs’
EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op)
^
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:17:4: note: in definition of macro ‘EIGEN_ARRAY_DECLARE_GLOBAL_UNARY’
(NAME)(const Eigen::ArrayBase& x) {
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:42:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h: In member function ‘Eigen::Quaternion<typename Eigen::internal::traits::Scalar> Eigen::QuaternionBase::slerp(const Scalar&, const Eigen::QuaternionBase&) const’:
/usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:729:17: error: ‘abs’ is not a member of ‘Eigen::numext’
Scalar absD = numext::abs(d);
^
/usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:729:17: note: suggested alternatives:
In file included from /usr/include/c++/5/cstdlib:72:0,
from /usr/include/c++/5/ext/string_conversions.h:41,
from /usr/include/c++/5/bits/basic_string.h:5249,
from /usr/include/c++/5/string:52,
from /usr/include/c++/5/bits/locale_classes.h:40,
from /usr/include/c++/5/bits/ios_base.h:41,
from /usr/include/c++/5/ios:42,
from /usr/include/c++/5/istream:38,
from /usr/include/c++/5/sstream:38,
from /usr/include/c++/5/complex:45,
from /usr/include/eigen3/Eigen/Core:70,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/stdlib.h:774:12: note: ‘abs’
extern int abs (int __x) __THROW attribute ((const)) __wur;
^
In file included from /usr/include/eigen3/Eigen/Core:70:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/c++/5/complex:597:5: note: ‘std::abs’
abs(const complex<_Tp>& __z) { return __complex_abs(__z.__rep()); }
^
In file included from /usr/include/eigen3/Eigen/Core:441:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:58:36: note: ‘Eigen::abs’
EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op)
^
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:17:4: note: in definition of macro ‘EIGEN_ARRAY_DECLARE_GLOBAL_UNARY’
(NAME)(const Eigen::ArrayBase& x) {
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:46:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Scaling.h: At global scope:
/usr/local/include/eigen3/Eigen/src/Geometry/Scaling.h:116:55: error: ‘product’ has not been declared
EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(Derived,Scalar,product)
^
/usr/local/include/eigen3/Eigen/src/Geometry/Scaling.h:117:1: error: expected constructor, destructor, or type conversion before ‘operator’
operator*(const MatrixBase& matrix, const UniformScaling& s)
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:47:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Hyperplane.h: In member function ‘Eigen::Hyperplane<_Scalar, _AmbientDim, Options>::Scalar Eigen::Hyperplane<_Scalar, _AmbientDim, Options>::absDistance(const VectorType&) const’:
/usr/local/include/eigen3/Eigen/src/Geometry/Hyperplane.h:148:83: error: ‘abs’ is not a member of ‘Eigen::numext’
EIGEN_DEVICE_FUNC inline Scalar absDistance(const VectorType& p) const { return numext::abs(signedDistance(p)); }
^
/usr/local/include/eigen3/Eigen/src/Geometry/Hyperplane.h:148:83: note: suggested alternatives:
In file included from /usr/include/c++/5/cstdlib:72:0,
from /usr/include/c++/5/ext/string_conversions.h:41,
from /usr/include/c++/5/bits/basic_string.h:5249,
from /usr/include/c++/5/string:52,
from /usr/include/c++/5/bits/locale_classes.h:40,
from /usr/include/c++/5/bits/ios_base.h:41,
from /usr/include/c++/5/ios:42,
from /usr/include/c++/5/istream:38,
from /usr/include/c++/5/sstream:38,
from /usr/include/c++/5/complex:45,
from /usr/include/eigen3/Eigen/Core:70,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/stdlib.h:774:12: note: ‘abs’
extern int abs (int __x) __THROW attribute ((const)) __wur;
^
In file included from /usr/include/eigen3/Eigen/Core:70:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/c++/5/complex:597:5: note: ‘std::abs’
abs(const complex<_Tp>& __z) { return __complex_abs(__z.__rep()); }
^
In file included from /usr/include/eigen3/Eigen/Core:441:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:58:36: note: ‘Eigen::abs’
EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op)
^
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:17:4: note: in definition of macro ‘EIGEN_ARRAY_DECLARE_GLOBAL_UNARY’
(NAME)(const Eigen::ArrayBase& x) {
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:47:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Hyperplane.h: In member function ‘Eigen::Hyperplane<_Scalar, _AmbientDim, Options>::VectorType Eigen::Hyperplane<_Scalar, _AmbientDim, Options>::intersection(const Eigen::Hyperplane<_Scalar, _AmbientDim, Options>&) const’:
/usr/local/include/eigen3/Eigen/src/Geometry/Hyperplane.h:197:12: error: ‘abs’ is not a member of ‘Eigen::numext’
if(numext::abs(coeffs().coeff(1))>numext::abs(coeffs().coeff(0)))
^
/usr/local/include/eigen3/Eigen/src/Geometry/Hyperplane.h:197:12: note: suggested alternatives:
In file included from /usr/include/c++/5/cstdlib:72:0,
from /usr/include/c++/5/ext/string_conversions.h:41,
from /usr/include/c++/5/bits/basic_string.h:5249,
from /usr/include/c++/5/string:52,
from /usr/include/c++/5/bits/locale_classes.h:40,
from /usr/include/c++/5/bits/ios_base.h:41,
from /usr/include/c++/5/ios:42,
from /usr/include/c++/5/istream:38,
from /usr/include/c++/5/sstream:38,
from /usr/include/c++/5/complex:45,
from /usr/include/eigen3/Eigen/Core:70,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/stdlib.h:774:12: note: ‘abs’
extern int abs (int __x) __THROW attribute ((const)) __wur;
^
In file included from /usr/include/eigen3/Eigen/Core:70:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/c++/5/complex:597:5: note: ‘std::abs’
abs(const complex<_Tp>& __z) { return __complex_abs(__z.__rep()); }
^
In file included from /usr/include/eigen3/Eigen/Core:441:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:58:36: note: ‘Eigen::abs’
EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op)
^
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:17:4: note: in definition of macro ‘EIGEN_ARRAY_DECLARE_GLOBAL_UNARY’
(NAME)(const Eigen::ArrayBase& x) {
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:47:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/Hyperplane.h:197:43: error: ‘abs’ is not a member of ‘Eigen::numext’
if(numext::abs(coeffs().coeff(1))>numext::abs(coeffs().coeff(0)))
^
/usr/local/include/eigen3/Eigen/src/Geometry/Hyperplane.h:197:43: note: suggested alternatives:
In file included from /usr/include/c++/5/cstdlib:72:0,
from /usr/include/c++/5/ext/string_conversions.h:41,
from /usr/include/c++/5/bits/basic_string.h:5249,
from /usr/include/c++/5/string:52,
from /usr/include/c++/5/bits/locale_classes.h:40,
from /usr/include/c++/5/bits/ios_base.h:41,
from /usr/include/c++/5/ios:42,
from /usr/include/c++/5/istream:38,
from /usr/include/c++/5/sstream:38,
from /usr/include/c++/5/complex:45,
from /usr/include/eigen3/Eigen/Core:70,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/stdlib.h:774:12: note: ‘abs’
extern int abs (int __x) __THROW attribute ((const)) __wur;
^
In file included from /usr/include/eigen3/Eigen/Core:70:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/c++/5/complex:597:5: note: ‘std::abs’
abs(const complex<_Tp>& __z) { return __complex_abs(__z.__rep()); }
^
In file included from /usr/include/eigen3/Eigen/Core:441:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:58:36: note: ‘Eigen::abs’
EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op)
^
/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h:17:4: note: in definition of macro ‘EIGEN_ARRAY_DECLARE_GLOBAL_UNARY’
(NAME)(const Eigen::ArrayBase& x) {
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:49:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/AlignedBox.h: At global scope:
/usr/local/include/eigen3/Eigen/src/Geometry/AlignedBox.h:115:100: error: ‘quotient’ has not been declared
EIGEN_DEVICE_FUNC inline const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(VectorTypeSum, RealScalar, quotient)
^
/usr/local/include/eigen3/Eigen/src/Geometry/AlignedBox.h:115:108: error: expected ‘;’ at end of member declaration
EIGEN_DEVICE_FUNC inline const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(VectorTypeSum, RealScalar, quotient)
^
/usr/local/include/eigen3/Eigen/src/Geometry/AlignedBox.h:123:93: error: wrong number of template arguments (2, should be 1)
EIGEN_DEVICE_FUNC inline const CwiseBinaryOp< internal::scalar_difference_op<Scalar,Scalar>, const VectorType, const VectorType> sizes() const
^
In file included from /usr/include/eigen3/Eigen/Core:296:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h:182:34: note: provided for ‘template struct Eigen::internal::scalar_difference_op’
template struct scalar_difference_op;
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:49:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/AlignedBox.h:123:130: error: template argument 1 is invalid
EIGEN_DEVICE_FUNC inline const CwiseBinaryOp< internal::scalar_difference_op<Scalar,Scalar>, const VectorType, const VectorType> sizes() const
^
/usr/local/include/eigen3/Eigen/src/Geometry/AlignedBox.h:134:87: error: wrong number of template arguments (2, should be 1)
EIGEN_DEVICE_FUNC inline CwiseBinaryOp< internal::scalar_difference_op<Scalar,Scalar>, const VectorType, const VectorType> diagonal() const
^
In file included from /usr/include/eigen3/Eigen/Core:296:0,
from /usr/include/eigen3/Eigen/StdVector:14,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h:182:34: note: provided for ‘template struct Eigen::internal::scalar_difference_op’
template struct scalar_difference_op;
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:49:0,
from /home/cc/sp_ws/src/sptam/src/sptam/MapPoint.hpp:37,
from /home/cc/sp_ws/src/sptam/src/sptam/Map.hpp:35,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.hpp:36,
from /home/cc/sp_ws/src/sptam/src/sptam/MapMaker.cpp:34:
/usr/local/include/eigen3/Eigen/src/Geometry/AlignedBox.h:134:124: error: template argument 1 is invalid
EIGEN_DEVICE_FUNC inline CwiseBinaryOp< internal::scalar_difference_op<Scalar,Scalar>, const VectorType, const VectorType> diagonal() const
^
sptam/src/sptam/CMakeFiles/sptam.dir/build.make:278: recipe for target 'sptam/src/sptam/CMakeFiles/sptam.dir/MapMaker.cpp.o' failed
make[2]: *** [sptam/src/sptam/CMakeFiles/sptam.dir/MapMaker.cpp.o] Error 1
CMakeFiles/Makefile2:3266: recipe for target 'sptam/src/sptam/CMakeFiles/sptam.dir/all' failed
make[1]: *** [sptam/src/sptam/CMakeFiles/sptam.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2

Error while running the roslaunch sptam kitti.launch

All the dependencies and the package compile correctly with Loop Closure enabled (after solving the problems with gtest from issues)

I get the error with roslaunch sptam kitti.launch:
`

process[sptam_path-2]: started with pid [25729]
process[sptam-3]: started with pid [25742]
[rospack] Unable to create temporary cache file /home/civit/.ros/.rospack_cache.SnkbTY: > Permission denied
[ INFO] [1585665696.909589941]: Initializing nodelet with 8 worker threads.
crossCheck: 0
OpenCV: threads set to -1

.
.
.
[ INFO] [1585665696.955380996]: Loop Detector initializing, loading vocabulary
[ INFO] [1585665702.835194208]: S-PTAM stereo node initialized.
[ INFO] [1585665729.056361792, 1385799339.756688080]: init calib
[ INFO] [1585665729.056493470, 1385799339.756688080]: baseline: 0.537151
[ INFO] [1585665729.068912331, 1385799339.766747106]: Trying to intialize map...
[ INFO] [1585665729.083122637, 1385799339.766747106]: Map initialized with 130 points.

/home/civit/catkin_SPTAM/devel/lib/sptam/sptam_node: symbol lookup error: /home/civit>/catkin_SPTAM/devel/lib/libsptam.so: undefined symbol: >_ZN3g2o30OptimizationAlgorithmLevenbergC1ESt10unique_ptrINS_6SolverESt14default_deleteIS2_EE
[sptam-3] process has died [pid 25742, exit code 127, cmd /home/civit/catkin_SPTAM/devel/lib/sptam/sptam_node /stereo/left/image_rect:=/kitti_stereo/left/image_rect /stereo/right/image_rect:=/kitti_stereo/right/image_rect /stereo/left/camera_info:=/kitti_stereo/left/camera_info /stereo/right/camera_info:=/kitti_stereo/right/camera_info __name:=sptam __log:=/home/civit/.ros/log/6c6636d0-735d-11ea-aad1-04ed338e233a/sptam-3.log].
log file: /home/civit/.ros/log/6c6636d0-735d-11ea-aad1-04ed338e233a/sptam-3*.log`

I checked that few other people have reported this as well (#13 , #37 ...) .I attempted to follow the instructions there, but it was not of much help.
I even cleaned the sptam and the g2o and rebuilt them.

`%for g2o

git clone https://github.com/RainerKuemmerle/g2o
cd ~/catkin_SPTAM/src/g2o
git checkout 4b9c2f5b68d14ad479457b18c5a2a0bce1541a90
mkdir build
cd build
cmake ~/catkin_SPTAM/src/g2o/
make
sudo make install`

P.S: I am new to ROS and ubuntu. However, I would like to run this implementation with ROS due to various other preferences

Camera calibration files for EuRoc MAV dataset

Hi

I am trying to run the S-PTAM with the EuRoc MAV dataset.
According your tutorial I need to run the following:

python sptam_directory/scripts/euroc_add_camera_info.py MH_01_easy.bag /mav0/cam0/sensor.yaml /mav0/cam1/sensor.yaml

However, I cannot find '/mav0/cam1/sensor.yaml ' file. Could you point me where is this file?

With Regards,
Alex

Error Evaluation code

Hi, Irse, do you have the sample code about the error evaluation part ? I also want to test the performance of this SLAM.
Thanks very much.

I still got a error never meet before. Does anyone successfully build this project? Please help me.

I got this problem when I run this :
roslaunch sptam mit.launch

[ERROR] [1513921915.103911788]: Failed to load nodelet [/sptam] of type [sptam/sptam_nodelet] even after refreshing the cache: MultiLibraryClassLoader: Could not create object of class type sptam::sptam_nodelet as no factory exists for it. Make sure that the library exists and was explicitly loaded through MultiLibraryClassLoader::loadLibrary() [ERROR] [1513921915.103948410]: The error before refreshing the cache was: Failed to load library /home/eason/sptam_ws/devel/lib//libsptam_nodelet.so. Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library (Poco exception = /home/eason/sptam_ws/devel/lib/libsptam.so: undefined symbol: _ZTIN3g2o9VertexCamE)
Does anyone successfully build this project or solve this problem? Please help me.

Run sptam using the euroc.launch on EuRoc MAV dataset Error

For Usage, I am trying to run sptam using the euroc.launch on EuRoc MAV dataset and the process has died. Thank you in advance for your answer.
haidara@haidara-virtual-machine:~/catkin_ws/src/sptam/launch$ roslaunch sptam euroc.launch
... logging to /home/haidara/.ros/log/932ace70-d558-11e7-9157-000c29704879/roslaunch-haidara-virtual-machine-22810.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://haidara-virtual-machine:33851/
SUMMARY

CLEAR PARAMETERS

/image_proc_left/
/image_proc_right/
/nodelet_manager/

PARAMETERS

/image_proc_left/queue_size: 1
/image_proc_right/queue_size: 1
/rosdistro: kinetic
/rosversion: 1.12.7
/sptam/BundleAdjustmentActiveKeyframes: 10
/sptam/DescriptorExtractor/Name: BRIEF
/sptam/DescriptorExtractor/bytes: 32
/sptam/DescriptorMatcher/Name: BruteForce-Hamming
/sptam/DescriptorMatcher/crossCheck: False
/sptam/EpipolarDistance: 1
/sptam/FeatureDetector/Name: ORB
/sptam/FeatureDetector/edgeThreshold: 31
/sptam/FeatureDetector/nFeatures: 200
/sptam/FeatureDetector/nLevels: 1
/sptam/FeatureDetector/scaleFactor: 1.2
/sptam/FrustumFarPlaneDist: 50.0
/sptam/FrustumNearPlaneDist: 0.1
/sptam/LoopDetectorVocabulary: /home/haidara/cat...
/sptam/MatchingCellSize: 15
/sptam/MatchingDistance: 25
/sptam/MatchingNeighborhood: 2
/sptam/approximate_sync: False
/sptam/base_frame: base_link
/sptam/camera_frame: cam0
/sptam/minimumTrackedPointsRatio: 0.9
/sptam/prediction_frame: map
/sptam/publish_transform: True
/sptam/use_prediction: False
/use_sim_time: True

NODES
/
bl_broadcaster (tf2_ros/static_transform_publisher)
gr_broadcaster (tf2_ros/static_transform_publisher)
gr_broadcaster2 (tf2_ros/static_transform_publisher)
image_proc_left (nodelet/nodelet)
image_proc_right (nodelet/nodelet)
imu_cam0_broadcaster (tf2_ros/static_transform_publisher)
imu_cam1_broadcaster (tf2_ros/static_transform_publisher)
nodelet_manager (nodelet/nodelet)
sptam (sptam/sptam_node)
sptam_path (ros_utils/pose_to_path)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
running rosparam delete /sptam/
process[imu_cam0_broadcaster-1]: started with pid [22836]
process[imu_cam1_broadcaster-2]: started with pid [22837]
process[bl_broadcaster-3]: started with pid [22839]
process[gr_broadcaster2-4]: started with pid [22864]
process[gr_broadcaster-5]: started with pid [22879]
process[sptam_path-6]: started with pid [22916]
process[nodelet_manager-7]: started with pid [22919]
process[image_proc_left-8]: started with pid [22922]
process[image_proc_right-9]: started with pid [22924]
process[sptam-10]: started with pid [22941]
[ INFO] [1511998711.169025421]: Loading nodelet /image_proc_left of type image_proc/rectify to manager nodelet_manager with the following remappings:
[ INFO] [1511998711.169166343]: /camera_info -> /cam0/camera_info
[ INFO] [1511998711.169203484]: /image_mono -> /cam0/image_raw
[ INFO] [1511998711.169227311]: /image_rect -> /stereo/left/image_rect
[ INFO] [1511998711.182625058]: Loading nodelet /image_proc_right of type image_proc/rectify to manager nodelet_manager with the following remappings:
[ INFO] [1511998711.182861811]: /camera_info -> /cam1/camera_info
[ INFO] [1511998711.182950892]: /image_mono -> /cam1/image_raw
[ INFO] [1511998711.183017716]: /image_rect -> /stereo/right/image_rect
[ INFO] [1511998711.192870027]: waitForService: Service [/nodelet_manager/load_nodelet] has not been advertised, waiting...
[ INFO] [1511998711.212457082]: waitForService: Service [/nodelet_manager/load_nodelet] has not been advertised, waiting...
[ INFO] [1511998711.305330010]: Initializing nodelet with 2 worker threads.
[ INFO] [1511998711.342899390]: Initializing nodelet with 2 worker threads.
[ INFO] [1511998711.376281932, 1403636632.755484881]: waitForService: Service [/nodelet_manager/load_nodelet] is now available.
[ INFO] [1511998711.381201138, 1403636632.765931872]: waitForService: Service [/nodelet_manager/load_nodelet] is now available.
crossCheck: 0
OpenCV: threads set to -1
nFeatures: 200
scaleFactor: 1.2
nLevels: 1
edgeThreshold: 31
firstLevel: 0
WTA_K: 2
scoreType: 0
patchSize: 31
fastThreshold: 20
nFeatures: 200
scaleFactor: 1.2
nLevels: 1
edgeThreshold: 31
firstLevel: 0
WTA_K: 2
scoreType: 0
patchSize: 31
fastThreshold: 20
bytes: 32
use_orientation: 0
bytes: 32
use_orientation: 0
[ INFO] [1511998712.006033681, 1403636633.388582162]: Loop Detector initializing, loading vocabulary
[ INFO] [1511998712.006946590, 1403636633.388582162]: Loop Detector could not initialize
Could not open file /home/haidara/catkin_ws/src/sptam/bow_voc/DBoW2/brief_mit_malaga_vocabulary.yml.gz
[ INFO] [1511998713.929126638, 1403636635.313204420]: S-PTAM stereo node initialized.
[ INFO] [1511998714.133194475, 1403636635.517002960]: init calib
[ INFO] [1511998714.133504417, 1403636635.517002960]: baseline: 0.110078
[ INFO] [1511998714.145918393, 1403636635.527508501]: Trying to intialize map...
[ INFO] [1511998714.161651899, 1403636635.537672623]: Map initialized with 105 points.
[sptam-10] process has died [pid 22941, exit code -11, cmd /home/haidara/catkin_ws/devel/lib/sptam/sptam_node /stereo/left/camera_info:=/cam0/camera_info /stereo/right/camera_info:=/cam1/camera_info robot/pose:=odom __name:=sptam __log:=/home/haidara/.ros/log/932ace70-d558-11e7-9157-000c29704879/sptam-10.log].
log file: /home/haidara/.ros/log/932ace70-d558-11e7-9157-000c29704879/sptam-10.log
*

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.