• Stars
    star
    548
  • Rank 81,119 (Top 2 %)
  • Language
    C++
  • License
    Apache License 2.0
  • Created almost 8 years ago
  • Updated over 1 year ago

Reviews

There are no reviews yet. Be the first to send feedback to the community and the maintainers!

Repository Details

Polynomial trajectory generation and optimization, especially for rotary-wing MAVs.

mav_trajectory_generation

This repository contains tools for polynomial trajectory generation and optimization based on methods described in [1]. These techniques are especially suitable for rotary-wing micro aerial vehicles (MAVs). This README provides a brief overview of our trajectory generation utilities with some examples.

Authors: Markus Achtelik, Michael Burri, Helen Oleynikova, Rik Bähnemann, Marija Popović
Maintainer: Rik Bähnemann, [email protected]
Affiliation: Autonomous Systems Lab, ETH Zurich

Bibliography

This implementation is largely based on the work of C. Richter et al, who should be cited if this is used in a scientific publication (or the preceding conference papers):
[1] C. Richter, A. Bry, and N. Roy, “Polynomial trajectory planning for aggressive quadrotor flight in dense indoor environments,” in International Journal of Robotics Research, Springer, 2016.

@incollection{richter2016polynomial,
  title={Polynomial trajectory planning for aggressive quadrotor flight in dense indoor environments},
  author={Richter, Charles and Bry, Adam and Roy, Nicholas},
  booktitle={Robotics Research},
  pages={649--666},
  year={2016},
  publisher={Springer}
}

Furthermore, the nonlinear optimization features our own extensions, described in:

Michael Burri, Helen Oleynikova, Markus Achtelik, and Roland Siegwart, “Real-Time Visual-Inertial Mapping, Re-localization and Planning Onboard MAVs in Previously Unknown Environments”. In IEEE Int. Conf. on Intelligent Robots and Systems (IROS), September 2015.

@inproceedings{burri2015real-time,
  author={Burri, Michael and Oleynikova, Helen and  and Achtelik, Markus W. and Siegwart, Roland},
  booktitle={Intelligent Robots and Systems (IROS 2015), 2015 IEEE/RSJ International Conference on},
  title={Real-Time Visual-Inertial Mapping, Re-localization and Planning Onboard MAVs in Unknown Environments},
  year={2015},
  month={Sept}
}

Installation Instructions (Ubuntu)

To install this package with ROS Indigo or ROS Kinetic:

  1. Install additional system dependencies (swap indigo for kinetic or melodic as necessary):

** Note: ROS melodic requires libyaml-cpp-dev and does not build with yaml_cpp_catkin in your catkin workspace!

sudo apt-get install python-wstool python-catkin-tools ros-indigo-cmake-modules libyaml-cpp-dev
  1. Set up a catkin workspace (if not already done):
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin init
catkin config --extend /opt/ros/indigo
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
catkin config --merge-devel
  1. Install the repository and its dependencies (with rosinstall):
cd src
wstool init
wstool set --git mav_trajectory_generation [email protected]:ethz-asl/mav_trajectory_generation.git -y
wstool update
wstool merge mav_trajectory_generation/install/mav_trajectory_generation_https.rosinstall
wstool update -j8
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source /opt/ros/indigo/setup.bash

In case you have your SSH keys for github set up, feel free to use the ssh rosinstall instead:

wstool merge mav_trajectory_generation/install/mav_trajectory_generation_ssh.rosinstall
  1. Use catkin_build to build the repository:
catkin build mav_trajectory_generation_ros

Basics

A vertex describes the properties of a support point of a polynomial path. Pairs of vertices are connected together to form segments. Each vertex has a set of constraints: the values of position derivatives that must be matched during optimization procedures. Typically, only the positions are specified for vertices along a path, while start and end vertices have all derivatives of position set to zero.

  x----------x-----------------x
vertex            segment

In the case of multi-dimensional vertices, the derivative constraints exist in all dimensions, with possibly different values.

Linear Optimization

In this section, we consider how to generate polynomial segments passing through a set of arbitrary vertices using the unconstrained linear optimization approach described in [1].

Necessary includes:

#include <mav_trajectory_generation/polynomial_optimization_linear.h>
  1. Create a list of three (x,y,z) vertices to fly through, e.g. (0,0,1) -> (1,2,3) -> (2,1,5), and define some parameters. The dimension variable denotes the spatial dimension of the path (here, 3D). The derivative_to_optimize should usually be set to the last derivative that should be continuous (here, snap).
