Changes build instructions to use Catkin. (#2)

Uses eth-asl repos for Ceres.
Adds missing package dependency.
master
Damon Kohler 2016-08-03 16:31:24 +02:00 committed by GitHub
parent 961afb6817
commit 3e179972da
2 changed files with 44 additions and 0 deletions

43
README.md Normal file
View File

@ -0,0 +1,43 @@
# Cartographer Project Overview
See https://github.com/googlecartographer/cartographer
## Installation
On Ubuntu 14.04 (Trusty) with ROS Indigo installed:
# Install the required libraries that are available as debs
sudo apt-get install \
ros-indigo-tf2-eigen \
g++ \
google-mock \
libboost-all-dev \
liblua5.2-dev \
libprotobuf-dev \
libwebp-dev \
protobuf-compiler \
python-sphinx \
libblas-dev \
liblapack-dev \
libpcap-dev # For 3D SLAM with Velodynes
# Set up your Catkin workspace
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
source /opt/ros/indigo/setup.bash
catkin_init_workspace
# Clone the necessary repos into your Catkin workspace
git clone https://github.com/googlecartographer/cartographer.git
git clone https://github.com/googlecartographer/cartographer_ros.git
git clone https://github.com/ethz-asl/ceres_catkin.git
git clone https://github.com/ethz-asl/suitesparse.git
git clone https://github.com/ethz-asl/glog_catkin.git
git clone https://github.com/ethz-asl/gflags_catkin.git
git clone https://github.com/ethz-asl/catkin_simple.git
git clone https://github.com/ros-drivers/velodyne.git # For 3D SLAM with Velodynes
# Build everything in your Catkin workspace
cd ~/catkin_ws
catkin_make_isolated
source devel_isolated/setup.bash

View File

@ -24,6 +24,7 @@
<buildtool_depend>catkin</buildtool_depend>
<build_depend>cartographer</build_depend>
<build_depend>eigen_conversions</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>cartographer_ros_msgs</build_depend>