Giter VIP home page Giter VIP logo

cartographer-project / cartographer Goto Github PK

View Code? Open in Web Editor NEW
7.0K 385.0 2.2K 5.8 MB

Cartographer is a system that provides real-time simultaneous localization and mapping (SLAM) in 2D and 3D across multiple platforms and sensor configurations.

License: Apache License 2.0

CMake 1.60% C++ 95.77% Lua 0.57% Python 0.40% Shell 0.50% XSLT 0.09% Batchfile 0.04% Starlark 0.99% C 0.03%
slam mapping localization robotics self-driving

cartographer's Introduction

Cartographer

Ubuntu 22.04 Build Status Ubuntu 20.04 Build Status Ubuntu 18.04 Build Status Debian Bullseye Build Status Debian Buster Build Status Documentation Status Apache 2 license.

Purpose

Cartographer is a system that provides real-time simultaneous localization and mapping (SLAM) in 2D and 3D across multiple platforms and sensor configurations.

Cartographer 3D SLAM Demo

A Note for ROS Users

Cartographer is no longer actively maintained. On rare occasions critical pull requests may be merged, but no new development is currently taking place, including issue response. If you are installing Cartographer in ROS 1 / ROS 2 using a binary package that package is a fork of this repository. The ROS fork of Cartographer is only maintained in a limited capacity. No new development takes place on this fork, but pull requests may be merged at the maintainers' discretion.

The ROS fork of Cartographer, and the ROS wrapper library, can be found at these locations:

Additional discussion can be found in this ROS Discourse thread.

Getting started

Contributing

You can find information about contributing to Cartographer at our Contribution page.

Open house slide archive

In the past there had been regular open-for-all meetings to discuss progress and plans for Cartographer. Slides of these Cartographer Open House meetings are listed below.

cartographer's People

Contributors

at-wat avatar brandon-northcutt avatar catskul avatar clalancette avatar codearno avatar damienrg avatar damonkohler avatar danielsievers avatar drigz avatar facontidavide avatar gaschler avatar jihoonl avatar jkammerl avatar jspricke avatar klwkbin avatar macmason avatar mbokeloh avatar michaelgrupp avatar mofef avatar ojura avatar pifon2a avatar schwoere avatar sebastianklose avatar sirver avatar sotnik-github avatar spielawa avatar stevewolter avatar wjwwood avatar wohe avatar zjwoody 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  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

cartographer's Issues

when can call finish_trajectory service?

when i call the service of finish_trajectory,it often return error:ERROR: transport error completing service call: unable to receive data from sender, check sender's logs for details,but What time is the right time?

install error about gtest

I'm installing cartographer_ros in ubuntu 14.04 and ROS indigo.
gcc version is 4.8.
Through the instruction of
https://google-cartographer-ros.readthedocs.io/en/latest/
I build a ros-workspace named cartographer_ws(Cause I already have a workspace named catkin_ws)
When I try to execute
catkin_make_isolated --install --use-ninja

I got output like that:

==> Processing catkin package: 'cartographer_ros'
==> Building with env: '/home/tyler/cartographer_ws/install_isolated/env.sh'
==> cmake /home/tyler/cartographer_ws/src/cartographer_ros/cartographer_ros -DCATKIN_DEVEL_PREFIX=/home/tyler/cartographer_ws/devel_isolated/cartographer_ros -DCMAKE_INSTALL_PREFIX=/home/tyler/cartographer_ws/install_isolated -G Ninja in '/home/tyler/cartographer_ws/build_isolated/cartographer_ros'
-- Found required Ceres dependency: Eigen version 3.2.8 in /usr/local/include/eigen3
-- Found required Ceres dependency: Glog in /usr/include
-- Found Ceres version: 1.11.0 installed in: /home/tyler/cartographer_ws/install_isolated
-- Build type: Release
-- Using CATKIN_DEVEL_PREFIX: /home/tyler/cartographer_ws/devel_isolated/cartographer_ros
-- Using CMAKE_PREFIX_PATH: /home/tyler/cartographer_ws/install_isolated;/opt/ros/indigo
-- This workspace overlays: /home/tyler/cartographer_ws/install_isolated;/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: /home/tyler/cartographer_ws/build_isolated/cartographer_ros/test_results
-- Found gtest: gtests will be built
CMake Error at /opt/ros/indigo/share/catkin/cmake/test/gtest.cmake:154 (add_library):
  add_library cannot create imported target "gtest" because another target
  with the same name already exists.
Call Stack (most recent call first):
  /opt/ros/indigo/share/catkin/cmake/all.cmake:147 (include)
  /opt/ros/indigo/share/catkin/cmake/catkinConfig.cmake:20 (include)
  CMakeLists.txt:36 (find_package)


CMake Error at /opt/ros/indigo/share/catkin/cmake/test/gtest.cmake:156 (add_library):
  add_library cannot create imported target "gtest_main" because another
  target with the same name already exists.
Call Stack (most recent call first):
  /opt/ros/indigo/share/catkin/cmake/all.cmake:147 (include)
  /opt/ros/indigo/share/catkin/cmake/catkinConfig.cmake:20 (include)
  CMakeLists.txt:36 (find_package)


-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.6.18
-- Using these message generators: gencpp;genlisp;genpy
-- Boost version: 1.54.0
-- Found the following Boost libraries:
--   system
--   filesystem
--   thread
--   date_time
--   iostreams
--   serialization
--   chrono
** WARNING ** io features related to pcap will be disabled
** WARNING ** io features related to png will be disabled
-- looking for PCL_COMMON
-- looking for PCL_OCTREE
-- looking for PCL_IO
-- Boost version: 1.54.0
-- Found the following Boost libraries:
--   system
--   iostreams
-- Configuring incomplete, errors occurred!
See also "/home/tyler/cartographer_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeOutput.log".
See also "/home/tyler/cartographer_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeError.log".
<== Failed to process package 'cartographer_ros': 
  Command '['/home/tyler/cartographer_ws/install_isolated/env.sh', 'cmake', '/home/tyler/cartographer_ws/src/cartographer_ros/cartographer_ros', '-DCATKIN_DEVEL_PREFIX=/home/tyler/cartographer_ws/devel_isolated/cartographer_ros', '-DCMAKE_INSTALL_PREFIX=/home/tyler/cartographer_ws/install_isolated', '-G', 'Ninja']' returned non-zero exit status 1

Reproduce this error by running:
==> cd /home/tyler/cartographer_ws/build_isolated/cartographer_ros && /home/tyler/cartographer_ws/install_isolated/env.sh cmake /home/tyler/cartographer_ws/src/cartographer_ros/cartographer_ros -DCATKIN_DEVEL_PREFIX=/home/tyler/cartographer_ws/devel_isolated/cartographer_ros -DCMAKE_INSTALL_PREFIX=/home/tyler/cartographer_ws/install_isolated -G Ninja

Command failed, exiting.

When I directly install in in the catkin_ws, I got the same error.

Support non-Ubuntu-package version of gmock and gtest

cmake/functions.cmake depends on Ubuntu package version of gmock and gtest install.

macro(google_enable_testing)
  set(GMOCK_SRC_DIR "/usr/src/gmock" CACHE STRING "Path to google-mock sources.")
  add_subdirectory(${GMOCK_SRC_DIR} "${CMAKE_CURRENT_BINARY_DIR}/gmock")

For example in Fedora 24, /usr/src/gmock does not contains CMakeLists.txt.

Latest (1.8+) version of googletest (containing gmock) supports system wide install again.
So, add_subdirectory for gmock will be no longer required in latest gtest environment.
(I have just commented out these lines for my build.)

Also, in environments with a built-from-source version of gmock, libgmock_main requires linking pthread.
I have simply modified macro(_common_test_stuff) as following:

diff --git a/cmake/functions.cmake b/cmake/functions.cmake
index 27f0beb..031412e 100644
--- a/cmake/functions.cmake
+++ b/cmake/functions.cmake
@@ -221,7 +221,7 @@ macro(_common_test_stuff)
   # Make sure that gmock always includes the correct gtest/gtest.h.
   target_include_directories("${NAME}" SYSTEM PRIVATE
     "${GMOCK_SRC_DIR}/gtest/include")