mav_trajectory_generation::Vertex::Vector vertices;
const int dimension = 3;
const int derivative_to_optimize = mav_trajectory_generation::derivative_order::SNAP;
mav_trajectory_generation::Vertex start(dimension), middle(dimension), end(dimension);
  1. Add constraints to the vertices.
start.makeStartOrEnd(Eigen::Vector3d(0,0,1), derivative_to_optimize);
vertices.push_back(start);

middle.addConstraint(mav_trajectory_generation::derivative_order::POSITION, Eigen::Vector3d(1,2,3));
vertices.push_back(middle);

end.makeStartOrEnd(Eigen::Vector3d(2,1,5), derivative_to_optimize);
vertices.push_back(end);
  1. Compute the segment times.
std::vector<double> segment_times;
const double v_max = 2.0;
const double a_max = 2.0;
segment_times = estimateSegmentTimes(vertices, v_max, a_max);
  1. Create an optimizer object and solve. The template parameter (N) denotes the number of coefficients of the underlying polynomial, which has to be even. If we want the trajectories to be snap-continuous, N needs to be at least 10; for minimizing jerk, 8.
const int N = 10;
mav_trajectory_generation::PolynomialOptimization<N> opt(dimension);
opt.setupFromVertices(vertices, segment_times, derivative_to_optimize);
opt.solveLinear();
  1. Obtain the polynomial segments.
mav_trajectory_generation::Segment::Vector segments;
opt.getSegments(&segments);

Nonlinear Optimization

In this section, we consider how to generate polynomial segments passing through a set of arbitrary vertices using the unconstrained nonlinear optimization approach described in [1]. The same approach is followed as in the previous section.

Necessary includes:

#include <mav_trajectory_generation/polynomial_optimization_nonlinear.h>
  1. Set up the problem by following Steps 1-3 in the Linear Optimization section.

  2. Set the parameters for nonlinear optimization. Below is an example, but the default parameters should be reasonable enough to use without fine-tuning.

NonlinearOptimizationParameters parameters;
parameters.max_iterations = 1000;
parameters.f_rel = 0.05;
parameters.x_rel = 0.1;
parameters.time_penalty = 500.0;
parameters.initial_stepsize_rel = 0.1;
parameters.inequality_constraint_tolerance = 0.1;
  1. Create an optimizer object and solve. The third argument of the optimization object (true/false) specifies whether the optimization is run over the segment times only.
const int N = 10;
PolynomialOptimizationNonLinear<N> opt(dimension, parameters, false);
opt.setupFromVertices(vertices, segment_times, derivative_to_optimize);
opt.addMaximumMagnitudeConstraint(mav_trajectory_generation::derivative_order::VELOCITY, v_max);                                opt.addMaximumMagnitudeConstraint(mav_trajectory_generation::derivative_order::ACCELERATION, a_max);
opt.optimize();
  1. Obtain the polynomial segments.
mav_trajectory_generation::Segment::Vector segments;
opt.getPolynomialOptimizationRef().getSegments(&segments);

Creating Trajectories

In this section, we consider how to use our trajectory optimization results. We first need to convert our optimization object into the Trajectory class:

#include <mav_trajectory_generation/trajectory.h>

mav_trajectory_generation::Trajectory trajectory;
opt.getTrajectory(&trajectory);