-  target_link_libraries("${NAME}" gmock_main)
+  target_link_libraries("${NAME}" gmock_main pthread)
 endmacro()

 function(google_catkin_test NAME)

(This hard-code should be replaced using find_package.)

Currently, I could not make a PR about this since I have not understood the structure of Google-style CMake.

Is that possible to manually indicate loops?

Thanks to this great work , cartographer works very well in indoor environment.
I am current using cartographer to map a large area, but I found the loop closure does not work in such environment.

image

In the picture , the two branches are actually the same place. Are there any APIs for manually fixing error loop detection?

build error

when i catkin_make the cartographer_ros packet,it always print an error:

-- +++ processing catkin package: 'cartographer_ros_msgs'
-- ==> add_subdirectory(cartographer_ros-master/cartographer_ros_msgs)
-- Found required Ceres dependency: Eigen version 3.2.0 in /usr/include/eigen3
-- Found required Ceres dependency: Glog in /usr/include
-- Found Ceres version: 1.11.0 installed in: /usr/local
CMake Error at cartographer_ros-master/cartographer_ros_msgs/CMakeLists.txt:24 (include):
include could not find load file:

/functions.cmake

CMake Error at cartographer_ros-master/cartographer_ros_msgs/CMakeLists.txt:25 (google_initialize_cartographer_project):
Unknown CMake command "google_initialize_cartographer_project".

-- Configuring incomplete, errors occurred!
See also "/home/viki/catkin_ws/build/CMakeFiles/CMakeOutput.log".
See also "/home/viki/catkin_ws/build/CMakeFiles/CMakeError.log".
make: *** [cmake_check_build_system] Error 1
Invoking "make cmake_check_build_system" failed
i can't understand it,please help me.

Problems with GMock

Version of GMock 1.6.0+svn437-0ubuntu5 (installed from the repos)
Version of Ubuntu 14.04

Please refer to the error below. This seems to be happening since four days ago?? Can it be a problem with the GMock version that is being used? the last version that I can find at link is the 1.8 version... the code already compiled with success before, I will try to revert this last commits to verify if the error persists, if the error happen because the version of GMock installed please update the minimum version needed to compile the project.

Many thanks in advance if some one can help with this problems.
And great work guys :)

In file included from /usr/include/gmock/gmock-actions.h:46:0, from /usr/include/gmock/gmock.h:58, from /home/andre/RosWorkspaces/catkin_ws/src/cartographer/cartographer/transform/rigid_transform_test_helpers.h:26, from /home/andre/RosWorkspaces/catkin_ws/src/cartographer/cartographer/kalman_filter/pose_tracker_test.cc:25: /usr/include/gmock/internal/gmock-internal-utils.h: In static member function ‘static testing::internal::StlContainerView<Element [N]>::const_reference testing::internal::StlContainerView<Element [N]>::ConstReference(const Element (&)[N])’: /usr/include/gmock/internal/gmock-internal-utils.h:439:27: error: ‘kReference’ was not declared in this scope return type(array, N, kReference); ^ /usr/include/gmock/internal/gmock-internal-utils.h: In static member function ‘static testing::internal::StlContainerView<Element [N]>::type testing::internal::StlContainerView<Element [N]>::Copy(const Element (&)[N])’: /usr/include/gmock/internal/gmock-internal-utils.h:446:27: error: ‘kCopy’ was not declared in this scope return type(array, N, kCopy); ^ /usr/include/gmock/internal/gmock-internal-utils.h: In static member function ‘static testing::internal::StlContainerView<std::tuple<_T1, _T2> >::const_reference testing::internal::StlContainerView<std::tuple<_T1, _T2> >::ConstReference(const std::tuple<_T1, _T2>&)’: /usr/include/gmock/internal/gmock-internal-utils.h:464:47: error: ‘kReference’ was not declared in this scope return type(get<0>(array), get<1>(array), kReference); ^ /usr/include/gmock/internal/gmock-internal-utils.h: In static member function ‘static testing::internal::StlContainerView<std::tuple<_T1, _T2> >::type testing::internal::StlContainerView<std::tuple<_T1, _T2> >::Copy(const std::tuple<_T1, _T2>&)’: /usr/include/gmock/internal/gmock-internal-utils.h:468:47: error: ‘kCopy’ was not declared in this scope return type(get<0>(array), get<1>(array), kCopy); ^ In file included from /home/andre/RosWorkspaces/catkin_ws/src/cartographer/cartographer/kalman_filter/pose_tracker_test.cc:22:0: /home/andre/RosWorkspaces/catkin_ws/src/cartographer/cartographer/common/lua_parameter_dictionary_test_helpers.h: In member function ‘virtual std::string cartographer::common::DummyFileResolver::GetFileContentOrDie(const string&)’: /home/andre/RosWorkspaces/catkin_ws/src/cartographer/cartographer/common/lua_parameter_dictionary_test_helpers.h:42:3: error: control reaches end of non-void function [-Werror=return-type] } ^ /home/andre/RosWorkspaces/catkin_ws/src/cartographer/cartographer/common/lua_parameter_dictionary_test_helpers.h: In member function ‘virtual std::string cartographer::common::DummyFileResolver::GetFullPathOrDie(const string&)’: /home/andre/RosWorkspaces/catkin_ws/src/cartographer/cartographer/common/lua_parameter_dictionary_test_helpers.h:46:3: error: control reaches end of non-void function [-Werror=return-type] } ^ cc1plus: some warnings being treated as errors make[2]: *** [cartographer/kalman_filter/CMakeFiles/kalman_filter_pose_tracker_test.dir/pose_tracker_test.cc.o] Error 1 make[1]: *** [cartographer/kalman_filter/CMakeFiles/kalman_filter_pose_tracker_test.dir/all] Error 2 make: *** [all] Error 2 andre@prtandre:~/RosWorkspaces/catkin_ws/src/cartographer/build$ sudo apt-cache google-mock [sudo] password for andre: andre@prtandre:~/RosWorkspaces/catkin_ws/src/cartographer/build$ apt-cache google-mock E: Invalid operation google-mock andre@prtandre:~/RosWorkspaces/catkin_ws/src/cartographer/build$ apt-cache info google-mock E: Invalid operation info

request ROS Indigo binary release

We are interested in running this package on multiple robots of the UTexas Building-Wide Intelligence project. It would be very helpful to have a ROS Indigo release for cartographer which we could depend on.

If you are not familiar with the process of creating ROS binary releases, the bloom package works great. After some initial setup, the job is quick and easy.

I am willing to assist by answering questions, as are the other members of the ROS discourse release category.

I believe other ROS users would also benefit from having a binary release available.

cc: @jsinapov, @Ashay-Lokhande

Expose pose estimate in between scan matches

Currently, pose estimates are only available after a scan match. We should expose the current estimate in between scan matches for use cases that require higher frequency estimates than scan matching can provide.

about the global loop-closure optimization between sub-maps

I think the global loop-closure optimization algorithm has an not small problem and bug in practical application , because it will lead to the entire map mapping errors and useless !

I will upload my bag file, some can download it to test for datails.

Results get worse compared to commit 116