We can also create new trajectories by splitting (getting a trajectory with a single dimension) or compositing (getting a trajectory by appending another trajectory:

// Splitting:
mav_trajectory_generation::Trajectory x_trajectory = trajectory.getTrajectoryWithSingleDimension(1);

// Compositing:
mav_trajectory_generation::Trajectory trajectory_with_yaw; trajectory.getTrajectoryWithAppendedDimension(yaw_trajectory, &trajectory_with_yaw);

Sampling Trajectories

In this section, we consider methods of evaluating the trajectory at particular instances of time. There are two methods of doing this.

  1. By evaluating directly from the Trajectory class.
// Single sample:
double sampling_time = 2.0;
int derivative_order = mav_trajectory_generation::derivative_order::POSITION;
Eigen::VectorXd sample = trajectory.evaluate(sampling_time, derivative_order);

// Sample range:
double t_start = 2.0;
double t_end = 10.0;
double dt = 0.01;
std::vector<Eigen::VectorXd> result;
std::vector<double> sampling_times; // Optional.
trajectory.evaluateRange(t_start, t_end, dt, derivative_order, &result, &sampling_times);
  1. By conversion to mav_msgs::EigenTrajectoryPoint state(s). These functions support 3D or 4D trajectories (the 4th dimension is assumed to be yaw if it exists).
#include <mav_trajectory_generation_ros/trajectory_sampling.h>

mav_msgs::EigenTrajectoryPoint state;
mav_msgs::EigenTrajectoryPoint::Vector states;

// Single sample:
double sampling_time = 2.0;
bool success = mav_trajectory_generation::sampleTrajectoryAtTime(trajectory, sample_time, &state);

// Sample range:
double t_start = 2.0;
double duration = 10.0;
double dt = 0.01;
success = mav_trajectory_generation::sampleTrajectoryInRange(trajectory, t_start, duration, dt, &states);

// Whole trajectory:
double sampling_interval = 0.01;
success = mav_trajectory_generation::sampleWholeTrajectory(trajectory, sampling_interval, &states);

Visualizing Trajectories

In this section, we describe how to visualize trajectories in rviz.

For a simple visualization:

#include <mav_trajectory_generation_ros/ros_visualization.h>

visualization_msgs::MarkerArray markers;
double distance = 1.0; // Distance by which to seperate additional markers. Set 0.0 to disable.
std::string frame_id = "world";

// From Trajectory class:
mav_trajectory_generation::drawMavTrajectory(trajectory, distance, frame_id, &markers);

// From mav_msgs::EigenTrajectoryPoint::Vector states:
mav_trajectory_generation::drawMavSampledTrajectory(states, distance, frame_id, &markers)

For a visualization including an additional marker at a set distance (e.g. hexacopter marker):

mav_visualization::HexacopterMarker hex(simple);

// From Trajectory class:
mav_trajectory_generation::drawMavTrajectoryWithMavMarker(trajectory, distance, frame_id, hex &markers);

// From mav_msgs::EigenTrajectoryPoint::Vector states:
mav_trajectory_generation::drawMavSampledTrajectoryWithMavMarker(states, distance, frame_id, hex, &markers)

Checking Input Feasibility

The package contains three implementations to check generated trajectories for input feasibility. The checks are based on the rigid-body model assumption and flat state characteristics presented in Mellinger2011.

@inproceedings{mellinger2011minimum,
  title={Minimum snap trajectory generation and control for quadrotors},
  author={Mellinger, Daniel and Kumar, Vijay},
  booktitle={Robotics and Automation (ICRA), 2011 IEEE International Conference on},
  pages={2520--2525},
  year={2011},
  organization={IEEE}
}

The trajectories are checked for low and high thrust, high velocities, high roll and pitch rates, high yaw rates and high yaw angular accelerations.

FeasibilitySampling implements a naive sampling-based check. FeasibilityRecursive implements a slightly adapted recursive feasibility test presented in Müller2015.

@article{mueller2015computationally,
  title={A computationally efficient motion primitive for quadrocopter trajectory generation},
  author={Mueller, Mark W and Hehn, Markus and D'Andrea, Raffaello},
  journal={IEEE Transactions on Robotics},
  volume={31},
  number={6},
  pages={1294--1310},
  year={2015},
  publisher={IEEE}
}

We adapted RapidQuadrocopterTrajectories to check arbitrary polynomial order trajectories for yaw and velocity feasibility.

FeasibilityAnalytic analytically checks the magnitudes except for the roll and pitch rates, where it runs the recursive test (recommended: low in computation time, no false positives).

Example

// Create input constraints.
typedef InputConstraintType ICT;
InputConstraints input_constraints;
input_constraints.addConstraint(ICT::kFMin, 0.5 * 9.81); // minimum acceleration in [m/s/s].
input_constraints.addConstraint(ICT::kFMax, 1.5 * 9.81); // maximum acceleration in [m/s/s].
input_constraints.addConstraint(ICT::kVMax, 3.5); // maximum velocity in [m/s].
input_constraints.addConstraint(ICT::kOmegaXYMax, M_PI / 2.0); // maximum roll/pitch rates in [rad/s].
input_constraints.addConstraint(ICT::kOmegaZMax, M_PI / 2.0); // maximum yaw rates in [rad/s].
input_constraints.addConstraint(ICT::kOmegaZDotMax, M_PI); // maximum yaw acceleration in [rad/s/s].

// Create feasibility object of choice (FeasibilityAnalytic,
// FeasibilitySampling, FeasibilityRecursive).
FeasibilityAnalytic feasibility_check(input_constraints);
feasibility_check.settings_.setMinSectionTimeS(0.01);

// Check feasibility.
Segment dummy_segment;
InputFeasibilityResult result =
    feasibility_check.checkInputFeasibility(dummy_segment);
std::cout << "The segment input is " << getInputFeasibilityResultName(result);
<< "." << std::endl;

Benchmarking

Both recursive and analytic checks are comparably fast. The recursive check may have a couple more false negatives, i.e., segments, that can not be determined feasible although they are. But this is neglectable. The sampling based check is both slow and may have false positives, i.e., consider segments feasible although they are not. We do not recommend using this.

Here are the computational results over 1000 random segments with different parameter settings:

Checking Half-Space Feasibility

The package also contains a method to check if a trajectory or segment is inside an arbitrary set of half spaces based on RapidQuadrocopterTrajectories. This is useful to check if a segment is inside a box or above ground.

Example ground plane feasibility:

// Create feasibility check.
FeasibilityBase feasibility_check;
// Create ground plane.
Eigen::Vector3d point(0.0, 0.0, 0.0);
Eigen::Vector3d normal(0.0, 0.0, 1.0);
feasibility_check.half_plane_constraints_.emplace_back(point, normal);
// Check feasibility.
Segment dummy_segment;
if(!feasibility_check.checkHalfPlaneFeasibility(segment)) {
  std::cout << "The segment is in collision with the ground plane." << std::endl;
}

Example box feasibility:

// Create feasibility check.
FeasibilityBase feasibility_check;
// Create box constraints.
Eigen::Vector3d box_center(0.0, 0.0, 0.0);
Eigen::Vector3d box_size(1.0, 1.0, 1.0);
feasibility_check.half_plane_constraints_ =
    HalfPlane::createBoundingBox(box_center, box_size);
// Check feasibility.
Segment dummy_segment;
if(!feasibility_check.checkHalfPlaneFeasibility(segment)) {
  std::cout << "The segment is not inside the box." << std::endl;
}

More Repositories

1

kalibr

The Kalibr visual-inertial calibration toolbox
C++
4,357
star
2

maplab

A Modular and Multi-Modal Mapping Framework
C++
2,610
star
3

voxblox

A library for flexible voxel-based mapping, mainly focusing on truncated and Euclidean signed distance fields.
C++
1,336
star
4

rotors_simulator

RotorS is a UAV gazebo simulator
C++
1,245
star
5

okvis

OKVIS: Open Keyframe-based Visual-Inertial SLAM.
C++
1,158
star
6

rovio

C++
1,126
star
7

segmap

A map representation based on 3D segments
C++
1,070
star
8

ethzasl_msf

MSF - Modular framework for multi sensor fusion based on an Extended Kalman Filter (EKF)
C++
985
star
9

lidar_align

A simple method for finding the extrinsic calibration between a 3D lidar and a 6-dof pose sensor
C++
836
star
10

hfnet

From Coarse to Fine: Robust Hierarchical Localization at Large Scale with HF-Net (https://arxiv.org/abs/1812.03506)
Python
739
star
11

mav_active_3d_planning

Modular framework for online informative path planning.
C++
564
star
12

polygon_coverage_planning

Coverage planning in general polygons with holes.
C++
528
star
13

aerial_mapper

Real-time Dense Point Cloud, Digital Surface Map (DSM) and (Ortho-)Mosaic Generation for UAVs
C++
524
star
14

voxgraph

Voxblox-based Pose graph optimization
C++
513
star
15

robust_point_cloud_registration

Robust Point Cloud Registration Using Iterative Probabilistic Data Associations ("Robust ICP")
C++
513
star
16

mav_voxblox_planning

MAV planning tools using voxblox as the map representation.
Makefile
463
star
17

hand_eye_calibration

Python tools to perform time-synchronization and hand-eye calibration.
Python
439
star
18

dynablox

Real-time detection of diverse dynamic objects in complex environments.
C++
436
star
19

voxblox-plusplus

A volumetric object-level semantic mapping framework.
C++
409
star
20

mav_control_rw

Control strategies for rotary wing Micro Aerial Vehicles using ROS
C
350
star
21

ethzasl_sensor_fusion

time delay single and multi sensor fusion framework based on an EKF
C++
327
star
22

nbvplanner

A real-time capable exploration and inspection path planner (next best view planning)
C++
295
star
23

panoptic_mapping

A flexible submap-based framework towards spatio-temporally consistent volumetric mapping and scene understanding.
C++
275
star
24

ethzasl_icp_mapping

3D mapping tools for robotic applications
C++
268
star
25

okvis_ros

OKVIS: Open Keyframe-based Visual-Inertial SLAM (ROS Version)
C++
256
star
26

versavis

An Open Versatile Multi-Camera Visual-Inertial Sensor Suite
C++
256
star
27

kitti_to_rosbag

Dataset tools for working with the KITTI dataset raw data ( http://www.cvlibs.net/datasets/kitti/raw_data.php ) and converting it to a ROS bag. Also allows a library for direct access to poses, velodyne scans, and images.
C++
248
star
28

laser_slam

This package provides an end-to-end system to laser-based graph SLAM using laser point clouds.
C++
248
star
29

geodetic_utils

Simple library for converting coordinates to/from several geodetic frames (lat/lon, ECEF, ENU, NED, etc.)
C++
247
star
30

COIN-LIO

🪙 COIN-LIO: Complementary Intensity-Augmented LiDAR Inertial Odometry (ICRA 2024)
C++
245
star
31

image_undistort

A compact package for undistorting images directly from kalibr calibration files. Can also perform dense stereo estimation
C++
245
star
32

ethzasl_ptam

Modified version of Parallel Tracking and Mapping (PTAM)
C++
235
star
33

wavemap

Fast, efficient and accurate multi-resolution, multi-sensor 3D occupancy mapping
C++
226
star
34

cblox

Voxblox-based submapping
C++
207
star
35

aslam_cv2

C++
196
star
36

glocal_exploration

Efficient local and global exploration on submap collections with changing past pose estimates.
C++
186
star
37

volumetric_mapping

A repository for 3D volumetric (occupancy) maps, providing a generic interface for disparity map and pointcloud insertion, and support for custom sensor error models.
C++
186
star
38

vgn

Real-time 6 DOF grasp detection in clutter.
Python
181
star
39

hierarchical_loc

Deep image retrieval for efficient 6-DoF localization
Python
172
star
40

orb_slam_2_ros

ROS interface for ORBSLAM2!!
C++
171
star
41

mav_dji_ros_interface

Interface of DJI autopilot based on its OSDK (3.2)
C++
156
star
42

lidar_undistortion

Catkin package that provides lidar motion undistortion based on an external 6DoF pose estimation input.
C++
145
star
43

programming_guidelines

This repository contains style-guides, discussions, eclipse/emacs auto-formatter for commonly used programming languages
Emacs Lisp
139
star
44

tsdf-plusplus

TSDF++: A Multi-Object Formulation for Dynamic Object Tracking and Reconstruction
C++
135
star
45

odom_predictor

Integrates an IMU to predict future odometry readings
C++
134
star
46

depth_segmentation

A collection of segmentation methods working on depth images
C++
133
star
47

grid_map_geo

Geolocalization for grid map using GDAL.
C++
129
star
48

neuralblox

Real-time Neural Representation Fusion for Robust Volumetric Mapping
Python
127
star
49

StructuralInspectionPlanner

ASL Structural Inspection Planner
C++
108
star
50

phaser

A robust pointcloud registration pipeline based on correlation.
C++
106
star
51

eth_supermegabot

Instructions for ETH center for robotics summer school 2019.
Python
102
star
52

terrain-navigation

Repository for Safe Low Altitude Navigation in steep terrain for fixed-wing Aerial Vehicles
C++
98
star
53

waypoint_navigator

Stand-alone waypoint navigator
C++
96
star
54

ethzasl_xsens_driver

Driver for xsens IMUs
Python
96
star
55

mav_tools_public

General launch files, parameters and wiki entries on our systems and related issues
95
star
56

data-driven-dynamics

Data Driven Dynamics Modeling for Aerial Vehicles
Python
94
star
57

reinmav-gym

Reinforcement Learning framework for MAVs using the OpenAI Gym environment
Python
93
star
58

cuckoo_time_translator

algorithms for synchronizing clocks
C++
88
star
59

minkindr

A minimal library for transformations, following the kindr interface. Uses active quaternions of rotation in Hamilton notation.
C++
88
star
60

unreal_airsim

Simulation interface to Unreal Engine 4 based on the AirSim plugin.
C++
87
star
61

waverider

RMPs on multi-resolution occupancy maps for efficient reactive collision avoidance
87
star
62

ethz_piksi_ros

ROS drivers for the Piksi RTK GPS module
C++
85
star
63

sl_sensor

SL Sensor: An open-source, real-time and ROS-based structured light sensor for high accuracy construction robotic applications
C++
84
star
64

voxblox_ground_truth

Create ground truth voxblox maps from Gazebo worlds or .ply files
C++
83
star
65

vicon_bridge

This is a driver providing data from VICON motion capture systems. It is based on the vicon_mocap package from the starmac stacks. Additionally, it can handle multiple subjects / segments and allows to calibrate an origin of the vehicle(s) as this is somehow tedious with the VICON Tracker.
C++
80
star
66

ros-system-monitor

System monitoring tools for ROS.
Python
80
star
67

navrep

Python
73
star
68

curves

A library of curves for estimation.
C++
72
star
69

schweizer_messer

Programming tools for robotics.
C++
65
star
70

time_autosync

Automatically syncs a camera to a rigidly attached IMUs time frame
C++
63
star
71

unreal_cv_ros

Unreal CV ROS Perception Simulator
Python
62
star
72

ai_for_robotics

Programming Exercises Accompanying the Lecture "Artificial Intelligence for Robotics"
Python
60
star
73

lcd

Line Clustering and Description for Place Recognition
C++
59
star
74

trajectory_toolkit

Python tool for analyzing and evaluating trajectory data
Python
59
star
75

dataset_tools

Loader for the generic ASL dataset formats.
MATLAB
58
star
76

rl-navigation

OpenEdge ABL
57
star
77

asl-student-templates

Templates and overview information for student projects at ASL
PostScript
56
star
78

libseekthermal

Driver library for Seek Thermal imaging devices
C++
55
star
79

reactive_avoidance

Reactive obstacle avoidance using raytracing or lidars
C++
52
star
80

plotty

matplotlib-cpp with Eigen interfaces.
C++
52
star
81

forest_gen

Generates randomized Poisson forests to use for UAV collision avoidance evaluations.
Python
49
star
82

3d_vsg

3D Variable Scene Graphs for long-term semantic scene change prediction.
Python
49
star
83

sampling_based_control

Jupyter Notebook
47
star
84

mav_comm

This repository contains message and service definitions used for mavs. All future message definitions go in here, existing ones in other stacks should be moved here where possible.
C++
46
star
85

tmplanner

Terrain monitoring planner
C++
45
star
86

3d3l

Deep Learned Keypoint Detection and Description for 3D LiDARs
Python
44
star
87

fgsp

Jupyter Notebook
44
star
88

autolabel

A project for computing high-quality ground truth training examples for RGB-D data.
Python
43
star
89

mav_gtsam_estimator

A GTSAM based state estimation framework.
C++
43
star
90

visensor_node

Visual inertial SLAM sensor ROS node.
C++
43
star
91

Learn-to-Calibrate

We utilize deep reinforcement learning to obtain favorable trajectories for visual-inertial system calibration.
C++
43
star
92

cvae_exploration_planning

Learning informed sampling distributions and information gains for efficient exploration planning.
Python
42
star
93

active_grasp

Closed-loop next-best view planning for grasp detection in clutter.
Python
41
star
94

two_state_information_filter

C++
41
star
95

ssc_exploration

Incremental 3D Scene Completion for Safe and Efficient Exploration Mapping and Planning
41
star
96

maplab_rovio

Hard-fork of ROVIO to integrate localization.
C++
40
star
97

rtklibros

rtklib with ros interfacing and adapted feedback from external Kalman filter
C
40
star
98

libvisensor

Low level hardware driver for the visual inertial SLAM sensor.
C++
39
star
99

3dsnet

3DSNet: Unsupervised Shape-to-shape 3D Style Transfer
C++
39
star
100

mav_system_identification

Matlab scripts to perform system identification for muti-rotor systems
MATLAB
38
star