We started working with the cartographer in the end of october. So we started with the version 116. We worked on that Version till early january. We decided to go onto the newest Version at that point and had no problem running the rosbag again. The only difference was the result. We tried a few weeks to get it to a result as good as befor, but couldnt get it running. We wrote a shell script to auto test some parameters, this got us a better result, but still not as good as befor. As reference we had a mobile mapping system from riegel (similar to this http://www.riegl.com/nc/products/mobile-scanning/produktdetail/product/scanner/53/)
We also integrated the gps fix from the xsens to get better result, this did not made a big difference as the xsens uses a internal filter.

We are using a Sick lms500 and a xsens as imu. They were mounted on a Van and we were driving around near our university. We are working in postprocessing on a VM with xubuntu 14.04. (4cores 16gb ram)

To the Results:
Version 116:
a4_t1

Parameter test results:
autoparameter_angepasst17-01
(this is with gps as odom, thats why its rotated)

We did read some of the commit msgs, but could not really find out which step made our results getting worse. Maybe someone of you can find the problem.

I m attaching the rosbag, the configuration files, launchfiles and urdf modells. (old and new Version, the other configurations were not changed)
Also I m attaching a program with remaps the imu-data, because we had problems doing it with the ros-internal tools. Also this has the program for the gpsfix to utm conversion node. (this are in the folder cartographer_fue and are build in a normal catkin_ws with catkin_make )
As github just supports 10mb uploads, the files are on google-drive: https://drive.google.com/open?id=0B0ht7RlOmWvLX0UzalhycGdLVjg

If you need some new Information or I missed some needed information feel free to ask.

Can I use a Velodyne VLP-16 lidar for 3D reconstruction?

3D mapping you have tow lidars,a horizontal_laser_3d can do it too,but a vertical_laser_3d always failed, Can I use a tilted laser to mapping,(eg. A Velodyne VLP-16 lidar with a tilt of 45 degrees)to get trajectory and reconstruction?

Cross compiling error: LIbDl linking issue

Hello,
I am cross compiling cartographer-ros and it seems in the generated link.txt, "-ldl" is missing for libraries using LUA.

During the linking step, for those files, I get the error:

undefined reference to symbol 'dlsym@@GLIBC_2.4'

It simply means the libdl is not linked properly with the lua dependant files.
I tried modifying the find lua function since the -ldl needs to be right before the -lm but without success.

I am cross-compiling for an arm 32 bits system using Yocto on Ubuntu 14.04. Everything goes well adding this flag manually but you may have an idea of making it more consistent.

Cartographer expects the IMU to point Z-wards

This report is a continuation of this thread on the Cartographer Google group. I think @SirVer is right, that Cartographer simply expects that the IMU is mounted with the z axis pointing upwards. The warning is caused by the following check in cartographer/mapping_2d/local_trajectory_builder.cc, which calculates the inclination of the IMU tracker orientation estimate from the z axis and complains if > 20:

  // Log a warning if the backpack inclination exceeds 20 degrees. In these
  // cases, it's very likely that 2D SLAM will fail.
  const Eigen::Vector3d gravity_direction =
      imu_tracker_->orientation() * Eigen::Vector3d::UnitZ();
  const double inclination = std::acos(gravity_direction.z());

If this assumption is not fulfilled (in our example, the IMU is mounted with the y axis pointing up), this inclination amounts to approximately 90 degrees and causes these seemingly harmless warnings about the maximum inclination being exceeded. Other than that, Cartographer seems to work fine.

I am not sure if I can definitely propose how to solve this. Perhaps this check can be rethought - e.g. transform the IMU tracker orientation estimate into the laser sensor frame, which by standard conventions should definitely have its z axis pointing up; then apply the check above in the same way.

If you would like to have a look for yourself, I have prepared an example bag which matches the situation described in the Google groups thread. To run, go into the launch folder and execute roslaunch t20_cartographer.launch from there.

velodyne frequency

The frequency of the topic of vertical_laser_3d or horizontal_laser_3d in your ros bag data is about 1527HZ,but the frequency of the velodyne 16 is 10HZ,Why?How do you split the data of the laser scans from the velodyne's lidar?Excuse me for my bad english!

Global loop closure optimization breaks the map

Hello guys,

i am testing cartographer now since few weeks and have occasionally the problem, that the global loop closure optimization makes the almost perfect map much worse.

See this example:
image
(before optimization)

image
(after optimization)

I am running cartographer with a 2d lidar (40hz, <60m range) and an imu (40hz) on ubuntu 14.04, ros indigo. I use the latest sources of cartographer.

You can find here an example bag files to reproduce the issue i am describing: https://drive.google.com/file/d/0B9jUq7WkDIxbOE95cHhJVGlPMFU/view
The lua configuration i use:
https://drive.google.com/open?id=0B9jUq7WkDIxbbkVXRjBYanNRT00
Launch file:
https://drive.google.com/open?id=0B9jUq7WkDIxbdkRyaGxDbU5lTnc

I read in #127 the advice increasing the huber_scale and min_score. I played around with different values and in many cases the quality of the map is getting worse.

Is the cause for worse maps in my case the same reasons as described in #127? Are their any other parameters one can/should tune for getting the global optimization produce more "stable" results?

Thanks in advance!

std container types of Eigen matrix types missing eigen allocators

Per https://eigen.tuxfamily.org/dox-devel/group__TopicStlContainers.html

Using STL containers on fixed-size vectorizable Eigen types, or classes having members of such types, requires special handling.

Either std container types should use the Eigen::aligned_allocator (preferred)

or a container specialization that has the same effect.

A first attempt to grep for instances that are missing aligned allocators yields a number of apparent cases where std::vector requires an aligned allocator.

$ grep -r "std::\w*<Eigen" 
cartographer/mapping_2d/ray_casting.cc:  std::vector<Eigen::Array2i> ends;
cartographer/mapping_2d/scan_matching/correlative_scan_matcher.h:typedef std::vector<Eigen::Array2i> DiscreteScan;
cartographer/mapping_3d/hybrid_grid.h:    const std::pair<Eigen::Array3i, ValueType> operator*() const {
cartographer/mapping_3d/hybrid_grid.h:      return std::pair<Eigen::Array3i, ValueType>(GetCellIndex(), GetValue());
cartographer/mapping_3d/submaps.h:  std::vector<Eigen::Array4i> voxel_indices_and_probabilities_;
cartographer/mapping_3d/scan_matching/fast_correlative_scan_matcher.h:  std::vector<std::vector<Eigen::Array3i>> cell_indices_per_depth;
cartographer/mapping_3d/scan_matching/fast_correlative_scan_matcher.cc:  std::vector<std::vector<Eigen::Array3i>> cell_indices_per_depth;
cartographer/mapping_3d/scan_matching/fast_correlative_scan_matcher.cc:  std::vector<Eigen::Array3i> full_resolution_cell_indices;
cartographer/mapping_3d/kalman_local_trajectory_builder_test.cc:  std::vector<Eigen::Vector3f> bubbles_;
cartographer/kalman_filter/unscented_kalman_filter.h:      std::function<Eigen::Matrix<FloatType, K, 1>(const StateType&)> h,
cartographer/kalman_filter/unscented_kalman_filter.h:    std::vector<Eigen::Matrix<FloatType, K, 1>> Z;
cartographer/sensor/point_cloud.h:typedef std::vector<Eigen::Vector3f> PointCloud;
cartographer/sensor/point_cloud.h:typedef std::vector<Eigen::Vector2f> PointCloud2D;
cartographer/sensor/laser_test.cc:  std::vector<std::pair<Eigen::Vector3f, int>> pairs;
cartographer/sensor/laser_test.cc:              Contains(PairApproximatelyEquals(std::pair<Eigen::Vector3f, int>(
cartographer/sensor/laser_test.cc:              Contains(PairApproximatelyEquals(std::pair<Eigen::Vector3f, int>(
cartographer/sensor/laser_test.cc:              Contains(PairApproximatelyEquals(std::pair<Eigen::Vector3f, int>(

I'll try to produce a pull request fixing this issue unless someone can indicate not an issue in this case for some reason unaware of.

can not build the cartographer in x86 ubuntu 14.04

error at:
[245/327] Building CXX object cartogra...dir/fast_correlative_scan_matcher.cc.o
FAILED: /usr/bin/c++ -O3 -DNDEBUG -isystem /usr/include/eigen3 -isystem /usr/local/include -I. -I.. -I../cartographer/common/{Boost_INCLUDE_DIRS} -isystem /usr/include/lua5.2 -O3 -DNDEBUG -std=c++11 -Wall -Wpedantic -Werror=format-security -Werror=return-type -Werror=uninitialized -MMD -MT cartographer/mapping_2d/scan_matching/CMakeFiles/mapping_2d_scan_matching_fast_correlative_scan_matcher.dir/fast_correlative_scan_matcher.cc.o -MF "cartographer/mapping_2d/scan_matching/CMakeFiles/mapping_2d_scan_matching_fast_correlative_scan_matcher.dir/fast_correlative_scan_matcher.cc.o.d" -o cartographer/mapping_2d/scan_matching/CMakeFiles/mapping_2d_scan_matching_fast_correlative_scan_matcher.dir/fast_correlative_scan_matcher.cc.o -c ../cartographer/mapping_2d/scan_matching/fast_correlative_scan_matcher.cc
In file included from /opt/eigen/Eigen/Geometry:39:0,
from /opt/eigen/Eigen/Dense:6,
from /usr/local/include/ceres/internal/numeric_diff.h:40,
from /usr/local/include/ceres/dynamic_numeric_diff_cost_function.h:70,
from /usr/local/include/ceres/ceres.h:44,
from ../cartographer/common/math.h:25,
from ../cartographer/mapping_2d/probability_grid.h:28,
from ../cartographer/mapping_2d/scan_matching/fast_correlative_scan_matcher.h:33,
from ../cartographer/mapping_2d/scan_matching/fast_correlative_scan_matcher.cc:17:
/opt/eigen/Eigen/src/Geometry/Rotation2D.h: In instantiation of ‘Eigen::Rotation2D Eigen::Rotation2D::operator_(const Eigen::Rotation2D&) const [with Scalar = double]’:
../cartographer/mapping_2d/scan_matching/fast_correlative_scan_matcher.cc:270:73: required from here
/opt/eigen/Eigen/src/Geometry/Rotation2D.h:78:28: error: could not convert ‘(((Eigen::Rotation2D::Scalar)((const Eigen::Rotation2D
)this)->Eigen::Rotation2D::m_angle) + ((Eigen::Rotation2D::Scalar)other.Eigen::Rotation2D::m_angle))’ from ‘Eigen::Rotation2D::Scalar {aka double}’ to ‘Eigen::Rotation2D’
{ return m_angle + other.m_angle; }
^
[245/327] Building CXX object cartogra...eal_time_correlative_scan_matcher.cc.o
FAILED: /usr/bin/c++ -O3 -DNDEBUG -isystem /usr/include/eigen3 -isystem /usr/local/include -I. -I.. -isystem /usr/include/lua5.2 -I../cartographer/common/{Boost_INCLUDE_DIRS} -O3 -DNDEBUG -std=c++11 -Wall -Wpedantic -Werror=format-security -Werror=return-type -Werror=uninitialized -MMD -MT cartographer/mapping_2d/scan_matching/CMakeFiles/mapping_2d_scan_matching_real_time_correlative_scan_matcher.dir/real_time_correlative_scan_matcher.cc.o -MF "cartographer/mapping_2d/scan_matching/CMakeFiles/mapping_2d_scan_matching_real_time_correlative_scan_matcher.dir/real_time_correlative_scan_matcher.cc.o.d" -o cartographer/mapping_2d/scan_matching/CMakeFiles/mapping_2d_scan_matching_real_time_correlative_scan_matcher.dir/real_time_correlative_scan_matcher.cc.o -c ../cartographer/mapping_2d/scan_matching/real_time_correlative_scan_matcher.cc
In file included from /opt/eigen/Eigen/Geometry:39:0,
from /opt/eigen/Eigen/Dense:6,
from /usr/local/include/ceres/internal/numeric_diff.h:40,
from /usr/local/include/ceres/dynamic_numeric_diff_cost_function.h:70,
from /usr/local/include/ceres/ceres.h:44,
from ../cartographer/common/math.h:25,
from ../cartographer/mapping_2d/probability_grid.h:28,
from ../cartographer/mapping_2d/scan_matching/real_time_correlative_scan_matcher.h:44,
from ../cartographer/mapping_2d/scan_matching/real_time_correlative_scan_matcher.cc:17:
/opt/eigen/Eigen/src/Geometry/Rotation2D.h: In instantiation of ‘Eigen::Rotation2D Eigen::Rotation2D::operator_(const Eigen::Rotation2D&) const [with Scalar = double]’:
../cartographer/mapping_2d/scan_matching/real_time_correlative_scan_matcher.cc:123:71: required from here
/opt/eigen/Eigen/src/Geometry/Rotation2D.h:78:28: error: could not convert ‘(((Eigen::Rotation2D::Scalar)((const Eigen::Rotation2D
)this)->Eigen::Rotation2D::m_angle) + ((Eigen::Rotation2D::Scalar)other.Eigen::Rotation2D::m_angle))’ from ‘Eigen::Rotation2D::Scalar {aka double}’ to ‘Eigen::Rotation2D’
{ return m_angle + other.m_angle; }
^
[245/327] Building CXX object cartogra....dir/trajectory_connectivity_test.cc.o

ninja: build stopped: subcommand failed.

plz help~

why two lidars?

2D mapping only need one horizontal lidar,but your bag data always have another vertical_laser_2d,why?

3d model

if the cartograper can save a 3d point cloud model of the scanning room , how do it?

location perform not well

hi,firstly thanks for your work.When I use the package with my robot I face with a problem that the location information from cartographer seem wave largely ,and sometimes I even suspect the (x,y) is reversal,which is (y,x)!! I use only an URG-10LX for the sensor,the laser works well with gmapping package.
here is my .lua format:

include "map_builder.lua"
options = {
  map_builder = MAP_BUILDER,
  sensor_bridge = {
    horizontal_laser_min_range = 0.3,
    horizontal_laser_max_range = 5.6,
    horizontal_laser_missing_echo_ray_length = 1.2,
    constant_odometry_translational_variance = 0.,
    constant_odometry_rotational_variance = 0.,
  },
  map_frame = "map",
  tracking_frame = "laser",
  published_frame = "laser",
  odom_frame = "odom",
  provide_odom_frame = true,
  use_odometry_data = false,
  use_horizontal_laser = true,
  use_horizontal_multi_echo_laser = false,
  num_lasers_3d = 0,
  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
}
MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e2
return options

Edited by @SirVer: formatting

pass-by-value on Eigen types may cause alignment issues

Per Eigen docs, passing eign types by value may cause alignment issues and unexplained crashes:

http://eigen.tuxfamily.org/dox-devel/group__TopicPassingByValue.html

At least two instance of this exist in the project.

./cartographer/transform/transform.h

template <typename T>
Eigen::Matrix<T, 3, 1> RotationQuaternionToAngleAxisVector( Eigen::Quaternion<T> quaternion) 

and

template <typename T>
Eigen::Quaternion<T> AngleAxisVectorToRotationQuaternion(Eigen::Matrix<T, 3, 1> angle_axis)

There may be others.

Build failure on Debian testing

Building cartographer fails on Debian testing. Googletest version is 1.8.0-6 (Debian)

Build output is as follows:

==> make cmake_check_build_system in '/opt/ros/ros_catkin_ws/build_isolated/cartographer/install'
-- Build type: Release
-- Found PythonInterp: /usr/bin/python (found version "2.7.13") 
CMake Error at /usr/src/googletest/googletest/cmake/internal_utils.cmake:149 (add_library):
  add_library cannot create target "gmock" because another target with the
  same name already exists.  The existing target is a static library created
  in source directory "/usr/src/googletest/googlemock".  See documentation
  for policy CMP0002 for more details.
Call Stack (most recent call first):
  /usr/src/googletest/googletest/cmake/internal_utils.cmake:172 (cxx_library_with_type)
  /usr/src/gmock/CMakeLists.txt:84 (cxx_library)


CMake Error at /usr/src/googletest/googletest/cmake/internal_utils.cmake:149 (add_library):
  add_library cannot create target "gmock_main" because another target with
  the same name already exists.  The existing target is a static library
  created in source directory "/usr/src/googletest/googlemock".  See
  documentation for policy CMP0002 for more details.
Call Stack (most recent call first):
  /usr/src/googletest/googletest/cmake/internal_utils.cmake:172 (cxx_library_with_type)
  /usr/src/gmock/CMakeLists.txt:89 (cxx_library)


CMake Error at /usr/src/gmock/CMakeLists.txt:106 (install):
  install TARGETS given target "gmock" which does not exist in this
  directory.


-- Found GMock: gmock_main;-lpthread  
-- Boost version: 1.62.0
-- Found the following Boost libraries:
--   iostreams
--   regex
-- Found required Ceres dependency: Eigen version 3.3.0 in /usr/include/eigen3
-- Found required Ceres dependency: glog
-- Found Ceres version: 1.12.0 installed in: /usr/local with components: [LAPACK, SchurSpecializations, OpenMP]
-- Configuring incomplete, errors occurred!
See also "/opt/ros/ros_catkin_ws/build_isolated/cartographer/install/CMakeFiles/CMakeOutput.log".
See also "/opt/ros/ros_catkin_ws/build_isolated/cartographer/install/CMakeFiles/CMakeError.log".
Makefile:3786: die Regel f?r Ziel ?cmake_check_build_system? scheiterte
make: *** [cmake_check_build_system] Fehler 1
<== Failed to process package 'cartographer': 
  Command '['/usr/local/env.sh', 'make', 'cmake_check_build_system']' returned non-zero exit status 2

Reproduce this error by running:
==> cd /opt/ros/ros_catkin_ws/build_isolated/cartographer && /usr/local/env.sh make cmake_check_build_system

Command failed, exiting.

Cartographer worse than Gmapping

Launch file, Bag ,Configuration is here.

I tested the same bag file in gmapping and cartographer. The two results are listed as follows,

Cartographer,
image

Just like I mentioned in #190 , the loop closure detection did not work.

Gmapping(which is very similar to the real environment),
image

Since I had already combined imu data into odom(/odometry/filtered in the ros bag), I did not provide the raw imu data(/costly_imu in the ros bag) to both slam.

Would you @SirVer please tell what should I do next?

Thanks very much.

Structs and classes containing eigen typed data members missing EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Per docs classes and structs containing eigen types require EIGEN_MAKE_ALIGNED_OPERATOR_NEW to be safely allocated on the heap.

https://eigen.tuxfamily.org/dox-devel/group__TopicStructHavingEigenMembers.html

The following incomplete list may violate this requirement:

$ find ./ -name "*.h*" | xargs grep --color "^[^(]*Eigen::[^(&={]*$"
./cartographer/transform/rigid_transform.h:  using Affine = Eigen::Transform<FloatType, 2, Eigen::Affine>;
./cartographer/transform/rigid_transform.h:  using Vector = Eigen::Matrix<FloatType, 2, 1>;
./cartographer/transform/rigid_transform.h:  using Rotation2D = Eigen::Rotation2D<FloatType>;
./cartographer/transform/rigid_transform.h:  using Affine = Eigen::Transform<FloatType, 3, Eigen::Affine>;
./cartographer/transform/rigid_transform.h:  using Vector = Eigen::Matrix<FloatType, 3, 1>;
./cartographer/transform/rigid_transform.h:  using Quaternion = Eigen::Quaternion<FloatType>;
./cartographer/transform/rigid_transform.h:  using AngleAxis = Eigen::AngleAxis<FloatType>;
./cartographer/mapping_2d/map_limits.h:  Eigen::Vector2d max_;
./cartographer/mapping_2d/xy_index.h:  Eigen::Array2i min_xy_index_;
./cartographer/mapping_2d/xy_index.h:  Eigen::Array2i max_xy_index_;
./cartographer/mapping_2d/xy_index.h:  Eigen::Array2i xy_index_;
./cartographer/mapping_2d/scan_matching/correlative_scan_matcher.h:typedef std::vector<Eigen::Array2i> DiscreteScan;
./cartographer/mapping_2d/scan_matching/fast_correlative_scan_matcher.h:  const Eigen::Array2i offset_;
./cartographer/mapping_2d/scan_matching/occupied_space_cost_functor.h:    Eigen::Matrix<T, 3, 3> transform;
./cartographer/common/math.h:  Eigen::SelfAdjointEigenSolver<Eigen::Matrix<double, N, N>>
./cartographer/mapping_3d/rotation_cost_function.h:  const Eigen::Quaterniond delta_rotation_imu_frame_;
./cartographer/mapping_3d/acceleration_cost_function.h:  const Eigen::Vector3d delta_velocity_imu_frame_;
./cartographer/mapping_3d/hybrid_grid.h:  const Eigen::Vector3f origin_;
./cartographer/mapping_3d/imu_integration.h:  Eigen::Vector3d linear_acceleration;
./cartographer/mapping_3d/imu_integration.h:  Eigen::Vector3d angular_velocity;
./cartographer/mapping_3d/imu_integration.h:  Eigen::Matrix<T, 3, 1> delta_velocity;
./cartographer/mapping_3d/imu_integration.h:  Eigen::Quaternion<T> delta_rotation;
./cartographer/mapping_3d/submaps.h:                        Eigen::Array2i* min_index, Eigen::Array2i* max_index);
./cartographer/mapping_3d/submaps.h:  std::vector<Eigen::Array4i> voxel_indices_and_probabilities_;
./cartographer/mapping_3d/scan_matching/fast_correlative_scan_matcher.h:  std::vector<std::vector<Eigen::Array3i>> cell_indices_per_depth;
./cartographer/mapping_3d/scan_matching/fast_correlative_scan_matcher.h:  Eigen::Array3i offset;
./cartographer/mapping_3d/scan_matching/rotational_scan_matcher.h:  Eigen::VectorXf histogram_;
./cartographer/mapping/sparse_pose_graph.h:      Eigen::Matrix<double, 3, 3> sqrt_Lambda_ij;
./cartographer/mapping/sparse_pose_graph.h:      Eigen::Matrix<double, 6, 6> sqrt_Lambda_ij;
./cartographer/mapping/submaps.h:  Eigen::Vector3f origin;
./cartographer/kalman_filter/unscented_kalman_filter.h:  Eigen::SelfAdjointEigenSolver<Eigen::Matrix<FloatType, N, N>>
./cartographer/kalman_filter/unscented_kalman_filter.h:  using StateType = Eigen::Matrix<FloatType, N, 1>;
./cartographer/kalman_filter/unscented_kalman_filter.h:  using StateCovarianceType = Eigen::Matrix<FloatType, N, N>;
./cartographer/kalman_filter/unscented_kalman_filter.h:    std::vector<Eigen::Matrix<FloatType, K, 1>> Z;
./cartographer/kalman_filter/pose_tracker.h:typedef Eigen::Matrix3d Pose2DCovariance;
./cartographer/kalman_filter/pose_tracker.h:typedef Eigen::Matrix<double, 6, 6> PoseCovariance;
./cartographer/kalman_filter/pose_tracker.h:  Eigen::Quaterniond orientation_;
./cartographer/kalman_filter/pose_tracker.h:  Eigen::Vector3d gravity_direction_;
./cartographer/kalman_filter/pose_tracker.h:  Eigen::Vector3d imu_angular_velocity_;
./cartographer/kalman_filter/pose_tracker.h:  using StateCovariance = Eigen::Matrix<double, kDimension, kDimension>;
./cartographer/kalman_filter/gaussian_distribution.h:  Eigen::Matrix<T, N, 1> mean_;
./cartographer/kalman_filter/gaussian_distribution.h:  Eigen::Matrix<T, N, N> covariance_;
./cartographer/sensor/compressed_point_cloud.h:  Eigen::Vector3f current_point_;
./cartographer/sensor/compressed_point_cloud.h:  Eigen::Vector3i current_block_coordinates_;
./cartographer/sensor/laser.h:  Eigen::Vector2f origin;
./cartographer/sensor/laser.h:  Eigen::Vector3f origin;
./cartographer/sensor/laser.h:  Eigen::Vector3f origin;
./cartographer/sensor/point_cloud.h:typedef std::vector<Eigen::Vector3f> PointCloud;
./cartographer/sensor/point_cloud.h:typedef std::vector<Eigen::Vector2f> PointCloud2D;

build on mac

Hi,

I try to follow the installation guide and compile this software on a mac os 10.12 (Don't know whether you have already supported this platform), and encountered the following problem with generating cmake files:

Tianweis-Macbook:build STW$ cmake ..
-- Build type: Release
CMake Error at cmake/functions.cmake:356 (add_subdirectory):
add_subdirectory given source "/usr/src/gmock" which is not an existing
directory.
Call Stack (most recent call first):
CMakeLists.txt:26 (google_enable_testing)

-- Boost version: 1.61.0
-- Found the following Boost libraries:
-- system
-- iostreams
-- regex
-- Found required Ceres dependency: Eigen version 3.2.9 in /usr/local/include/eigen3
-- Found required Ceres dependency: Glog in /usr/local/include
-- Found Ceres version: 1.11.0 installed in: /usr/local
-- Found Lua: /usr/local/lib/liblua.5.2.dylib (found version "5.2.4")
CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/common/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/common/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:21 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:31 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:42 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:47 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:59 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:68 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:78 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:84 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:95 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:105 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:110 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:119 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:126 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:135 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:141 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:150 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/common/CMakeLists.txt:160 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/common/CMakeLists.txt:169 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/common/CMakeLists.txt:178 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/common/CMakeLists.txt:185 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/common/CMakeLists.txt:194 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/common/CMakeLists.txt:201 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/common/CMakeLists.txt:209 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/kalman_filter/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/kalman_filter/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/kalman_filter/CMakeLists.txt:17 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/kalman_filter/CMakeLists.txt:23 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/kalman_filter/CMakeLists.txt:33 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/kalman_filter/CMakeLists.txt:53 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/kalman_filter/CMakeLists.txt:62 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/kalman_filter/CMakeLists.txt:69 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/kalman_filter/CMakeLists.txt:81 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping/proto/CMakeLists.txt:24 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping/proto/CMakeLists.txt:24 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping/proto/CMakeLists.txt:29 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping/proto/CMakeLists.txt:29 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping/proto/CMakeLists.txt:37 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping/proto/CMakeLists.txt:37 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping/proto/CMakeLists.txt:44 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping/proto/CMakeLists.txt:44 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping/sparse_pose_graph/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping/sparse_pose_graph/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping/sparse_pose_graph/proto/CMakeLists.txt:26 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping/sparse_pose_graph/proto/CMakeLists.txt:26 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/sparse_pose_graph/CMakeLists.txt:17 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/sparse_pose_graph/CMakeLists.txt:32 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:18 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:31 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:60 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:71 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:83 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:100 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:117 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:129 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:139 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:146 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:157 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:165 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping/CMakeLists.txt:172 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_2d/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_2d/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_2d/proto/CMakeLists.txt:20 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_2d/proto/CMakeLists.txt:20 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_2d/proto/CMakeLists.txt:32 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_2d/proto/CMakeLists.txt:32 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_2d/scan_matching/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_2d/scan_matching/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_2d/scan_matching/proto/CMakeLists.txt:22 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_2d/scan_matching/proto/CMakeLists.txt:22 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_2d/scan_matching/proto/CMakeLists.txt:27 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_2d/scan_matching/proto/CMakeLists.txt:27 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:17 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:38 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:52 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:69 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:81 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:91 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:108 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:116 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:122 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:135 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:143 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/scan_matching/CMakeLists.txt:155 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/sparse_pose_graph/CMakeLists.txt:15 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/sparse_pose_graph/CMakeLists.txt:45 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:19 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:30 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:48 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:70 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:85 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:97 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:110 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:137 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:160 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:170 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:181 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:188 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:195 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:211 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_2d/CMakeLists.txt:222 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_3d/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_3d/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_3d/proto/CMakeLists.txt:23 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_3d/proto/CMakeLists.txt:23 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_3d/proto/CMakeLists.txt:28 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_3d/proto/CMakeLists.txt:28 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_3d/proto/CMakeLists.txt:40 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_3d/proto/CMakeLists.txt:40 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_3d/proto/CMakeLists.txt:45 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_3d/proto/CMakeLists.txt:45 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_3d/proto/CMakeLists.txt:50 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_3d/proto/CMakeLists.txt:50 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_3d/scan_matching/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_3d/scan_matching/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/mapping_3d/scan_matching/proto/CMakeLists.txt:22 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/mapping_3d/scan_matching/proto/CMakeLists.txt:22 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:17 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:41 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:62 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:69 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:81 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:94 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:109 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:119 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:131 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:139 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:152 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:163 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:172 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/scan_matching/CMakeLists.txt:180 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/sparse_pose_graph/CMakeLists.txt:15 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/sparse_pose_graph/CMakeLists.txt:46 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/sparse_pose_graph/CMakeLists.txt:70 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:19 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:25 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:36 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:48 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:60 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:72 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:97 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:109 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:124 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:137 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:148 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:165 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:179 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:209 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:219 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:225 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:253 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:274 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:280 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:287 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:304 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/mapping_3d/CMakeLists.txt:312 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/sensor/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/sensor/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/sensor/proto/CMakeLists.txt:20 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/sensor/proto/CMakeLists.txt:20 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/sensor/proto/CMakeLists.txt:27 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/sensor/proto/CMakeLists.txt:27 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:17 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:31 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:46 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:59 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:72 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:83 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:96 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:103 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:110 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/sensor/CMakeLists.txt:117 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:283 (_parse_arguments)
cartographer/transform/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:310 (google_library)
cartographer/transform/proto/CMakeLists.txt:15 (google_proto_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/transform/CMakeLists.txt:17 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/transform/CMakeLists.txt:30 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/transform/CMakeLists.txt:39 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cartographer/transform/CMakeLists.txt:51 (google_library)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/transform/CMakeLists.txt:66 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:246 (_parse_arguments)
cartographer/transform/CMakeLists.txt:76 (google_test)

CMake Warning at cmake/functions.cmake:39 (cmake_parse_arguments):
keyword defined more than once: USES_GLOG
Call Stack (most recent call first):
cmake/functions.cmake:264 (_parse_arguments)
cmake/functions.cmake:175 (google_library)
CMakeLists.txt:66 (google_combined_library)

CMake Warning (dev) at cmake/functions.cmake:180 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "cartographer". Use
the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"common_proto_ceres_solver_options". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"common_blocking_queue". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"common_ceres_solver_options". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_config". Use
the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"common_configuration_file_resolver". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"common_fixed_ratio_sampler". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_histogram".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_lua". Use the
target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"common_lua_parameter_dictionary". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"common_lua_parameter_dictionary_test_helpers". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_make_unique".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_math". Use
the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_mutex". Use
the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"common_ordered_multi_queue". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_port". Use
the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_rate_timer".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_thread_pool".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "common_time". Use
the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"kalman_filter_proto_pose_tracker_options". Use the target name directly
with add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"kalman_filter_gaussian_distribution". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"kalman_filter_odometry_state_tracker". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"kalman_filter_pose_tracker". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"kalman_filter_unscented_kalman_filter". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_proto_map_builder_options". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_proto_scan_matching_progress". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_proto_sparse_pose_graph_options". Use the target name directly
with add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_proto_submaps". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_proto_trajectory_connectivity". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_sparse_pose_graph_proto_constraint_builder_options". Use the
target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_sparse_pose_graph_proto_optimization_problem_options". Use the
target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_sparse_pose_graph_constraint_builder". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_sparse_pose_graph_optimization_problem_options". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_global_trajectory_builder_interface". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "mapping_map_builder".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_probability_values". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_sensor_collator". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_sparse_pose_graph". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "mapping_submaps".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_trajectory_connectivity". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_trajectory_node". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_proto_laser_fan_inserter_options". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_proto_local_trajectory_builder_options". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_proto_submaps_options". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_proto_ceres_scan_matcher_options". Use the
target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_proto_fast_correlative_scan_matcher_options".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_proto_real_time_correlative_scan_matcher_options".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_ceres_scan_matcher". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_correlative_scan_matcher". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_fast_correlative_scan_matcher". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_fast_global_localizer". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_occupied_space_cost_functor". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_real_time_correlative_scan_matcher". Use the
target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_rotation_delta_cost_functor". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_scan_matching_translation_delta_cost_functor". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_sparse_pose_graph_constraint_builder". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_sparse_pose_graph_optimization_problem". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_global_trajectory_builder". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_laser_fan_inserter". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_local_trajectory_builder". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_map_limits". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_probability_grid". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_ray_casting". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_2d_sparse_pose_graph". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "mapping_2d_submaps".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "mapping_2d_xy_index".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_proto_kalman_local_trajectory_builder_options". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_proto_laser_fan_inserter_options". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_proto_local_trajectory_builder_options". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_proto_motion_filter_options". Use the target name directly
with add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_proto_optimizing_local_trajectory_builder_options". Use the
target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_proto_submaps_options". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_proto_ceres_scan_matcher_options". Use the
target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_proto_fast_correlative_scan_matcher_options".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_ceres_scan_matcher". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_fast_correlative_scan_matcher". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_interpolated_grid". Use the target name directly
with add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_occupied_space_cost_functor". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_precomputation_grid". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_real_time_correlative_scan_matcher". Use the
target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_rotation_delta_cost_functor". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_rotational_scan_matcher". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_scan_matching_translation_delta_cost_functor". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_sparse_pose_graph_constraint_builder". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_sparse_pose_graph_optimization_problem". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_acceleration_cost_function". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_ceres_pose". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_global_trajectory_builder". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_hybrid_grid". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_imu_integration". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_kalman_local_trajectory_builder". Use the target name directly
with add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_kalman_local_trajectory_builder_options". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_laser_fan_inserter". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_local_trajectory_builder". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_local_trajectory_builder_interface". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_local_trajectory_builder_options". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_motion_filter". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_optimizing_local_trajectory_builder". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_optimizing_local_trajectory_builder_options". Use the target
name directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_rotation_cost_function". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_sparse_pose_graph". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "mapping_3d_submaps".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"mapping_3d_translation_cost_function". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "proto_trajectory".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"sensor_proto_adaptive_voxel_filter_options". Use the target name directly
with add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"sensor_proto_configuration". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "sensor_proto_sensor".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"sensor_compressed_point_cloud". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"sensor_configuration". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "sensor_laser". Use
the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "sensor_point_cloud".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"sensor_sensor_packet_period_histogram_builder". Use the target name
directly with add_custom_command, or use the generator expression
$<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "sensor_voxel_filter".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"transform_proto_transform". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"transform_rigid_transform". Use the target name directly with
add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"transform_rigid_transform_test_helpers". Use the target name directly
with add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "transform_transform".
Use the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at cmake/functions.cmake:190 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target
"transform_transform_interpolation_buffer". Use the target name directly
with add_custom_command, or use the generator expression $<TARGET_FILE>, as
appropriate.

Call Stack (most recent call first):
CMakeLists.txt:66 (google_combined_library)
This warning is for project developers. Use -Wno-dev to suppress it.

CMake Warning (dev) at CMakeLists.txt:70 (get_property):
Policy CMP0026 is not set: Disallow use of the LOCATION target property.
Run "cmake --help-policy CMP0026" for policy details. Use the cmake_policy
command to set the policy and suppress this warning.

The LOCATION property should not be read from target "cartographer". Use
the target name directly with add_custom_command, or use the generator
expression $<TARGET_FILE>, as appropriate.

This warning is for project developers. Use -Wno-dev to suppress it.

-- Configuring incomplete, errors occurred!
See also "/Users/STW/Documents/Projects/cartographer/build/CMakeFiles/CMakeOutput.log".

And also I need to add a FindEigen.cmake file to solve some eigen finding issue on mac. Can you help me with the problem (above) with GLOG?

Cartographer build error

Hi!

I tried to build cartographer on my system (Ubuntu 14.04, gcc 4.8.4, ROS Indigo).
Followed the instructions for ROS, and after executing
catkin_make_isolated --install --use-ninja

I got the following error. Could you please help me out? Thanks!

==> Processing catkin package: 'cartographer_ros'
==> Creating build directory: 'build_isolated/cartographer_ros'
==> Building with env: '/home/max/install_isolated/env.sh'
==> cmake /home/max/src/cartographer_ros/cartographer_ros -DCATKIN_DEVEL_PREFIX=/home/max/devel_isolated/cartographer_ros -DCMAKE_INSTALL_PREFIX=/home/max/install_isolated -G Ninja in '/home/max/build_isolated/cartographer_ros'
-- The C compiler identification is GNU 4.8.4
-- The CXX compiler identification is GNU 4.8.4
-- Check for working C compiler using: Ninja
-- Check for working C compiler using: Ninja -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Check for working CXX compiler using: Ninja
-- Check for working CXX compiler using: Ninja -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Found required Ceres dependency: Eigen version 3.2.0 in /usr/include/eigen3
-- Found required Ceres dependency: glog
-- Looking for include file pthread.h
-- Looking for include file pthread.h - found
-- Looking for pthread_create
-- Looking for pthread_create - not found
-- Looking for pthread_create in pthreads
-- Looking for pthread_create in pthreads - not found
-- Looking for pthread_create in pthread
-- Looking for pthread_create in pthread - found
-- Performing Test GFLAGS_IN_GOOGLE_NAMESPACE
-- Performing Test GFLAGS_IN_GOOGLE_NAMESPACE - Success
-- Found required Ceres dependency: gflags
-- Found Ceres version: 1.12.0 installed in: /home/max/install_isolated with components: [LAPACK, SuiteSparse, SparseLinearAlgebraLibrary, SchurSpecializations, OpenMP]
-- Build type: Release
-- Found PythonInterp: /usr/bin/python (found version "2.7.6") 
-- Found Threads: TRUE  
-- Found GMock: gmock_main;-lpthread  
-- Using CATKIN_DEVEL_PREFIX: /home/max/devel_isolated/cartographer_ros
-- Using CMAKE_PREFIX_PATH: /home/max/install_isolated;/opt/ros/indigo
-- This workspace overlays: /home/max/install_isolated;/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: /home/max/build_isolated/cartographer_ros/test_results
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.6.18
-- Using these message generators: gencpp;genlisp;genpy
-- Found PkgConfig: /usr/bin/pkg-config (found version "0.26") 
-- checking for one of the modules 'yaml-cpp>=0.5.1'
-- checking for module 'eigen3'
--   found eigen3, version 3.2.0
-- Found eigen: /usr/include/eigen3  
-- 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
-- Found openni: /usr/lib/libOpenNI.so  
-- Found libusb-1.0: /usr/include  
-- looking for PCL_COMMON
-- Found PCL_COMMON: /usr/lib/libpcl_common.so  
-- looking for PCL_OCTREE
-- Found PCL_OCTREE: /usr/lib/libpcl_octree.so  
-- looking for PCL_IO
-- Found PCL_IO: /usr/lib/libpcl_io.so  
-- Found PCL: /usr/lib/x86_64-linux-gnu/libboost_system.so;/usr/lib/x86_64-linux-gnu/libboost_filesystem.so;/usr/lib/x86_64-linux-gnu/libboost_thread.so;/usr/lib/x86_64-linux-gnu/libboost_date_time.so;/usr/lib/x86_64-linux-gnu/libboost_iostreams.so;/usr/lib/x86_64-linux-gnu/libboost_serialization.so;/usr/lib/x86_64-linux-gnu/libpthread.so;optimized;/usr/lib/libpcl_common.so;debug;/usr/lib/libpcl_common.so;optimized;/usr/lib/libpcl_octree.so;debug;/usr/lib/libpcl_octree.so;/usr/lib/libOpenNI.so;vtkCommon;vtkRendering;vtkHybrid;vtkCharts;optimized;/usr/lib/libpcl_io.so;debug;/usr/lib/libpcl_io.so;/usr/lib/x86_64-linux-gnu/libboost_system.so;/usr/lib/x86_64-linux-gnu/libboost_filesystem.so;/usr/lib/x86_64-linux-gnu/libboost_thread.so;/usr/lib/x86_64-linux-gnu/libboost_date_time.so;/usr/lib/x86_64-linux-gnu/libboost_iostreams.so;/usr/lib/x86_64-linux-gnu/libboost_serialization.so;/usr/lib/x86_64-linux-gnu/libpthread.so;/usr/lib/libOpenNI.so;vtkCommon;vtkRendering;vtkHybrid;vtkCharts  
-- Found Eigen3: /usr/include/eigen3 (Required is at least version "2.91.0") 
-- Boost version: 1.54.0
-- Found the following Boost libraries:
--   system
--   iostreams
CMake Error at cartographer_ros/CMakeLists.txt:1 (google_library):
  Unknown CMake command "google_library".


-- Configuring incomplete, errors occurred!
See also "/home/max/build_isolated/cartographer_ros/CMakeFiles/CMakeOutput.log".
See also "/home/max/build_isolated/cartographer_ros/CMakeFiles/CMakeError.log".
<== Failed to process package 'cartographer_ros': 
  Command '['/home/max/install_isolated/env.sh', 'cmake', '/home/max/src/cartographer_ros/cartographer_ros', '-DCATKIN_DEVEL_PREFIX=/home/max/devel_isolated/cartographer_ros', '-DCMAKE_INSTALL_PREFIX=/home/max/install_isolated', '-G', 'Ninja']' returned non-zero exit status 1


Error in Yaw estimation on 180 deg turns.

Hi All
I am using Cartographer for 2D slam on a robot with a 10m range, 270 deg FOV, 15 Hz planar laser scanner and wheel encoders. It seems like ceres scan matcher is incorrectly estimating the yaw after a 180-deg turn which, when multiplied by the arm-length as the robot travels ahead, leads to a large error in the position of the robot. This error gets corrected by the pose graph matcher eventually causing big jumps in the pose of the robot. The final maps I get out of the system look pretty good but I also care about the real-time accuracy of the localization.

As you can see in the images, the scans are in a very close proximity to the walls(even closer if you extrapolate backwards from figure 1 to the point right after the 180 deg turn) and It seems like ceres scan matcher should be able to correct the error without the backend having to kick-in. I tried tuning most of the configuration values that seem relevant to real-time operation of cartographer(ceres scan matcher, voxler and motion filter) but I couldn't get any better results than what I have in the attached images. I m overlooking something here. Has anyone of you dealt with this problem before and know what could cause this? Thanks in advance.

a_edited
Figure 1: Snapshot of the map as estimated by SPA. The robot was travelling as depicted by the yellow arrows at about 1 m/s. The green dots show the laser returns.

b_edited
Figure 2: Snapshot of the map as estimated by SPA a few seconds later. The robot was travelling as depicted by the yellow arrows a about 1 m/s. The green dots show the laser returns.

PS: I am using cartographer with our in-house framework and I have a wrapper around the MapBuilder that conceptually replicates the ROS package. I will be attaching the Lua configuration table that I am using shortly.

-- Anurag

getting started ?

Hello,

I read the quick start but there is not much to read

as I click on next, there are configuration variables, I have no idea which file should be opened to define these variables

also how do I add carographer to one of my program, how do I declare sensors/odometers and how do I feed cartographer with these data

what format should they have, how do I normalize these data ?

thanks

Support for loading saved submaps and pose graph for long-term SLAM.

Hi Authors and other Contributors
Let me start by thanking you all for writing Cartographer and open-sourcing it. It adds immense value to the robotics society as it is probably the only SLAM algorithm as of now that is field-ready. Great job!

I am using Cartographer with our in-house framework to create a solution for a long-term 2D mapping and localization. For the implementation to be truly long-term, I need to add the ability of being able to save the pose of the robot, sub-maps and the pose-graph(SPA) on shutdown and load them back into cartographer on subsequent startup of the software. I will be beginning my efforts on this very soon and was wondering if you guys have any thoughts, pointers to references or inputs before I begin. I would be more than happy to collaborate as suitable.

Here's a quick brain dump of what I think needs to be done to accomplish this:

  • Serialization, saving, loading and construction of sub-maps in local trajectory builder(front-end) and sparse pose graph in global trajectory builder.

  • Saving and loading of robot pose(with covariance?) and instantiation of map builder with this pose as the starting point.

  • A global matching scheme to match the new scans to the loaded sub-maps in the vicinity(scaled based on covariance?) of the seed pose before cartographer resurrects and operates as normal. May be?

  • A strategy to appropriately kick-start the internal kalman filters. Not sure how the time-jump will affect those.

  • Swapping in new laser frames to replace stale frames in the pose-graph that are no longer representative of the environment. Also limiting the insertion of laser scans to situations when new area is being explored or when swapping out an stale scan . This will

    1. Avoid growth of pose-graph over course of time to an intractable number of constraints.
    2. Make the pose-graph adaptive to the long-term, slow changes in the environment.

Please do share your thoughts that you think might help. I will be updating this post as I think of more items.

Thanks

-- Anurag

trajectory builder - outdoor data

I am trying to build a 3d map from a rosbag

I serve data needed by cartographer_ros by doing the following things on our rosbag:
Republish our IMU data by inverting the direction of Z acceleration. I also set the angular velocity co-variance to 0 for all fields.
Use VLP16 driver and republish velodyne_points as points2. We publish one point cloud per velodyne packet.
Publish static_transforms between base-link and imu and base-link and velodyne.

The challenge I am facing is our trajectory builder isn’t building more than one trajectory. I.e. I am facing trouble with the pose estimation that is published as the map->odom transform by cartographer. I haven’t changed any parameters in trajectory builder or sparse_pose from the main cartographer source code.

All the matched scans overlay on each other when visualized in rviz.

I think that there is some configuration there that needs modification because the velocity of the robot is much greater than the velocity of the backpack.

Thanks for your help. Let me know if you need more information

We are using the demo_car_3d.launch

Here is the ros source code: https://drive.google.com/open?id=0BzptGYp7_SKtY3JmaE1yQURsOXM

The ROSBAG we are using: https://drive.google.com/open?id=0BzptGYp7_SKtLUtrR3dZZzY3TGs

Velocity speed estimate is noisy and unstable with a higher frequency laser (previously: Cartographer crashes with a Pioneer 3DX bag)

I am getting a crash when mapping with Cartographer and a Pioneer robot. I am using Ubuntu 16.04, ROS Kinetic, cartographer @ddb3c890a6 and cartographer-project/cartographer_ros@f7057fc5a35aed4. A sample crash log can be found here. The launch file and the appropriate bag can be found here. To run, extract the archive, change into the launch directory and call roslaunch pioneer_cartographer.launch from there.

The crash usually occurs somewhere around 60-70 seconds into the bag (counting from the 25th second, where it starts in the launch file) , after the robot makes a right turn to the hallway looking up. The pose estimate makes wild jumps just before it crashes, with a message like the following one: [FATAL]: ... probability_grid.h:161] Check failed: limits_.Contains(xy_index) -215

The crash seems to be related to odometry - if use_odometry is set to false in the .lua file, Cartographer doesn't crash. However, scan matching in that case doesn't work very well; it gets stuck in the same hallway where it crashes when using odometry.

Cartographer installation problem

Hi,

I use Ubuntu 16.04 LTS, G++ compiler version 5.4.0. And I would like to install and use cartographer without ROS.

So after having run successfully (and consecutively) install_debs.sh and install_ceres.h (located both inside cartographer/scripts), I executed install_cartographer.sh script
and I got this error:
`# Build and install Cartographer.
cd cartographer
mkdir build
cd build
cmake .. -G Ninja
-- The C compiler identification is GNU 5.4.0
-- The CXX compiler identification is GNU 5.4.0
-- Check for working C compiler using: Ninja
-- Check for working C compiler using: Ninja -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Detecting C compile features
-- Detecting C compile features - done
-- Check for working CXX compiler using: Ninja
-- Check for working CXX compiler using: Ninja -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
CMake Error at common/CMakeLists.txt:19 (google_test):
Unknown CMake command "google_test".

CMake Warning (dev) in CMakeLists.txt:
No cmake_minimum_required command is present. A line of code such as

cmake_minimum_required(VERSION 3.5)

should be added at the top of the file. The version specified may be lower
if you wish to support older CMake versions for this project. For more
information run "cmake --help-policy CMP0000".
This warning is for project developers. Use -Wno-dev to suppress it.

-- Configuring incomplete, errors occurred!
`
It seems like the install_debs.sh hasn't installed google test.

What am I supposed to do now? Install directly google test inside cartographer ? Which I tried and it wasn' successful

Thanks in advance for your answer.

reading cmake file syntax

Greeting,
CMakeLists.txt uses syntax commands which are extra to standard ROS commands e.g. google_library().

Where I can read about this syntax ?
Rgds

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.