├── .clang-format ├── .conda_config ├── .gitignore ├── CMakeLists.txt ├── LICENSE ├── README.md ├── experiments ├── CMakeLists.txt ├── include │ ├── FixedLagBackend.h │ ├── JRL-custom.h │ ├── JRL.h │ ├── JRLFrontend.h │ ├── LMBackend.h │ ├── MEstBackend.h │ └── tqdm.h └── src │ ├── FixedLagBackend.cpp │ ├── JRL-custom.cpp │ ├── JRLFrontend.cpp │ └── MEstBackend.cpp ├── figures ├── header.pdf ├── header.py ├── header_animated.py ├── monte_carlo.py ├── readme.gif ├── sabercat_results.pdf ├── sabercat_results.py ├── sim.pdf ├── sim.py ├── sim_monte_carlo_ideal.pdf ├── sim_monte_carlo_real.pdf ├── surface.pdf ├── surface.py ├── tukey.pdf └── tukey.py ├── python ├── CMakeLists.txt ├── CMakeMacros.txt ├── bindings.cpp ├── rose │ ├── __init__.py │ ├── dataset.py │ ├── datasets │ │ ├── flat.py │ │ ├── grizzly.py │ │ ├── kaist.py │ │ └── sabercat.py │ ├── jrl.py │ ├── plot.py │ └── sim.py └── setup.py.in ├── requirements.in ├── rose ├── CMakeLists.txt ├── include │ └── rose │ │ ├── PlanarPriorFactor.h │ │ ├── WheelBaseline.h │ │ ├── WheelFactorBase.h │ │ ├── WheelRose.h │ │ └── ZPriorFactor.h └── src │ ├── WheelBaseline.cpp │ ├── WheelFactorBase.cpp │ └── WheelRose.cpp ├── scripts ├── 2jrl_run.py ├── optimize_cov.py ├── results.py ├── run_sabercat.sh ├── sim.py └── sim_monte_carlo.py └── tests ├── CMakeLists.txt ├── main.cpp ├── test_CombinedIMUFactor.cpp ├── test_Factors.cpp ├── test_IMUBias.cpp ├── test_JRL.cpp ├── test_Jacobians.cpp └── test_StereoFactor.cpp /.clang-format: -------------------------------------------------------------------------------- 1 | --- 2 | ColumnLimit: 120 3 | IndentWidth: 4 -------------------------------------------------------------------------------- /.conda_config: -------------------------------------------------------------------------------- 1 | rose -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | .vscode 2 | build 3 | data 4 | data-new 5 | /*.png 6 | __pycache__ 7 | *.jrr 8 | *.jrl 9 | *.yaml 10 | *.log 11 | *.png 12 | *.gif -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #################### BASIC SETUP #################### 2 | cmake_minimum_required(VERSION 3.16) 3 | project(ROSE VERSION 0.1 LANGUAGES CXX) 4 | 5 | set(CMAKE_CXX_STANDARD 17) 6 | 7 | option(EXPERIMENTS "Build experiments" OFF) 8 | 9 | #################### IMPORT DEPENDENCIES #################### 10 | find_package(GTSAM REQUIRED) 11 | 12 | #################### ADD TARGETS #################### 13 | add_subdirectory(rose) 14 | 15 | if(EXPERIMENTS) 16 | add_subdirectory(experiments) 17 | add_subdirectory(python) 18 | add_subdirectory(tests) 19 | endif(EXPERIMENTS) -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2024 Robot Perception Lab 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # ROSE: Robust Off-road wheel odometry with Slip Estimation 2 | 3 | This is the public repository for ROSE, a factor for incorporating wheel odometry measurements into factors graphs to provide increased accuracy, redundancy, and robustness. 4 | 5 |

6 | Example SVO + Rose trajectory. 9 |

10 | 11 | ROSE does this by integration wheel odometry in 6D using a piecewise planar method, as well as estimating slip and wheel intrinsics online. To learn more, please checkout our paper (TODO: Insert link). 12 | 13 | ## Building 14 | 15 | By default, ROSE only builds the wheel factors for usage in gtsam. It's only dependency when used like this is [gtsam 4.2](https://github.com/borglab/gtsam/releases/tag/4.2). This can be done simply using cmake, 16 | 17 | ```bash 18 | mkdir build 19 | cd build 20 | cmake .. -DCMAKE_BUILD_TYPE=Release 21 | make 22 | sudo make install 23 | ``` 24 | 25 | If you are interested in running our experimental setup, you'll need a [slightly custom version of gtsam](https://github.com/contagon/gtsam/tree/my-helpers-4.2) and the latest version of [JRL](https://github.com/DanMcGann/jrl). Once you have the python wrappers for both of these installed, things are built identically using cmake and make, 26 | 27 | ```bash 28 | mkdir build 29 | cd build 30 | cmake .. -DCMAKE_BUILD_TYPE=Release -DEXPERIMENTS=ON 31 | make 32 | sudo make install 33 | ``` 34 | 35 | ## Citation 36 | 37 | If citing, please reference TODO 38 | 39 | ## TODO 40 | 41 | - [ ] Fill out TODOs here once published (at least on arxiv) 42 | - [ ] Figure out licensing stuff 43 | -------------------------------------------------------------------------------- /experiments/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.11) 2 | 3 | find_package(jrl REQUIRED) 4 | 5 | # Create Library 6 | add_library(experiments 7 | src/JRL-custom.cpp 8 | src/JRLFrontend.cpp 9 | src/FixedLagBackend.cpp 10 | src/MEstBackend.cpp 11 | ) 12 | 13 | # Set Library Properties 14 | target_include_directories(experiments PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include") 15 | target_link_libraries(experiments PUBLIC jrl rose) -------------------------------------------------------------------------------- /experiments/include/FixedLagBackend.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | 6 | // These have to be in a specific order, otherwise we get boost errors 7 | // clang-format off 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | // clang-format on 20 | 21 | #include "rose/WheelFactorBase.h" 22 | 23 | using gtsam::symbol_shorthand::B; 24 | using gtsam::symbol_shorthand::I; 25 | using gtsam::symbol_shorthand::L; 26 | using gtsam::symbol_shorthand::M; 27 | using gtsam::symbol_shorthand::S; 28 | using gtsam::symbol_shorthand::V; 29 | using gtsam::symbol_shorthand::W; 30 | using gtsam::symbol_shorthand::X; 31 | using StereoFactor = gtsam::GenericStereoFactor; 32 | using FactorSet = std::set; 33 | 34 | class FixedLagBackend { 35 | private: 36 | template void addPriorEstimate(PriorFactorPointer factor); 37 | void addIMUEstimate(gtsam::CombinedImuFactor::shared_ptr factor); 38 | void addLandmarkEstimate(StereoFactor::shared_ptr factor); 39 | void addWheel2Estimate(rose::WheelFactor2::shared_ptr factor); 40 | void addWheel3Estimate(rose::WheelFactor3::shared_ptr factor); 41 | void addWheel4Estimate(rose::WheelFactor4::shared_ptr factor); 42 | void addWheel5Estimate(rose::WheelFactor5::shared_ptr factor); 43 | 44 | bool isDegenerate(gtsam::NonlinearFactor::shared_ptr factor); 45 | bool getStateToMarg(gtsam::Key &stateToMarg, bool &isKeyframe); 46 | void getLMMargDrop(gtsam::Key stateToMarg, const gtsam::VariableIndex &variableIndex, gtsam::KeySet &keysToMarg, 47 | gtsam::KeySet &keysToDrop, FactorSet &facsToMarg, FactorSet &facsToDrop); 48 | void getOdomMargDrop(gtsam::Key stateToMarg, const gtsam::VariableIndex &variableIndex, gtsam::KeySet &keysToMarg, 49 | gtsam::KeySet &keysToDrop, FactorSet &facsToMarg, FactorSet &facsToDrop); 50 | 51 | protected: 52 | gtsam::NonlinearFactorGraph graph_; 53 | gtsam::Values state_; 54 | 55 | uint64_t regframeNum_ = 5; 56 | uint64_t keyframeNum_ = 5; 57 | double keyframeDist_ = 0.1; 58 | 59 | // Empty slots to fill graph, so graph doesn't grow exponentially 60 | std::queue graphEmptySlots_; 61 | // Connections between states (X) and landmarks (L) 62 | std::map mapKey2Key_; 63 | // Keyframe indices (NOT GTSAM KEYS) 64 | std::queue keyFrames_; 65 | // Regframe indices (NOT GTSAM KEYS) 66 | std::queue regFrames_; 67 | 68 | uint64_t marginalIdx_; 69 | 70 | virtual gtsam::NoiseModelFactor::shared_ptr processFactor(gtsam::NoiseModelFactor::shared_ptr factor) = 0; 71 | 72 | public: 73 | void setRegframeNum(uint64_t regframeNum) { regframeNum_ = regframeNum; } 74 | void setKeyframeNum(uint64_t keyframeNum) { keyframeNum_ = keyframeNum; } 75 | void setKeyframeSpace(float keyframeDist) { keyframeDist_ = keyframeDist; } 76 | 77 | virtual std::string getName() { return "BaseBackend"; } 78 | gtsam::Values getState() { return state_; }; 79 | gtsam::NonlinearFactorGraph getGraph() { return graph_; }; 80 | uint64_t getCurrNumKeyframes() { return keyFrames_.size(); }; 81 | uint64_t getCurrNumRegframes() { return regFrames_.size(); }; 82 | 83 | // Each call to this will only remove 1 state 84 | void marginalize(); 85 | void addMeasurements(gtsam::NonlinearFactorGraph graph, uint64_t stateIdx); 86 | virtual void solve() = 0; 87 | }; -------------------------------------------------------------------------------- /experiments/include/JRL-custom.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "jrl/IOMeasurements.h" 4 | #include "jrl/IOValues.h" 5 | #include "jrl/Metrics.h" 6 | 7 | #include "gtsam/base/types.h" 8 | #include 9 | #include 10 | #include 11 | #include 12 | 13 | #include "rose/PlanarPriorFactor.h" 14 | #include "rose/WheelBaseline.h" 15 | #include "rose/WheelFactorBase.h" 16 | #include "rose/WheelRose.h" 17 | #include "rose/ZPriorFactor.h" 18 | 19 | using namespace rose; 20 | 21 | namespace jrl_rose { 22 | 23 | static const std::string IMUBiasTag = "IMUBias"; 24 | static const std::string StereoPoint2Tag = "StereoPoint2"; 25 | 26 | static const std::string StereoFactorPose3Point3Tag = "StereoFactorPose3Point3"; 27 | static const std::string CombinedIMUTag = "CombinedIMU"; 28 | static const std::string PriorFactorIMUBiasTag = "PriorFactorIMUBias"; 29 | 30 | static const std::string PlanarPriorTag = "PlanarPrior"; 31 | static const std::string ZPriorTag = "ZPrior"; 32 | static const std::string WheelBaselineTag = "WheelBaseline"; 33 | 34 | static const std::string WheelRoseTag = "WheelRose"; 35 | static const std::string WheelRoseSlipTag = "WheelRoseSlip"; 36 | static const std::string WheelRoseIntrTag = "WheelRoseIntrinsics"; 37 | static const std::string WheelRoseIntrSlipTag = "WheelRoseIntrinsicsSlip"; 38 | 39 | // ------------------------- Values ------------------------- // 40 | // StereoPoint2 41 | gtsam::StereoPoint2 parseStereoPoint2(const json &input_json); 42 | 43 | json serializeStereoPoint2(gtsam::StereoPoint2 point); 44 | 45 | // ConstantBias 46 | gtsam::imuBias::ConstantBias parseIMUBias(const json &input_json); 47 | 48 | json serializeIMUBias(gtsam::imuBias::ConstantBias point); 49 | 50 | // ------------------------- Matrices ------------------------- // 51 | gtsam::Matrix parseMatrix(const json &input_json, int row, int col); 52 | 53 | json serializeMatrix(gtsam::Matrix mat); 54 | 55 | gtsam::Matrix parseCovariance(json input_json, int d); 56 | 57 | json serializeCovariance(gtsam::Matrix covariance); 58 | 59 | // ------------------------- IMUFactor ------------------------- // 60 | gtsam::NonlinearFactor::shared_ptr parseCombinedIMUFactor(const json &input_json); 61 | 62 | json serializeCombinedIMUFactor(std::string type_tag, gtsam::NonlinearFactor::shared_ptr &factor); 63 | 64 | // ------------------------- StereoFactor ------------------------- // 65 | gtsam::NonlinearFactor::shared_ptr parseStereoFactor(const json &input_json); 66 | 67 | json serializeStereoFactor(std::string type_tag, gtsam::NonlinearFactor::shared_ptr &factor); 68 | 69 | // ------------------------- PlanarPrior ------------------------- // 70 | gtsam::NonlinearFactor::shared_ptr parsePlanarPriorFactor(const nlohmann::json &input_json); 71 | 72 | nlohmann::json serializePlanarPriorFactor(gtsam::NonlinearFactor::shared_ptr factor); 73 | 74 | gtsam::NonlinearFactor::shared_ptr parseZPriorFactor(const nlohmann::json &input_json); 75 | 76 | nlohmann::json serializeZPriorFactor(gtsam::NonlinearFactor::shared_ptr factor); 77 | 78 | // ------------------------- WheelBase ------------------------- // 79 | typedef std::function PWParser; 80 | typedef std::function PWSerializer; 81 | 82 | PreintegratedWheelBase::shared_ptr parsePWBase(const nlohmann::json &input_json); 83 | 84 | nlohmann::json serializePWBase(PreintegratedWheelBase::shared_ptr pwm); 85 | 86 | gtsam::NonlinearFactor::shared_ptr parseWheelFactor2(const nlohmann::json &input_json, PWParser pwparser); 87 | 88 | nlohmann::json serializeWheelFactor2(std::string tag, PWSerializer pwser, gtsam::NonlinearFactor::shared_ptr factor); 89 | 90 | gtsam::NonlinearFactor::shared_ptr parseWheelFactor3(const nlohmann::json &input_json, PWParser pwparser); 91 | 92 | nlohmann::json serializeWheelFactor3(std::string tag, PWSerializer pwser, gtsam::NonlinearFactor::shared_ptr factor); 93 | 94 | gtsam::NonlinearFactor::shared_ptr parseWheelFactor4(const nlohmann::json &input_json, PWParser pwparser); 95 | 96 | nlohmann::json serializeWheelFactor4(std::string tag, PWSerializer pwser, gtsam::NonlinearFactor::shared_ptr factor); 97 | 98 | gtsam::NonlinearFactor::shared_ptr parseWheelFactor5(const nlohmann::json &input_json, PWParser pwparser); 99 | 100 | nlohmann::json serializeWheelFactor5(std::string tag, PWSerializer pwser, gtsam::NonlinearFactor::shared_ptr factor); 101 | 102 | // ------------------------- Baseline ------------------------- // 103 | PreintegratedWheelBase::shared_ptr parsePWMBaseline(nlohmann::json input_json); 104 | 105 | // ------------------------- ROSE ------------------------- // 106 | PreintegratedWheelRose::shared_ptr parsePWMRose(const nlohmann::json &input_json); 107 | 108 | nlohmann::json serializePWMRose(PreintegratedWheelBase::shared_ptr pwm); 109 | 110 | // ------------------------- Metrics ------------------------- // 111 | template 112 | std::pair computeATE(gtsam::Values ref, gtsam::Values est, bool align = false, 113 | bool align_with_scale = false) { 114 | est = est.filter(); 115 | if (align) { 116 | est = jrl::alignment::align(est, ref, align_with_scale); 117 | } 118 | 119 | double squared_translation_error = 0.0; 120 | double squared_rotation_error = 0.0; 121 | for (auto &key : est.keys()) { 122 | std::pair squared_pose_error = 123 | jrl::metrics::internal::squaredPoseError(est.at(key), ref.at(key)); 124 | 125 | squared_translation_error += squared_pose_error.first; 126 | squared_rotation_error += squared_pose_error.second; 127 | } 128 | 129 | // Return the RMSE of the pose errors 130 | return std::make_pair(std::sqrt(squared_translation_error / est.size()), 131 | std::sqrt(squared_rotation_error / est.size())); 132 | } 133 | 134 | } // namespace jrl_rose 135 | -------------------------------------------------------------------------------- /experiments/include/JRL.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "jrl/IOMeasurements.h" 4 | #include "jrl/IOValues.h" 5 | #include "jrl/Parser.h" 6 | #include "jrl/Writer.h" 7 | 8 | #include "rose/PlanarPriorFactor.h" 9 | #include "rose/WheelBaseline.h" 10 | #include "rose/WheelFactorBase.h" 11 | #include "rose/WheelRose.h" 12 | #include "rose/ZPriorFactor.h" 13 | 14 | #include "JRL-custom.h" 15 | 16 | // ------------------------- Register Custom Options ------------------------- // 17 | namespace jrl_rose { 18 | inline jrl::Parser makeRoseParser() { 19 | jrl::Parser parser; 20 | 21 | // clang-format off 22 | parser.registerMeasurementParser(WheelRoseTag, [](const json& input){ return parseWheelFactor2(input, parsePWMRose); }); 23 | parser.registerMeasurementParser(WheelRoseSlipTag, [](const json& input){ return parseWheelFactor3(input, parsePWMRose); }); 24 | parser.registerMeasurementParser(WheelRoseIntrTag, [](const json& input){ return parseWheelFactor4(input, parsePWMRose); }); 25 | parser.registerMeasurementParser(WheelRoseIntrSlipTag, [](const json& input){ return parseWheelFactor5(input, parsePWMRose); }); 26 | 27 | parser.registerMeasurementParser(WheelBaselineTag, [](const json& input){ return parseWheelFactor2(input, parsePWMBaseline); }); 28 | 29 | parser.registerMeasurementParser(PlanarPriorTag, parsePlanarPriorFactor); 30 | parser.registerMeasurementParser(ZPriorTag, parseZPriorFactor); 31 | 32 | parser.registerMeasurementParser(CombinedIMUTag, [](const json& input){ return parseCombinedIMUFactor(input); }); 33 | parser.registerMeasurementParser(StereoFactorPose3Point3Tag, [](const json& input){ return parseStereoFactor(input); }); 34 | parser.registerMeasurementParser(PriorFactorIMUBiasTag, [](const json& input) { return jrl::io_measurements::parsePrior(&parseIMUBias, input); }); 35 | parser.registerValueParser(IMUBiasTag, [](const json& input, gtsam::Key key, gtsam::Values& accum) { return jrl::io_values::valueAccumulator(&parseIMUBias, input, key, accum); }); 36 | parser.registerValueParser(StereoPoint2Tag, [](const json& input, gtsam::Key key, gtsam::Values& accum) { return jrl::io_values::valueAccumulator(&parseStereoPoint2, input, key, accum); }); 37 | // clang-format on 38 | 39 | return parser; 40 | } 41 | 42 | inline jrl::Writer makeRoseWriter() { 43 | jrl::Writer writer; 44 | 45 | // clang-format off 46 | writer.registerMeasurementSerializer(WheelRoseTag, [](gtsam::NonlinearFactor::shared_ptr factor) { return serializeWheelFactor2(WheelRoseTag, serializePWMRose, factor); }); 47 | writer.registerMeasurementSerializer(WheelRoseSlipTag, [](gtsam::NonlinearFactor::shared_ptr factor) { return serializeWheelFactor3(WheelRoseSlipTag, serializePWMRose, factor); }); 48 | writer.registerMeasurementSerializer(WheelRoseIntrTag, [](gtsam::NonlinearFactor::shared_ptr factor) { return serializeWheelFactor4(WheelRoseIntrTag, serializePWMRose, factor); }); 49 | writer.registerMeasurementSerializer(WheelRoseIntrSlipTag, [](gtsam::NonlinearFactor::shared_ptr factor) { return serializeWheelFactor5(WheelRoseIntrSlipTag, serializePWMRose, factor); }); 50 | 51 | writer.registerMeasurementSerializer(WheelBaselineTag, [](gtsam::NonlinearFactor::shared_ptr factor) { return serializeWheelFactor2(WheelBaselineTag, serializePWBase, factor); }); 52 | 53 | writer.registerMeasurementSerializer(PlanarPriorTag, serializePlanarPriorFactor); 54 | writer.registerMeasurementSerializer(ZPriorTag, serializeZPriorFactor); 55 | 56 | writer.registerMeasurementSerializer(CombinedIMUTag, [](gtsam::NonlinearFactor::shared_ptr factor) { return serializeCombinedIMUFactor(CombinedIMUTag, factor); }); 57 | writer.registerMeasurementSerializer(StereoFactorPose3Point3Tag, [](gtsam::NonlinearFactor::shared_ptr factor) { return serializeStereoFactor(StereoFactorPose3Point3Tag, factor); }); 58 | writer.registerMeasurementSerializer(PriorFactorIMUBiasTag, [](gtsam::NonlinearFactor::shared_ptr& factor) { return jrl::io_measurements::serializePrior(&serializeIMUBias, PriorFactorIMUBiasTag, factor); }); 59 | writer.registerValueSerializer(IMUBiasTag, [](gtsam::Key key, gtsam::Values& vals) { return serializeIMUBias(vals.at(key)); }); 60 | writer.registerValueSerializer(StereoPoint2Tag, [](gtsam::Key key, gtsam::Values& vals) { return serializeStereoPoint2(vals.at(key)); }); 61 | // clang-format on 62 | 63 | return writer; 64 | } 65 | } // namespace jrl_rose -------------------------------------------------------------------------------- /experiments/include/JRLFrontend.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | #include 7 | 8 | #include "FixedLagBackend.h" 9 | #include "JRL-custom.h" 10 | #include "JRL.h" 11 | #include "tqdm.h" 12 | 13 | using gtsam::symbol_shorthand::B; 14 | using gtsam::symbol_shorthand::L; 15 | using gtsam::symbol_shorthand::V; 16 | using gtsam::symbol_shorthand::X; 17 | 18 | class JRLFrontend { 19 | private: 20 | boost::shared_ptr backend_; 21 | 22 | // TODO: Some sort of structure to hold intermediate results 23 | // - timing 24 | // - errors 25 | // - outliers results at various checkpoints 26 | 27 | jrl::TypedValues makeTypedValues(gtsam::Values values); 28 | 29 | public: 30 | JRLFrontend(boost::shared_ptr backend); 31 | 32 | gtsam::Values run(jrl::Dataset &dataset, std::vector sensors, std::string outfile, int n_steps = 0, 33 | bool use_tqdm = true); 34 | }; -------------------------------------------------------------------------------- /experiments/include/LMBackend.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "FixedLagBackend.h" 4 | 5 | class LMBackend : public FixedLagBackend { 6 | protected: 7 | gtsam::NoiseModelFactor::shared_ptr processFactor(gtsam::NoiseModelFactor::shared_ptr factor); 8 | 9 | public: 10 | void solve(); 11 | std::string getName() { return "LM"; } 12 | }; -------------------------------------------------------------------------------- /experiments/include/MEstBackend.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "FixedLagBackend.h" 4 | 5 | class MEstBackend : public FixedLagBackend { 6 | protected: 7 | gtsam::noiseModel::mEstimator::Base::shared_ptr robustKernel_; 8 | std::string kernelName_; 9 | 10 | gtsam::NoiseModelFactor::shared_ptr processFactor(gtsam::NoiseModelFactor::shared_ptr factor); 11 | 12 | public: 13 | MEstBackend(gtsam::noiseModel::mEstimator::Base::shared_ptr robustKernel, std::string kernelName) 14 | : robustKernel_(robustKernel), kernelName_(kernelName) {} 15 | 16 | void solve(); 17 | std::string getName() { return "MEst-" + kernelName_; } 18 | }; -------------------------------------------------------------------------------- /experiments/include/tqdm.h: -------------------------------------------------------------------------------- 1 | /****************** 2 | 3 | Gotten from: https://github.com/aminnj/cpptqdm 4 | 5 | Licensed under MIT, see above repo. 6 | 7 | *****************/ 8 | #ifndef TQDM_H 9 | #define TQDM_H 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | 22 | class tqdm { 23 | private: 24 | // time, iteration counters and deques for rate calculations 25 | std::chrono::time_point t_first = std::chrono::system_clock::now(); 26 | std::chrono::time_point t_old = std::chrono::system_clock::now(); 27 | int n_old = 0; 28 | std::vector deq_t; 29 | std::vector deq_n; 30 | int nupdates = 0; 31 | int total_ = 0; 32 | int period = 1; 33 | unsigned int smoothing = 50; 34 | bool use_ema = true; 35 | float alpha_ema = 0.1; 36 | 37 | std::vector bars = {" ", "▏", "▎", "▍", "▌", "▋", "▊", "▉", "█"}; 38 | 39 | bool in_screen = (system("test $STY") == 0); 40 | bool in_tmux = (system("test $TMUX") == 0); 41 | bool is_tty = isatty(1); 42 | bool use_colors = true; 43 | bool color_transition = true; 44 | int width = 40; 45 | 46 | std::string right_pad = "▏"; 47 | std::string label = ""; 48 | 49 | void hsv_to_rgb(float h, float s, float v, int &r, int &g, int &b) { 50 | if (s < 1e-6) { 51 | v *= 255.; 52 | r = v; 53 | g = v; 54 | b = v; 55 | } 56 | int i = (int)(h * 6.0); 57 | float f = (h * 6.) - i; 58 | int p = (int)(255.0 * (v * (1. - s))); 59 | int q = (int)(255.0 * (v * (1. - s * f))); 60 | int t = (int)(255.0 * (v * (1. - s * (1. - f)))); 61 | v *= 255; 62 | i %= 6; 63 | int vi = (int)v; 64 | if (i == 0) { 65 | r = vi; 66 | g = t; 67 | b = p; 68 | } else if (i == 1) { 69 | r = q; 70 | g = vi; 71 | b = p; 72 | } else if (i == 2) { 73 | r = p; 74 | g = vi; 75 | b = t; 76 | } else if (i == 3) { 77 | r = p; 78 | g = q; 79 | b = vi; 80 | } else if (i == 4) { 81 | r = t; 82 | g = p; 83 | b = vi; 84 | } else if (i == 5) { 85 | r = vi; 86 | g = p; 87 | b = q; 88 | } 89 | } 90 | 91 | public: 92 | tqdm() { 93 | if (in_screen) { 94 | set_theme_basic(); 95 | color_transition = false; 96 | } else if (in_tmux) { 97 | color_transition = false; 98 | } 99 | } 100 | 101 | void reset() { 102 | t_first = std::chrono::system_clock::now(); 103 | t_old = std::chrono::system_clock::now(); 104 | n_old = 0; 105 | deq_t.clear(); 106 | deq_n.clear(); 107 | period = 1; 108 | nupdates = 0; 109 | total_ = 0; 110 | label = ""; 111 | } 112 | 113 | void set_theme_line() { bars = {"─", "─", "─", "╾", "╾", "╾", "╾", "━", "═"}; } 114 | void set_theme_circle() { bars = {" ", "◓", "◑", "◒", "◐", "◓", "◑", "◒", "#"}; } 115 | void set_theme_braille() { bars = {" ", "⡀", "⡄", "⡆", "⡇", "⡏", "⡟", "⡿", "⣿"}; } 116 | void set_theme_braille_spin() { bars = {" ", "⠙", "⠹", "⠸", "⠼", "⠴", "⠦", "⠇", "⠿"}; } 117 | void set_theme_vertical() { bars = {"▁", "▂", "▃", "▄", "▅", "▆", "▇", "█", "█"}; } 118 | void set_theme_basic() { 119 | bars = {" ", " ", " ", " ", " ", " ", " ", " ", "#"}; 120 | right_pad = "|"; 121 | } 122 | void set_label(std::string label_) { label = label_; } 123 | void disable_colors() { 124 | color_transition = false; 125 | use_colors = false; 126 | } 127 | 128 | void finish() { 129 | progress(total_, total_); 130 | printf("\n"); 131 | fflush(stdout); 132 | } 133 | void progress(int curr, int tot) { 134 | if (is_tty && (curr % period == 0)) { 135 | total_ = tot; 136 | nupdates++; 137 | auto now = std::chrono::system_clock::now(); 138 | double dt = ((std::chrono::duration)(now - t_old)).count(); 139 | double dt_tot = ((std::chrono::duration)(now - t_first)).count(); 140 | int dn = curr - n_old; 141 | n_old = curr; 142 | t_old = now; 143 | if (deq_n.size() >= smoothing) 144 | deq_n.erase(deq_n.begin()); 145 | if (deq_t.size() >= smoothing) 146 | deq_t.erase(deq_t.begin()); 147 | deq_t.push_back(dt); 148 | deq_n.push_back(dn); 149 | 150 | double avgrate = 0.; 151 | if (use_ema) { 152 | avgrate = deq_n[0] / deq_t[0]; 153 | for (unsigned int i = 1; i < deq_t.size(); i++) { 154 | double r = 1.0 * deq_n[i] / deq_t[i]; 155 | avgrate = alpha_ema * r + (1.0 - alpha_ema) * avgrate; 156 | } 157 | } else { 158 | double dtsum = std::accumulate(deq_t.begin(), deq_t.end(), 0.); 159 | int dnsum = std::accumulate(deq_n.begin(), deq_n.end(), 0.); 160 | avgrate = dnsum / dtsum; 161 | } 162 | 163 | // learn an appropriate period length to avoid spamming stdout 164 | // and slowing down the loop, shoot for ~25Hz and smooth over 3 165 | // seconds 166 | if (nupdates > 10) { 167 | period = (int)(std::min(std::max((1.0 / 25) * curr / dt_tot, 1.0), 5e5)); 168 | smoothing = 25 * 3; 169 | } 170 | double peta = (tot - curr) / avgrate; 171 | double pct = (double)curr / (tot * 0.01); 172 | if ((tot - curr) <= period) { 173 | pct = 100.0; 174 | avgrate = tot / dt_tot; 175 | curr = tot; 176 | peta = 0; 177 | } 178 | 179 | double fills = ((double)curr / tot * width); 180 | int ifills = (int)fills; 181 | 182 | printf("\015 "); 183 | if (use_colors) { 184 | if (color_transition) { 185 | // red (hue=0) to green (hue=1/3) 186 | int r = 255, g = 255, b = 255; 187 | hsv_to_rgb(0.0 + 0.01 * pct / 3, 0.65, 1.0, r, g, b); 188 | printf("\033[38;2;%d;%d;%dm ", r, g, b); 189 | } else { 190 | printf("\033[32m "); 191 | } 192 | } 193 | for (int i = 0; i < ifills; i++) 194 | std::cout << bars[8]; 195 | if (!in_screen and (curr != tot)) 196 | printf("%s", bars[(int)(8.0 * (fills - ifills))]); 197 | for (int i = 0; i < width - ifills - 1; i++) 198 | std::cout << bars[0]; 199 | printf("%s ", right_pad.c_str()); 200 | if (use_colors) 201 | printf("\033[1m\033[31m"); 202 | printf("%4.1f%% ", pct); 203 | if (use_colors) 204 | printf("\033[34m"); 205 | 206 | std::string unit = "Hz"; 207 | double div = 1.; 208 | if (avgrate > 1e6) { 209 | unit = "MHz"; 210 | div = 1.0e6; 211 | } else if (avgrate > 1e3) { 212 | unit = "kHz"; 213 | div = 1.0e3; 214 | } 215 | printf("[%4d/%4d | %3.1f %s | %.0fs<%.0fs] ", curr, tot, avgrate / div, unit.c_str(), dt_tot, peta); 216 | printf("%s ", label.c_str()); 217 | if (use_colors) 218 | printf("\033[0m\033[32m\033[0m\015 "); 219 | 220 | if ((tot - curr) > period) 221 | fflush(stdout); 222 | } 223 | } 224 | }; 225 | #endif -------------------------------------------------------------------------------- /experiments/src/JRLFrontend.cpp: -------------------------------------------------------------------------------- 1 | #include "JRLFrontend.h" 2 | // #include 3 | 4 | // using time_point = std::chrono::time_point; 5 | // void init_time(time_point& start){ 6 | // start = std::chrono::high_resolution_clock::now(); 7 | // } 8 | // void step(time_point& start, std::string out){ 9 | // auto stop = std::chrono::high_resolution_clock::now(); 10 | // auto duration = std::chrono::duration_cast(stop - start); 11 | // std::cout << out << " " << duration.count() << std::endl; 12 | // init_time(start); 13 | // } 14 | 15 | JRLFrontend::JRLFrontend(boost::shared_ptr backend) : backend_(backend) {} 16 | 17 | jrl::TypedValues JRLFrontend::makeTypedValues(gtsam::Values values) { 18 | jrl::ValueTypes types; 19 | for (gtsam::Symbol key : values.keys()) { 20 | if (key.chr() == 'x') { 21 | types[key] = jrl::Pose3Tag; 22 | } else if (key.chr() == 'w') { 23 | types[key] = jrl::Pose3Tag; 24 | } else if (key.chr() == 'i') { 25 | types[key] = jrl::Point3Tag; 26 | } else if (key.chr() == 'v') { 27 | types[key] = jrl::Point3Tag; 28 | } else if (key.chr() == 'b') { 29 | types[key] = jrl_rose::IMUBiasTag; 30 | } else if (key.chr() == 'l') { 31 | types[key] = jrl::Point3Tag; 32 | } else if (key.chr() == 's') { 33 | types[key] = jrl::Point2Tag; 34 | } else { 35 | throw std::range_error("Trying to assign ValueTags, " + std::to_string(key.chr()) + " lacks a definition."); 36 | } 37 | } 38 | return jrl::TypedValues(values, types); 39 | } 40 | 41 | gtsam::Values JRLFrontend::run(jrl::Dataset &dataset, std::vector sensors, std::string outfile, 42 | int n_steps, bool use_tqdm) { 43 | std::vector measurements = dataset.measurements('a'); 44 | gtsam::Values gt = dataset.groundTruth('a'); 45 | 46 | // Set everything up 47 | tqdm bar; 48 | bar.set_theme_basic(); 49 | if (use_tqdm) { 50 | } 51 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 52 | n_steps = (n_steps == 0 || n_steps > measurements.size()) ? measurements.size() : n_steps; 53 | gtsam::Values finalValues; 54 | 55 | // Iterate over each timestep 56 | for (uint64_t i = 0; i < n_steps; ++i) { 57 | jrl::Entry entry = measurements[i].filter(sensors); 58 | 59 | backend_->addMeasurements(entry.measurements, entry.stamp); 60 | backend_->solve(); 61 | backend_->marginalize(); 62 | 63 | // Print each timestep of results 64 | if (use_tqdm) { 65 | auto ate = jrl_rose::computeATE(gt, backend_->getState(), false); 66 | bar.progress(i, n_steps); 67 | bar.set_label("#F: " + std::to_string(backend_->getGraph().nrFactors()) + 68 | // ", #RF: " + std::to_string(backend_->getCurrNumRegframes()) + 69 | // ", #KF: " + std::to_string(backend_->getCurrNumKeyframes()) + 70 | ", ATEt: " + std::to_string(ate.first)); // + ", ATErot: " + std::to_string(ate.second)); 71 | } 72 | // Copy for our perfect version 73 | finalValues.insert_or_assign(backend_->getState()); 74 | } 75 | if (use_tqdm) { 76 | bar.finish(); 77 | } 78 | 79 | std::string methodInfo = outfile.substr(outfile.find_last_of("/") + 1); 80 | jrl::Results finalResults(dataset.name(), methodInfo, {'a'}, {{'a', makeTypedValues(finalValues)}}); 81 | writer.writeResults(finalResults, outfile); 82 | 83 | return finalValues; 84 | } -------------------------------------------------------------------------------- /experiments/src/MEstBackend.cpp: -------------------------------------------------------------------------------- 1 | #include "MEstBackend.h" 2 | 3 | gtsam::NoiseModelFactor::shared_ptr MEstBackend::processFactor(gtsam::NoiseModelFactor::shared_ptr factor) { 4 | auto stereo = boost::dynamic_pointer_cast(factor); 5 | if (stereo) { 6 | return factor->cloneWithNewNoiseModel(gtsam::noiseModel::Robust::Create(robustKernel_, factor->noiseModel())); 7 | } else { 8 | return factor; 9 | } 10 | } 11 | 12 | void MEstBackend::solve() { 13 | gtsam::LevenbergMarquardtParams m_params; 14 | gtsam::LevenbergMarquardtOptimizer optimizer(graph_, state_, m_params); 15 | state_ = optimizer.optimize(); 16 | } -------------------------------------------------------------------------------- /figures/header.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/rpl-cmu/rose/556005669cb9f76b94669d0ad36361ef8978f4a6/figures/header.pdf -------------------------------------------------------------------------------- /figures/header.py: -------------------------------------------------------------------------------- 1 | from pathlib import Path 2 | 3 | import earthpy.spatial as es 4 | import matplotlib.pyplot as plt 5 | import numpy as np 6 | import rasterio 7 | import rose.jrl 8 | import rose.plot as plot 9 | import seaborn as sns 10 | from rasterio.warp import Resampling, calculate_default_transform, reproject 11 | from rose.dataset import Dataset2JRL, Sensor 12 | from rose import FlatDataset 13 | 14 | if __name__ == "__main__": 15 | traj = "all_2024-02-09-14-08-29" 16 | 17 | is_top = True 18 | map_file = "/home/contagon/Downloads/ned19_n40x50_w080x00_pa_southwest_2006.img" 19 | 20 | is_top = False 21 | map_file = "/home/contagon/catkin_new/src/multicam_frontend_ros/config/gascola_imagery_august_2020/gascola_august_2020.vrt" 22 | 23 | # ------------------------- Load in topographical map ------------------------- # 24 | dst_crs = "EPSG:32617" 25 | src = rasterio.open(map_file) 26 | 27 | transform, width, height = calculate_default_transform( 28 | src.crs, dst_crs, src.width, src.height, *src.bounds 29 | ) 30 | kwargs = src.meta.copy() 31 | kwargs.update( 32 | {"crs": dst_crs, "transform": transform, "width": width, "height": height} 33 | ) 34 | 35 | depth = 1 if is_top else 3 36 | 37 | destination = np.zeros((height, width, depth), dtype=src.dtypes[0]) 38 | 39 | for i in range(1, depth + 1): 40 | reproject( 41 | source=rasterio.band(src, i), 42 | destination=destination[:, :, i - 1], 43 | src_transform=src.transform, 44 | src_crs=src.crs, 45 | dst_transform=transform, 46 | dst_crs=dst_crs, 47 | resampling=Resampling.nearest, 48 | ) 49 | destination[destination < 0] = 200 50 | destination = destination.squeeze() 51 | print("Loaded topographical map") 52 | 53 | # ------------------------- Load all data ------------------------- # 54 | RESULTS = Path(f"data/{traj}") 55 | 56 | # Have to load this to get transform utm_T_vio 57 | dataset = FlatDataset(Path(f"/mnt/data/flat/{traj}")) 58 | data = Dataset2JRL(dataset) 59 | data.add_factors(Sensor.PRIOR) 60 | data.get_ground_truth() 61 | 62 | types = { 63 | plot.WheelType.GT.value: "_gt.jrr", 64 | plot.WheelType.WHEEL.value: "_wheel.jrr", 65 | plot.WheelType.WHEEL_PLANAR.value: "f-base.wheel_baseline.planar_prior.jrr", 66 | plot.WheelType.WHEEL_ROSE_INTR_SLIP.value: "f-base.wheel_intr_slip.jrr", 67 | } 68 | 69 | results = {} 70 | for name, filename in types.items(): 71 | values = ( 72 | rose.jrl.makeRoseParser() 73 | .parseResults(str(RESULTS / filename), False) 74 | .robot_solutions["a"] 75 | .values 76 | ) 77 | results[name] = plot.load_full_state(values, offset=data.utm_T_vio) 78 | 79 | print("Data Loaded") 80 | # ------------------------- Plot data ------------------------- # 81 | colors = plot.setup_plot() 82 | fig, ax = plt.subplots(1, 1, layout="constrained", figsize=(4, 4)) 83 | 84 | min_x, max_x, min_y, max_y = np.inf, -np.inf, np.inf, -np.inf 85 | for name, values in results.items(): 86 | if min_x > np.min(values["$p_y$"]): 87 | min_x = np.min(values["$p_y$"]) 88 | if max_x < np.max(values["$p_y$"]): 89 | max_x = np.max(values["$p_y$"]) 90 | if min_y > np.min(values["$p_x$"]): 91 | min_y = np.min(values["$p_x$"]) 92 | if max_y < np.max(values["$p_x$"]): 93 | max_y = np.max(values["$p_x$"]) 94 | 95 | diff = 25 96 | min_x -= diff 97 | max_x += diff 98 | min_y -= diff 99 | max_y += diff 100 | 101 | x1, y1 = ~transform * (min_x, min_y) 102 | x2, y2 = ~transform * (max_x, max_y) 103 | final_map = destination[int(y2) : int(y1), int(x1) : int(x2)] 104 | extent = [0, max_x - min_x, 0, max_y - min_y] 105 | 106 | if is_top: 107 | cmap = sns.diverging_palette(220, 20, s=40, as_cmap=True) 108 | plt.imshow(final_map, extent=extent, cmap=cmap) 109 | plt.colorbar() 110 | 111 | hillshade = es.hillshade(final_map, azimuth=90, altitude=1) 112 | plt.imshow(hillshade, extent=extent, cmap="Greys", alpha=0.2) 113 | else: 114 | plt.imshow(final_map, extent=extent, cmap="grey", alpha=0.55) 115 | 116 | dark_ones = [plot.WheelType.WHEEL_ROSE_INTR_SLIP.value, plot.WheelType.GT.value] 117 | for name, values in results.items(): 118 | alpha = 1 if name in dark_ones else 0.9 119 | lw = 1.25 if name in dark_ones else 0.8 120 | ax.plot( 121 | values["$p_y$"] - min_x, 122 | values["$p_x$"] - min_y, 123 | label=name, 124 | c=colors[name], 125 | lw=lw, 126 | alpha=alpha, 127 | ) 128 | 129 | ax.set_aspect("equal") 130 | # ax.set_xlabel("East (m)") 131 | # ax.set_ylabel("North (m)") 132 | # ax.tick_params(axis="both", pad=-1) 133 | ax.set_xticks([]) 134 | ax.set_yticks([]) 135 | ax.grid(False) 136 | 137 | ob = plot.AnchoredHScaleBar( 138 | size=50, 139 | extent=0.02, 140 | label="50m", 141 | loc=1, 142 | frameon=True, 143 | ppad=1.75, 144 | sep=1, 145 | linekw=dict(color=colors["GT"], lw=0.6), 146 | framecolor=(0.6, 0.6, 0.6), 147 | # label_outline=0.75, 148 | ) 149 | ax.add_artist(ob) 150 | 151 | fig.legend(loc="lower center", ncol=4, bbox_to_anchor=(0.5, -0.07)) 152 | 153 | plt.savefig("figures/header.png", bbox_inches="tight", dpi=300) 154 | plt.savefig("figures/header.pdf", bbox_inches="tight", dpi=300) 155 | 156 | # plt.show() 157 | -------------------------------------------------------------------------------- /figures/header_animated.py: -------------------------------------------------------------------------------- 1 | from pathlib import Path 2 | 3 | import matplotlib.animation as animation 4 | import matplotlib.pyplot as plt 5 | import numpy as np 6 | import rasterio 7 | import rose.jrl 8 | import rose.plot as plot 9 | from rasterio.warp import Resampling, calculate_default_transform, reproject 10 | from rose.dataset import Dataset2JRL, Sensor 11 | from rose import FlatDataset 12 | from tqdm import tqdm 13 | 14 | 15 | def animate(traj): 16 | map_file = "/home/contagon/catkin_new/src/multicam_frontend_ros/config/gascola_imagery_august_2020/gascola_august_2020.vrt" 17 | 18 | # ------------------------- Load in topographical map ------------------------- # 19 | dst_crs = "EPSG:32617" 20 | src = rasterio.open(map_file) 21 | 22 | transform, width, height = calculate_default_transform( 23 | src.crs, dst_crs, src.width, src.height, *src.bounds 24 | ) 25 | kwargs = src.meta.copy() 26 | kwargs.update( 27 | {"crs": dst_crs, "transform": transform, "width": width, "height": height} 28 | ) 29 | 30 | destination = np.zeros((height, width, 3), dtype=src.dtypes[0]) 31 | 32 | for i in range(1, 4): 33 | reproject( 34 | source=rasterio.band(src, i), 35 | destination=destination[:, :, i - 1], 36 | src_transform=src.transform, 37 | src_crs=src.crs, 38 | dst_transform=transform, 39 | dst_crs=dst_crs, 40 | resampling=Resampling.nearest, 41 | ) 42 | destination[destination < 0] = 200 43 | destination = destination.squeeze() 44 | print("----Loaded topographical map") 45 | 46 | # ------------------------- Load all data ------------------------- # 47 | RESULTS = Path(f"data/{traj}") 48 | 49 | # Have to load this to get transform utm_T_vio 50 | dataset = FlatDataset(Path(f"/mnt/data/flat/{traj}")) 51 | data = Dataset2JRL(dataset) 52 | data.add_factors(Sensor.PRIOR) 53 | data.get_ground_truth() 54 | 55 | types = { 56 | plot.WheelType.GT.value: "_gt.jrr", 57 | plot.WheelType.WHEEL.value: "_wheel.jrr", 58 | plot.WheelType.WHEEL_PLANAR.value: "f-base.wheel_baseline.planar_prior.jrr", 59 | plot.WheelType.WHEEL_ROSE_INTR_SLIP.value: "f-base.wheel_intr_slip.jrr", 60 | } 61 | 62 | results = {} 63 | for name, filename in types.items(): 64 | values = ( 65 | rose.jrl.makeRoseParser() 66 | .parseResults(str(RESULTS / filename), False) 67 | .robot_solutions["a"] 68 | .values 69 | ) 70 | results[name] = plot.load_full_state(values, offset=data.utm_T_vio) 71 | 72 | print("----Data Loaded") 73 | 74 | # ------------------------- Plot data ------------------------- # 75 | ratio = 16 / 9 76 | width = 8 77 | 78 | colors = plot.setup_plot() 79 | fig, ax = plt.subplots(1, 1, layout="constrained", figsize=(width, width / ratio)) 80 | 81 | min_x, max_x, min_y, max_y = np.inf, -np.inf, np.inf, -np.inf 82 | for name, values in results.items(): 83 | if min_x > np.min(values["$p_y$"]): 84 | min_x = np.min(values["$p_y$"]) 85 | if max_x < np.max(values["$p_y$"]): 86 | max_x = np.max(values["$p_y$"]) 87 | if min_y > np.min(values["$p_x$"]): 88 | min_y = np.min(values["$p_x$"]) 89 | if max_y < np.max(values["$p_x$"]): 90 | max_y = np.max(values["$p_x$"]) 91 | 92 | # Give a little padding 93 | diff = 25 94 | min_x -= diff 95 | max_x += diff 96 | min_y -= diff 97 | max_y += diff 98 | 99 | # Get the aspect ratio of the map correct 100 | height = max_y - min_y 101 | width = max_x - min_x 102 | 103 | if width / height > ratio: 104 | diff = (width / ratio - height) / 2 105 | min_y -= diff 106 | max_y += diff 107 | else: 108 | diff = (height * ratio - width) / 2 109 | min_x -= diff 110 | max_x += diff 111 | 112 | x1, y1 = ~transform * (min_x, min_y) 113 | x2, y2 = ~transform * (max_x, max_y) 114 | final_map = destination[int(y2) : int(y1), int(x1) : int(x2)] 115 | extent = [0, max_x - min_x, 0, max_y - min_y] 116 | 117 | plt.imshow(final_map, extent=extent, cmap="grey", alpha=0.55) 118 | 119 | # dark_ones = [plot.WheelType.WHEEL_ROSE_INTR_SLIP.value, plot.WheelType.GT.value] 120 | lines = {} 121 | for name, values in results.items(): 122 | alpha = 1 # if name in dark_ones else 0.9 123 | lw = 1.25 # if name in dark_ones else 0.8 124 | (lines[name],) = ax.plot( 125 | [], 126 | [], 127 | label=name, 128 | c=colors[name], 129 | lw=lw, 130 | alpha=alpha, 131 | ) 132 | 133 | ax.set_aspect("equal") 134 | # ax.set_xlabel("East (m)") 135 | # ax.set_ylabel("North (m)") 136 | # ax.tick_params(axis="both", pad=-1) 137 | ax.set_xticks([]) 138 | ax.set_yticks([]) 139 | ax.grid(False) 140 | 141 | ob = plot.AnchoredHScaleBar( 142 | size=50, 143 | extent=0.02, 144 | label="50m", 145 | loc=1, 146 | frameon=True, 147 | ppad=1.75, 148 | sep=1, 149 | linekw=dict(color=colors["GT"], lw=0.6), 150 | framecolor=(0.6, 0.6, 0.6), 151 | # label_outline=0.75, 152 | ) 153 | ax.add_artist(ob) 154 | ax.legend(loc="lower right", ncol=1) 155 | 156 | fps = 30 157 | t = 5 158 | 159 | num_frames = fps * t 160 | N = len(results[plot.WheelType.GT.value]["$p_y$"]) 161 | show_every = N // num_frames 162 | loop = tqdm(total=num_frames, leave=False, desc="Animating") 163 | 164 | def update(frame): 165 | for name, values in results.items(): 166 | lines[name].set_data( 167 | values["$p_y$"][: show_every * frame + 1] - min_x, 168 | values["$p_x$"][: show_every * frame + 1] - min_y, 169 | ) 170 | loop.update(1) 171 | return lines.values() 172 | 173 | ani = animation.FuncAnimation( 174 | fig, 175 | update, 176 | frames=num_frames, 177 | blit=True, 178 | interval=1000 / fps, 179 | cache_frame_data=False, 180 | repeat=False, 181 | ) 182 | ani.save(f"figures/animations/{traj}.gif", dpi=300) 183 | 184 | 185 | if __name__ == "__main__": 186 | trajs = [p.stem for p in Path("/mnt/bags/best/").iterdir()] 187 | 188 | for t in trajs: 189 | try: 190 | print(t) 191 | animate(t) 192 | except Exception as _: 193 | print(f"Failed on {t}") 194 | continue 195 | -------------------------------------------------------------------------------- /figures/monte_carlo.py: -------------------------------------------------------------------------------- 1 | import matplotlib.pyplot as plt 2 | import pandas as pd 3 | import rose.plot as plot 4 | import seaborn as sns 5 | 6 | 7 | def plot_bars(file): 8 | colors = plot.setup_plot() 9 | tags_to_names = plot.tags_to_names() 10 | df = pd.read_pickle(f"figures/data/{file}.pkl") 11 | 12 | df["WheelFactor"] = df["WheelFactor"].replace(tags_to_names) 13 | 14 | variations = [ 15 | plot.WheelType.SVO.value, 16 | plot.WheelType.WHEEL.value, 17 | plot.WheelType.WHEEL_PLANAR.value, 18 | plot.WheelType.WHEEL_ROSE.value, 19 | plot.WheelType.WHEEL_ROSE_INTR_SLIP.value, 20 | ] 21 | df = df[df["WheelFactor"].isin(variations)] 22 | 23 | fig, ax = plt.subplots(1, 2, layout="constrained", figsize=(4.5, 2), dpi=147) 24 | sns.boxplot( 25 | df, 26 | hue="WheelFactor", 27 | y="ATEt", 28 | orient="v", 29 | ax=ax[0], 30 | hue_order=variations, 31 | legend=False, 32 | palette=colors, 33 | ) 34 | ax[0].set_title("ATEt $(m)$") 35 | ax[0].set_ylabel("") 36 | ax[0].tick_params(axis="y", pad=-2) 37 | ax[0].set_ylim(0, 10) 38 | 39 | sns.boxplot( 40 | df, 41 | hue="WheelFactor", 42 | y="ATEr", 43 | orient="v", 44 | ax=ax[1], 45 | hue_order=variations, 46 | legend="brief", 47 | palette=colors, 48 | ) 49 | ax[1].set_title("ATEr $(deg)$") 50 | ax[1].get_legend().remove() 51 | ax[1].set_ylabel("") 52 | ax[1].tick_params(axis="y", pad=-2) 53 | ax[1].set_ylim(0, 5) 54 | 55 | fig.legend(loc="lower center", ncol=3, bbox_to_anchor=(0.5, -0.23)) 56 | 57 | # plt.savefig(f"figures/{file}.png", bbox_inches="tight", dpi=300) 58 | plt.savefig(f"figures/{file}.pdf", bbox_inches="tight", dpi=300) 59 | # plt.show() 60 | 61 | 62 | if __name__ == "__main__": 63 | plot_bars("sim_monte_carlo_ideal") 64 | plot_bars("sim_monte_carlo_real") 65 | -------------------------------------------------------------------------------- /figures/readme.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/rpl-cmu/rose/556005669cb9f76b94669d0ad36361ef8978f4a6/figures/readme.gif -------------------------------------------------------------------------------- /figures/sabercat_results.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/rpl-cmu/rose/556005669cb9f76b94669d0ad36361ef8978f4a6/figures/sabercat_results.pdf -------------------------------------------------------------------------------- /figures/sabercat_results.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | from pathlib import Path 3 | 4 | import gtsam 5 | import matplotlib.pyplot as plt 6 | import numpy as np 7 | import pandas as pd 8 | import rose.jrl 9 | import rose.plot as plot 10 | import seaborn as sns 11 | from tabulate import tabulate 12 | 13 | 14 | def cbor(s): 15 | return s.endswith("cbor") 16 | 17 | 18 | np.set_printoptions(suppress=True, precision=4) 19 | 20 | 21 | def compute_traj_length(values: gtsam.Values): 22 | poses = gtsam.utilities.allPose3s(values) 23 | keys = sorted(list(poses.keys())) 24 | dist = 0 25 | x_prev = poses.atPose3(keys[0]) 26 | for k in keys[1:]: 27 | x_curr = poses.atPose3(k) 28 | dist += np.linalg.norm(x_curr.translation() - x_prev.translation()) 29 | x_prev = x_curr 30 | 31 | return dist 32 | 33 | 34 | if __name__ == "__main__": 35 | parser = argparse.ArgumentParser(description="Plot results of trajectory") 36 | parser.add_argument( 37 | "--align", 38 | action="store_true", 39 | help="Whether to align trajectories when computing error", 40 | ) 41 | parser.add_argument( 42 | "--show", action="store_true", help="Whether to display figure at end" 43 | ) 44 | parser.add_argument( 45 | "--filename", 46 | type=str, 47 | default="figures/sabercat_results.pdf", 48 | help="Where to save the resulting figure", 49 | ) 50 | args = parser.parse_args() 51 | 52 | # ------------------------- Load gt values ------------------------- # 53 | jrl_parser = rose.jrl.makeRoseParser() 54 | 55 | trajs = {} 56 | 57 | folders = [Path("./data") / p.stem for p in Path("/mnt/bags/best/").iterdir()] 58 | 59 | traj_files = [] 60 | for f in folders: 61 | traj_files.extend([p for p in f.iterdir() if p.suffix == ".jrr"]) 62 | 63 | # ------------------------- Load all trajectories ------------------------- # 64 | if traj_files: 65 | print("Loading Trajectories...", end="") 66 | for f in sorted(traj_files): 67 | try: 68 | if "mono" in str(f): 69 | continue 70 | 71 | results = jrl_parser.parseResults(str(f), cbor(f)) 72 | result_name = f.stem 73 | 74 | traj_name = f.parent.stem 75 | if traj_name not in trajs: 76 | trajs[traj_name] = {} 77 | 78 | trajs[traj_name][result_name] = results.robot_solutions["a"].values 79 | # print(f"\n\t{traj_name} - {result_name}...", end="") 80 | except Exception as _: 81 | print(f"\n\tFailed {f}", end="") 82 | 83 | for k, v in trajs.items(): 84 | trajs[k]["length"] = compute_traj_length(v["_gt"]) / 1000 85 | print("\tDone!\n") 86 | 87 | # ------------------------- Parse through to get the ones we want ------------------------- # 88 | 89 | out = [] 90 | for k, v in trajs.items(): 91 | out.append([k, v["length"]]) 92 | 93 | print("The following passed the minimum requirements:") 94 | out = sorted(out, key=lambda x: x[1]) 95 | print(tabulate(out, headers=["Trajectory", "Length"], tablefmt="github")) 96 | 97 | # ------------------------- Plot ------------------------- # 98 | print("Plotting ATE...") 99 | colors = plot.setup_plot() 100 | data = [] 101 | for traj_name, runs in trajs.items(): 102 | for name, values in runs.items(): 103 | if name in ["_gt", "length"]: 104 | continue 105 | 106 | if name == "_wheel": 107 | has_imu = False 108 | wheel_type = "wheel_only" 109 | else: 110 | sensors = name[2:].split(".") 111 | wheel_type = [n for n in sensors if "wheel" in n] 112 | wheel_type = "cam_only" if len(wheel_type) == 0 else wheel_type[0] 113 | if "planar_prior" in sensors: 114 | wheel_type += "_planar" 115 | has_imu = "imu" in sensors 116 | 117 | error = rose.jrl.computeATEPose3(runs["_gt"], values, align=args.align) 118 | 119 | data.append( 120 | [ 121 | traj_name, 122 | has_imu, 123 | wheel_type, 124 | error[0] / runs["length"], 125 | error[1] * 180 / np.pi, 126 | runs["length"], 127 | ] 128 | ) 129 | 130 | df = pd.DataFrame( 131 | data, 132 | columns=["Trajectory", "Uses IMU", "Wheel Type", "ATEt / km", "ATEr", "Length"], 133 | ) 134 | 135 | # Get rid of bad runs 136 | df = df[df["Wheel Type"] != "wheel_manifold"] 137 | df = df[df["Trajectory"] != "gps-denied-higher-res_2024-01-23-12-34-32"] 138 | 139 | # ------------------------- Plot ------------------------- # 140 | fig, ax = plt.subplots(1, 2, layout="constrained", figsize=(8, 2.5)) 141 | 142 | # W/O IMU 143 | alias = { 144 | "wheel_rose": plot.WheelType.WHEEL_ROSE.value, 145 | "wheel_intr_slip": plot.WheelType.WHEEL_ROSE_INTR_SLIP.value, 146 | "wheel_baseline": plot.WheelType.WHEEL_UNDER.value, 147 | "wheel_baseline_planar": plot.WheelType.WHEEL_PLANAR.value, 148 | "cam_only": plot.WheelType.SVO.value, 149 | "wheel_only": plot.WheelType.WHEEL.value, 150 | } 151 | df_no_imu = df[not df["Uses IMU"]].copy() 152 | df_no_imu["Wheel Type"] = df_no_imu["Wheel Type"].replace(alias) 153 | df_no_imu = df_no_imu[df_no_imu["Wheel Type"] != plot.WheelType.WHEEL_UNDER.value] 154 | df_no_imu["Wheel Type"] = pd.Categorical( 155 | df_no_imu["Wheel Type"], 156 | categories=[ 157 | plot.WheelType.SVO.value, 158 | plot.WheelType.WHEEL.value, 159 | plot.WheelType.WHEEL_PLANAR.value, 160 | plot.WheelType.WHEEL_ROSE.value, 161 | plot.WheelType.WHEEL_ROSE_INTR_SLIP.value, 162 | ], 163 | ordered=True, 164 | ) 165 | 166 | sns.swarmplot( 167 | df_no_imu, 168 | ax=ax[0], 169 | x="Wheel Type", 170 | y="ATEt / km", 171 | hue="Wheel Type", 172 | legend=False, 173 | size=4, 174 | palette=colors, 175 | ) 176 | 177 | sns.lineplot( 178 | df_no_imu, 179 | ax=ax[0], 180 | x="Wheel Type", 181 | y="ATEt / km", 182 | hue="Trajectory", 183 | legend=False, 184 | size=0.2, 185 | palette=["k"], 186 | alpha=0.2, 187 | ) 188 | ax[0].set_xlabel("") 189 | ax[0].set_title("Visual Wheel Odometry") 190 | ax[0].tick_params(axis="x", rotation=12, bottom=True) 191 | 192 | # With IMU 193 | alias = {k: v.replace("SVO", "SVIO") for k, v in alias.items()} 194 | df_with_imu = df[df["Uses IMU"]].copy() 195 | df_with_imu["Wheel Type"] = df_with_imu["Wheel Type"].replace(alias) 196 | df_with_imu = df_with_imu[ 197 | df_with_imu["Wheel Type"] != plot.WheelType.WHEEL.value.replace("SVO", "SVIO") 198 | ] 199 | df_with_imu["Wheel Type"] = pd.Categorical( 200 | df_with_imu["Wheel Type"], 201 | categories=[ 202 | plot.WheelType.SVO.value.replace("SVO", "SVIO"), 203 | plot.WheelType.WHEEL_UNDER.value.replace("SVO", "SVIO"), 204 | plot.WheelType.WHEEL_PLANAR.value.replace("SVO", "SVIO"), 205 | plot.WheelType.WHEEL_ROSE.value.replace("SVO", "SVIO"), 206 | plot.WheelType.WHEEL_ROSE_INTR_SLIP.value.replace("SVO", "SVIO"), 207 | ], 208 | ordered=True, 209 | ) 210 | 211 | sns.swarmplot( 212 | df_with_imu, 213 | ax=ax[1], 214 | x="Wheel Type", 215 | y="ATEt / km", 216 | hue="Wheel Type", 217 | legend=False, 218 | size=4, 219 | palette={k.replace("SVO", "SVIO"): v for k, v in colors.items()}, 220 | ) 221 | sns.lineplot( 222 | df_with_imu, 223 | ax=ax[1], 224 | x="Wheel Type", 225 | y="ATEt / km", 226 | hue="Trajectory", 227 | legend=False, 228 | size=0.2, 229 | palette=["k"], 230 | alpha=0.2, 231 | ) 232 | ax[1].set_xlabel("") 233 | ax[1].set_title("Visual Intertial Wheel Odometry") 234 | ax[1].tick_params(axis="x", rotation=12, bottom=True) 235 | ax[1].set_ylim([0, 200]) 236 | 237 | ax[0].set_ylim(ax[1].get_ylim()) 238 | 239 | # pivot = df_with_imu.pivot( 240 | # index="Trajectory", columns=["Wheel Type"], values="ATEt / km" 241 | # ) 242 | # print(pivot.to_markdown(tablefmt="github")) 243 | # print("\n\n\n") 244 | # print(pivot) 245 | 246 | if args.filename is not None: 247 | plt.savefig(args.filename, bbox_inches="tight", dpi=300) 248 | if args.show: 249 | plt.show() 250 | -------------------------------------------------------------------------------- /figures/sim.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/rpl-cmu/rose/556005669cb9f76b94669d0ad36361ef8978f4a6/figures/sim.pdf -------------------------------------------------------------------------------- /figures/sim.py: -------------------------------------------------------------------------------- 1 | from pathlib import Path 2 | 3 | import matplotlib.pyplot as plt 4 | import rose.jrl 5 | import rose.plot as plot 6 | from matplotlib.patches import ConnectionPatch, Rectangle 7 | 8 | 9 | # https://stackoverflow.com/a/73308476 10 | def indicate_inset(axin, axout, arrow_start=(0, 0), arrow_end=(0, 0)): 11 | (x0, x1), (y0, y1) = axin.get_xlim(), axin.get_ylim() 12 | width = x1 - x0 13 | height = y1 - y0 14 | 15 | rect = Rectangle( 16 | [x0, y0], 17 | width=width, 18 | height=height, 19 | transform=axout.transData, 20 | fc="none", 21 | ec="black", 22 | ) 23 | axout.add_patch(rect) 24 | 25 | conn = ConnectionPatch( 26 | xyA=arrow_start, 27 | coordsA=rect.get_transform(), 28 | xyB=arrow_end, 29 | coordsB=axin.transAxes, 30 | arrowstyle="->", 31 | ec="black", 32 | lw=0.75, 33 | ) 34 | fig.add_artist(conn) 35 | return rect, conn 36 | 37 | 38 | if __name__ == "__main__": 39 | # ------------------------- Load all data ------------------------- # 40 | tags_to_names = plot.tags_to_names() 41 | result_files = [p for p in Path("figures/data").glob("*.jrr")] 42 | jrl_parser = rose.jrl.makeRoseParser() 43 | 44 | results = {} 45 | for p in result_files: 46 | values = jrl_parser.parseResults(str(p), False).robot_solutions["a"].values 47 | name = tags_to_names.get(p.stem, None) 48 | results[name] = plot.load_full_state(values) 49 | 50 | # ------------------------- Plot data ------------------------- # 51 | colors = plot.setup_plot() 52 | # c = sns.color_palette("colorblind") 53 | names_states = [ 54 | r"$b$", 55 | r"$r_l$", 56 | r"$r_r$", 57 | r"$s_l$", 58 | r"$s_r$", 59 | ] 60 | unit_states = ["$m$", "$m$", "$m$", "$rad/s$", "$rad/s$"] 61 | names = [plot.WheelType.GT.value, plot.WheelType.WHEEL_ROSE_INTR_SLIP.value] 62 | 63 | fig = plt.figure(layout="constrained", figsize=(8, 1.5)) 64 | ax = [] 65 | ax.append(fig.add_subplot(161)) 66 | ax.append(fig.add_subplot(162)) 67 | ax.append(fig.add_subplot(163, sharey=ax[-1])) 68 | ax[-1].tick_params(labelleft=False) 69 | ax.append(fig.add_subplot(164)) 70 | ax.append(fig.add_subplot(165, sharey=ax[-1])) 71 | ax[-1].tick_params(labelleft=False) 72 | ax.append(fig.add_subplot(166)) 73 | 74 | # Plot all the main stuff 75 | for i, s in enumerate(names_states): 76 | ax[i].set_title(s + f" ({unit_states[i]})") 77 | ax[i].tick_params("y", pad=-2) 78 | ax[i].tick_params("x", pad=-2) 79 | ax[i].set_xticks([0, 250, 500]) 80 | for n in names: 81 | ax[i].plot(results[n][s], c=colors[n], alpha=0.75) 82 | 83 | # Plot the zoomed in stuff 84 | for n in names: 85 | ax[-1].plot(results[n][names_states[-1]], label=n, c=colors[n], alpha=0.75) 86 | 87 | # Make zoomed in figure 88 | ax[-1].set_xlim(286, 296) 89 | ax[-1].set_ylim(-1, 8) 90 | ax[-1].set_xticks([]) 91 | ax[-1].set_yticks([]) 92 | indicate_inset(ax[-1], ax[-2], arrow_start=(0.5, 0.5), arrow_end=(0.0, 0.5)) 93 | 94 | fig.legend( 95 | loc="lower center", 96 | bbox_to_anchor=(0.5, -0.2), 97 | fancybox=True, 98 | ncol=2, 99 | ) 100 | 101 | # enlarge figure to include everything 102 | plt.savefig("figures/sim.png", bbox_inches="tight", dpi=300) 103 | plt.savefig("figures/sim.pdf", bbox_inches="tight", dpi=300) 104 | # plt.show() 105 | -------------------------------------------------------------------------------- /figures/sim_monte_carlo_ideal.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/rpl-cmu/rose/556005669cb9f76b94669d0ad36361ef8978f4a6/figures/sim_monte_carlo_ideal.pdf -------------------------------------------------------------------------------- /figures/sim_monte_carlo_real.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/rpl-cmu/rose/556005669cb9f76b94669d0ad36361ef8978f4a6/figures/sim_monte_carlo_real.pdf -------------------------------------------------------------------------------- /figures/surface.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/rpl-cmu/rose/556005669cb9f76b94669d0ad36361ef8978f4a6/figures/surface.pdf -------------------------------------------------------------------------------- /figures/surface.py: -------------------------------------------------------------------------------- 1 | import gtsam 2 | import matplotlib.pyplot as plt 3 | import numpy as np 4 | import rose.plot 5 | import seaborn as sns 6 | from rose.dataset import Dataset2JRL, Sensor 7 | from rose.sim import SimParameters, Simulation 8 | 9 | np.set_printoptions(suppress=False, precision=3) 10 | 11 | 12 | def compute_traj_length(values: gtsam.Values): 13 | poses = gtsam.utilities.allPose3s(values) 14 | keys = sorted(list(poses.keys())) 15 | dist = 0 16 | x_prev = poses.atPose3(keys[0]) 17 | for k in keys[1:]: 18 | x_curr = poses.atPose3(k) 19 | dist += np.linalg.norm(x_curr.translation() - x_prev.translation()) 20 | x_prev = x_curr 21 | 22 | return dist 23 | 24 | 25 | if __name__ == "__main__": 26 | np.random.seed(0) 27 | params = SimParameters() 28 | 29 | params.time = 100 30 | params.num_feats = 50 31 | 32 | v = 2 33 | w = lambda t: np.cos(t * 1.5) # noqa: E731 34 | sim = Simulation(params, np.pi / 6, v=2) 35 | sim.run_all(w, v) 36 | 37 | dataset = Dataset2JRL(sim) 38 | dataset.add_factors(Sensor.PRIOR, use_gt_orien=True) 39 | gt = dataset.get_ground_truth() 40 | 41 | # ------------------------- Plot 3D Grid ------------------------- # 42 | c = rose.plot.setup_plot() 43 | state = rose.plot.load_full_state(gt, dataset.N, pandas=False) 44 | 45 | # Load data 46 | x = np.linspace(-5, state[:, 3].max() + 5) 47 | y = np.linspace(-5, state[:, 4].max() + 5) 48 | X, Y = np.meshgrid(x, y) 49 | p = np.column_stack((X.flatten(), Y.flatten(), np.zeros(X.size))) 50 | Z = -sim.M(p.T).reshape(X.shape) + sim.M([0, 0, 0]) 51 | 52 | minZ = Z.min() 53 | Z -= minZ 54 | 55 | print(state[:, 5].max() - state[:, 5].min()) 56 | 57 | # Setup figure 58 | fig, ax = plt.subplots( 59 | subplot_kw={"projection": "3d"}, 60 | figsize=(4, 2.7), 61 | dpi=300, 62 | ) 63 | 64 | ax.plot_surface( 65 | X, 66 | Y, 67 | Z, 68 | alpha=0.5, 69 | lw=0.01, 70 | cmap=sns.color_palette("crest", as_cmap=True), 71 | ) 72 | black = c[rose.plot.WheelType.GT.value] 73 | ax.plot(state[:, 3], state[:, 4], state[:, 5] - minZ, lw=3, c=black) 74 | 75 | # This changes the aspect ratio by changing the axis-box size (rather than just the limits) 76 | # We set x/y equal, then manually change the z aspect 77 | ax.set_aspect("equal", adjustable="box") 78 | aspect = ax.get_box_aspect() 79 | aspect[-1] *= 20 80 | ax.set_box_aspect(aspect) 81 | 82 | ax.set_zticks([0.0, 1.0, 2.0]) 83 | ax.set_yticks([0, 20, 40, 60, 80]) 84 | 85 | ax.tick_params(axis="x", pad=-2) 86 | ax.tick_params(axis="y", pad=-2) 87 | ax.tick_params(axis="z", pad=-2) 88 | 89 | fig.subplots_adjust(left=0.0, right=0.92, top=1.3, bottom=-0.25) 90 | 91 | plt.savefig("figures/surface.pdf", dpi=300) 92 | plt.savefig("figures/surface.png", dpi=300) 93 | # plt.show() 94 | -------------------------------------------------------------------------------- /figures/tukey.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/rpl-cmu/rose/556005669cb9f76b94669d0ad36361ef8978f4a6/figures/tukey.pdf -------------------------------------------------------------------------------- /figures/tukey.py: -------------------------------------------------------------------------------- 1 | import matplotlib.pyplot as plt 2 | import numpy as np 3 | import seaborn as sns 4 | from rose.plot import setup_plot 5 | 6 | c = setup_plot() 7 | c = sns.color_palette("colorblind") 8 | 9 | for i, ci in enumerate(c.as_hex()): 10 | print(f"\definecolor{{color{i}}}{{HTML}}{{{ci[1:]}}}") 11 | 12 | 13 | def tukey(r, c): 14 | if type(r) is np.ndarray: 15 | out = np.zeros_like(r) 16 | in_basin = np.abs(r) <= c 17 | out[~in_basin] = c**2 / 6 18 | out[in_basin] = (c**2 / 6) * (1 - (1 - (r[in_basin] / c) ** 2) ** 3) 19 | return out 20 | else: 21 | if np.abs(r) <= c: 22 | return (c**2 / 6) * (1 - (1 - (r / c) ** 2) ** 3) 23 | else: 24 | return c**2 / 6 25 | 26 | 27 | fig, ax = plt.subplots(1, 1, figsize=(3.5, 1.75), layout="constrained", dpi=300) 28 | c = 1.0 29 | xlim = [-(c**2) / 6 - 2 * c, c**2 / 6 + 2 * c] 30 | ylim = [-0.05 * (c**2) / 6, 1.1 * c**2 / 6] 31 | x = np.linspace(xlim[0], xlim[1], 100) 32 | y = tukey(x, c) 33 | 34 | sns.lineplot(x=x, y=y, ax=ax) 35 | ax.set_xlim(xlim) 36 | ax.set_ylim(ylim) 37 | 38 | plt.savefig("figures/tukey.pdf", dpi=300) 39 | -------------------------------------------------------------------------------- /python/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | include(CMakeMacros.txt) 2 | 3 | # ------------------------- Get pybind ------------------------- # 4 | find_package(pybind11 QUIET) 5 | if(NOT pybind11_FOUND) 6 | include(FetchContent) 7 | message(STATUS "Pulling pybind11 from git...") 8 | FetchContent_Declare( 9 | pybind11 10 | GIT_REPOSITORY https://github.com/pybind/pybind11.git 11 | GIT_TAG v2.10.4 12 | ) 13 | FetchContent_MakeAvailable(pybind11) 14 | endif() 15 | 16 | # ------------------------- Fix other targets ------------------------- # 17 | set_target_properties(rose PROPERTIES POSITION_INDEPENDENT_CODE TRUE) 18 | set_target_properties(experiments PROPERTIES POSITION_INDEPENDENT_CODE TRUE) 19 | 20 | # ------------------------- Setup python package ------------------------- # 21 | set(PYTHON_BUILD_DIRECTORY ${PROJECT_BINARY_DIR}/python) 22 | # TODO: README? 23 | configure_file(${PROJECT_SOURCE_DIR}/python/setup.py.in 24 | ${PYTHON_BUILD_DIRECTORY}/setup.py) 25 | create_symlinks("${CMAKE_CURRENT_SOURCE_DIR}/rose" "${PYTHON_BUILD_DIRECTORY}/rose") 26 | 27 | # ------------------------- Setup pybind target ------------------------- # 28 | pybind11_add_module(rose_python bindings.cpp) 29 | target_link_libraries(rose_python PUBLIC experiments) 30 | target_include_directories(rose_python PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include") 31 | 32 | set_target_properties(rose_python PROPERTIES 33 | INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib" 34 | INSTALL_RPATH_USE_LINK_PATH TRUE 35 | OUTPUT_NAME "rose_python" 36 | LIBRARY_OUTPUT_DIRECTORY "${PYTHON_BUILD_DIRECTORY}/rose" 37 | DEBUG_POSTFIX "" # Otherwise you will have a wrong name 38 | RELWITHDEBINFO_POSTFIX "" # Otherwise you will have a wrong name 39 | ) 40 | target_compile_features(rose_python PUBLIC cxx_std_17) 41 | 42 | # ------------------------- Setup Python install instructions ------------------------- # 43 | 44 | # Setup the install command. Simply delegates to pip (should work with environmets) 45 | find_package(Python COMPONENTS Interpreter Development REQUIRED) 46 | add_custom_target(python-install 47 | COMMAND ${Python_EXECUTABLE} -m pip install -e . 48 | DEPENDS rose_python 49 | WORKING_DIRECTORY ${JRL_PYTHON_BUILD_DIRECTORY}) 50 | 51 | # Setup uninstall command. This can also be done with pip 52 | add_custom_target(python-uninstall 53 | COMMAND pip uninstall rose 54 | WORKING_DIRECTORY ${JRL_PYTHON_BUILD_DIRECTORY}) -------------------------------------------------------------------------------- /python/CMakeMacros.txt: -------------------------------------------------------------------------------- 1 | # https://stackoverflow.com/questions/13959434/cmake-out-of-source-build-python-files 2 | function(create_symlinks source_folder dest_folder) 3 | if(${source_folder} STREQUAL ${dest_folder}) 4 | return() 5 | endif() 6 | 7 | file(GLOB files 8 | LIST_DIRECTORIES true 9 | RELATIVE "${source_folder}" 10 | "${source_folder}/*") 11 | foreach(path_file ${files}) 12 | get_filename_component(folder ${path_file} PATH) 13 | get_filename_component(ext ${path_file} EXT) 14 | set(ignored_ext ".tpl" ".h") 15 | list (FIND ignored_ext "${ext}" _index) 16 | if (${_index} GREATER -1) 17 | continue() 18 | endif () 19 | # Create REAL folder 20 | file(MAKE_DIRECTORY "${dest_folder}") 21 | 22 | # Delete symlink if it exists 23 | file(REMOVE "${dest_folder}/${path_file}") 24 | 25 | # Get OS dependent path to use in `execute_process` 26 | file(TO_NATIVE_PATH "${dest_folder}/${path_file}" link) 27 | file(TO_NATIVE_PATH "${source_folder}/${path_file}" target) 28 | 29 | # cmake-format: off 30 | if(UNIX) 31 | set(command ln -s ${target} ${link}) 32 | else() 33 | set(command cmd.exe /c mklink ${link} ${target}) 34 | endif() 35 | # cmake-format: on 36 | 37 | execute_process(COMMAND ${command} 38 | RESULT_VARIABLE result 39 | ERROR_VARIABLE output) 40 | 41 | if(NOT ${result} EQUAL 0) 42 | message( 43 | FATAL_ERROR 44 | "Could not create symbolic link for: ${target} --> ${output}") 45 | endif() 46 | 47 | endforeach(path_file) 48 | endfunction(create_symlinks) -------------------------------------------------------------------------------- /python/bindings.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | #include "JRL-custom.h" 11 | #include "JRL.h" 12 | #include "JRLFrontend.h" 13 | #include "MEstBackend.h" 14 | #include "rose/WheelBaseline.h" 15 | #include "rose/WheelRose.h" 16 | 17 | namespace py = pybind11; 18 | using namespace pybind11::literals; 19 | using namespace rose; 20 | 21 | // Holder type for pybind11 22 | PYBIND11_DECLARE_HOLDER_TYPE(TYPE_PLACEHOLDER_DONOTUSE, boost::shared_ptr); 23 | PYBIND11_DECLARE_HOLDER_TYPE(TYPE_PLACEHOLDER_DONOTUSE, std::shared_ptr); 24 | 25 | PYBIND11_MODULE(rose_python, m) { 26 | // Import gtsam to ensure that python has access to return types 27 | py::module gtsam = py::module::import("gtsam"); 28 | py::module jrl = py::module::import("jrl"); 29 | 30 | // ------------------------- Custom JRL bindings for the below ------------------------- // 31 | m.attr("IMUBiasTag") = py::str(jrl_rose::IMUBiasTag); 32 | m.attr("StereoPoint2Tag") = py::str(jrl_rose::StereoPoint2Tag); 33 | m.attr("StereoFactorPose3Point3Tag") = py::str(jrl_rose::StereoFactorPose3Point3Tag); 34 | m.attr("CombinedIMUTag") = py::str(jrl_rose::CombinedIMUTag); 35 | m.attr("PriorFactorIMUBiasTag") = py::str(jrl_rose::PriorFactorIMUBiasTag); 36 | 37 | m.def("computeATEPose2", 38 | py::overload_cast(&jrl_rose::computeATE), 39 | py::return_value_policy::copy, py::arg("ref"), py::arg("est"), py::arg("align") = true, 40 | py::arg("align_with_scale") = false); 41 | m.def("computeATEPose3", 42 | py::overload_cast(&jrl_rose::computeATE), 43 | py::return_value_policy::copy, py::arg("ref"), py::arg("est"), py::arg("align") = true, 44 | py::arg("align_with_scale") = false); 45 | 46 | m.attr("WheelRoseTag") = py::str(jrl_rose::WheelRoseTag); 47 | m.attr("WheelRoseSlipTag") = py::str(jrl_rose::WheelRoseSlipTag); 48 | m.attr("WheelRoseIntrTag") = py::str(jrl_rose::WheelRoseIntrTag); 49 | m.attr("WheelRoseIntrSlipTag") = py::str(jrl_rose::WheelRoseIntrSlipTag); 50 | m.attr("WheelBaselineTag") = py::str(jrl_rose::WheelBaselineTag); 51 | m.attr("PlanarPriorTag") = py::str(jrl_rose::PlanarPriorTag); 52 | m.attr("ZPriorTag") = py::str(jrl_rose::ZPriorTag); 53 | 54 | m.def("makeRoseParser", jrl_rose::makeRoseParser); 55 | m.def("makeRoseWriter", jrl_rose::makeRoseWriter); 56 | 57 | // ------------------------- Frontend ------------------------- // 58 | py::class_>(m, "JRLFrontend") 59 | .def(py::init>(), "backend"_a) 60 | .def("run", &JRLFrontend::run); 61 | m.def( 62 | "makeFrontend", 63 | [](int kf = 5, int rf = 0, float spacing = 0) { 64 | boost::shared_ptr backend = 65 | boost::make_shared(gtsam::noiseModel::mEstimator::GemanMcClure::Create(3), "gm"); 66 | ; 67 | backend->setKeyframeNum(kf); 68 | backend->setRegframeNum(rf); 69 | backend->setKeyframeSpace(spacing); 70 | return JRLFrontend(backend); 71 | }, 72 | "kf"_a = 5, "rf"_a = 0, "spacing"_a = 0); 73 | 74 | // ------------------------- WheelFactors Bases ------------------------- // 75 | py::class_>(m, "PreintegratedWheelParams") 76 | .def(py::init<>()) 77 | .def_readwrite("wxCov", &PreintegratedWheelParams::wxCov) 78 | .def_readwrite("wyCov", &PreintegratedWheelParams::wyCov) 79 | .def_readwrite("vyCov", &PreintegratedWheelParams::vyCov) 80 | .def_readwrite("vzCov", &PreintegratedWheelParams::vzCov) 81 | .def_readwrite("omegaVelCov", &PreintegratedWheelParams::omegaVelCov) 82 | .def_readwrite("intrinsics", &PreintegratedWheelParams::intrinsics) 83 | .def_readwrite("intrinsicsBetweenCov", &PreintegratedWheelParams::intrinsicsBetweenCov) 84 | .def_static("MakeShared", &PreintegratedWheelParams::MakeShared) 85 | .def("make2DCov", &PreintegratedWheelParams::make2DCov) 86 | .def("make3DCov", &PreintegratedWheelParams::make3DCov) 87 | .def("setWVCovFromWheel", &PreintegratedWheelParams::setWVCovFromWheel) 88 | .def("setWVCovFromWV", &PreintegratedWheelParams::setWVCovFromWV) 89 | .def("intrinsicsMat", &PreintegratedWheelParams::intrinsicsMat); 90 | 91 | py::class_>(m, "PreintegratedWheelBase") 92 | .def(py::init>(), "params"_a) 93 | .def("preint", &PreintegratedWheelBase::preint) 94 | .def("params", &PreintegratedWheelBase::params) 95 | .def("deltaTij", &PreintegratedWheelBase::deltaTij) 96 | .def("resetIntegration", &PreintegratedWheelBase::resetIntegration) 97 | .def("preintMeasCov", &PreintegratedWheelBase::preintMeasCov) 98 | .def("integrateMeasurements", &PreintegratedWheelBase::integrateMeasurements); 99 | 100 | py::class_>(m, "WheelFactor2") 101 | .def(py::init, gtsam::Pose3>(), "key1"_a, 102 | "key2"_a, "pwm"_a, "body_T_sensor"_a = gtsam::Pose3::Identity()) 103 | .def("pwm", &WheelFactor2::pwm) 104 | .def("predict", &WheelFactor2::predict); 105 | 106 | py::class_>(m, "WheelFactor3") 107 | .def(py::init, gtsam::Pose3>(), 108 | "key1"_a, "key2"_a, "key2"_a, "pwm"_a, "body_T_sensor"_a = gtsam::Pose3::Identity()) 109 | .def("pwm", &WheelFactor3::pwm) 110 | .def("predict", &WheelFactor3::predict); 111 | 112 | py::class_>(m, "WheelFactor4") 113 | .def(py::init, 114 | gtsam::Pose3>(), 115 | "x_i"_a, "i_i"_a, "x_j"_a, "i_j"_a, "pwm"_a, "body_T_sensor"_a = gtsam::Pose3::Identity()) 116 | .def("pwm", &WheelFactor4::pwm) 117 | .def("predict", &WheelFactor4::predict); 118 | 119 | py::class_>(m, "WheelFactor5") 120 | .def(py::init, gtsam::Pose3>(), 122 | "x_i"_a, "i_i"_a, "x_j"_a, "i_j"_a, "s"_a, "pwm"_a, "body_T_sensor"_a = gtsam::Pose3::Identity()) 123 | .def("pwm", &WheelFactor5::pwm) 124 | .def("predict", &WheelFactor5::predict); 125 | 126 | py::class_>(m, "PlanarPriorFactor") 127 | .def(py::init(), "key1"_a, "cov"_a, 128 | "body_T_sensor"_a = gtsam::Pose3::Identity()); 129 | 130 | py::class_>(m, "ZPriorFactor") 131 | .def(py::init(), "key1"_a, "cov"_a, 132 | "body_T_sensor"_a = gtsam::Pose3::Identity()); 133 | 134 | // ------------------------- PreintegratedWheel Implementations ------------------------- // 135 | py::class_, PreintegratedWheelBase>( 136 | m, "PreintegratedWheelBaseline") 137 | .def(py::init>(), "params"_a) 138 | .def(py::init(), "base"_a) 139 | .def("integrateVelocities", &PreintegratedWheelBaseline::integrateVelocities) 140 | .def( 141 | "predict", [](PreintegratedWheelBaseline *self, const gtsam::Pose3 &x1) { return self->predict(x1); }, 142 | "x1"_a) 143 | .def("copy", &PreintegratedWheelBaseline::copy); 144 | 145 | py::class_, PreintegratedWheelBase>( 146 | m, "PreintegratedWheelRose") 147 | .def(py::init>(), "params"_a) 148 | .def("integrateMeasurements", &PreintegratedWheelRose::integrateMeasurements) 149 | .def("preint_H_slip", &PreintegratedWheelRose::preint_H_slip) 150 | .def("preint_H_intr", &PreintegratedWheelRose::preint_H_intr) 151 | .def( 152 | "predict", [](PreintegratedWheelRose *self, const gtsam::Pose3 &x1) { return self->predict(x1); }, "x1"_a) 153 | .def("copy", &PreintegratedWheelRose::copy); 154 | } -------------------------------------------------------------------------------- /python/rose/__init__.py: -------------------------------------------------------------------------------- 1 | from .datasets.flat import FlatDataset 2 | from .datasets.grizzly import GrizzlyBag 3 | from .datasets.kaist import KaistDataset 4 | from .datasets.sabercat import SabercatBag 5 | from .rose_python import ( 6 | PlanarPriorFactor, 7 | PreintegratedWheelBaseline, 8 | PreintegratedWheelParams, 9 | PreintegratedWheelRose, 10 | WheelFactor2, 11 | WheelFactor3, 12 | WheelFactor4, 13 | WheelFactor5, 14 | ZPriorFactor, 15 | makeFrontend, 16 | ) 17 | 18 | __all__ = [ 19 | "FlatDataset", 20 | "GrizzlyBag", 21 | "KaistDataset", 22 | "SabercatBag", 23 | "PlanarPriorFactor", 24 | "PreintegratedWheelBaseline", 25 | "PreintegratedWheelParams", 26 | "PreintegratedWheelRose", 27 | "WheelFactor2", 28 | "WheelFactor3", 29 | "WheelFactor4", 30 | "WheelFactor5", 31 | "ZPriorFactor", 32 | "makeFrontend", 33 | ] 34 | -------------------------------------------------------------------------------- /python/rose/datasets/flat.py: -------------------------------------------------------------------------------- 1 | import functools 2 | from pathlib import Path 3 | 4 | import gtsam 5 | import numpy as np 6 | import yaml 7 | from rose.dataset import ( 8 | BaseData, 9 | BaseIntrinsics, 10 | BaseNoise, 11 | CameraData, 12 | CameraIntrinsics, 13 | CamNoise, 14 | Dataset, 15 | GTData, 16 | IMUData, 17 | IMUNoise, 18 | PriorNoise, 19 | Sensor, 20 | WheelData, 21 | WheelIntrinsics, 22 | WheelNoise, 23 | ) 24 | 25 | 26 | class FlatDataset(Dataset): 27 | def __init__(self, dir: Path) -> None: 28 | self.dir = dir 29 | self.name = dir.stem 30 | 31 | self.intrinsics_override = {} 32 | self.noise_override = {} 33 | self.extrinsics_override = {} 34 | 35 | def clear_cache(self): 36 | self.extrinsics.cache_clear() 37 | self.intrinsics.cache_clear() 38 | self.noise.cache_clear() 39 | self.data.cache_clear() 40 | 41 | def add_intrinsics(self, sensor: Sensor, intrinsics): 42 | self.intrinsics_override[sensor] = intrinsics 43 | self.intrinsics.cache_clear() 44 | 45 | def add_noise(self, sensor: Sensor, noise): 46 | self.noise_override[sensor] = noise 47 | self.noise.cache_clear() 48 | 49 | def add_extrinsics(self, sensor: Sensor, extrinsics): 50 | self.extrinsics_override[sensor] = extrinsics 51 | self.extrinsics.cache_clear() 52 | 53 | def loadyaml(self, file: Path) -> dict: 54 | with open(file, "r") as f: 55 | y = yaml.safe_load(f) 56 | return y 57 | 58 | @functools.cache 59 | def extrinsics(self, sensor: Sensor) -> gtsam.Pose3: 60 | if sensor in self.extrinsics_override: 61 | return self.extrinsics_override[sensor] 62 | 63 | d = self.dir / f"calibration/ext_{sensor.name.lower()}.txt" 64 | return gtsam.Pose3(np.loadtxt(d)) 65 | 66 | @functools.cache 67 | def intrinsics(self, sensor: Sensor) -> BaseIntrinsics: 68 | """ 69 | Load various vehicle sensor intrinsics 70 | """ 71 | if sensor in self.intrinsics_override: 72 | return self.intrinsics_override[sensor] 73 | 74 | d = self.dir / f"calibration/int_{sensor.name.lower()}.yaml" 75 | intrinsics = self.loadyaml(d) 76 | 77 | if sensor == Sensor.CAM: 78 | return CameraIntrinsics(**intrinsics) 79 | elif sensor == Sensor.WHEEL: 80 | return WheelIntrinsics(**intrinsics) 81 | 82 | return intrinsics 83 | 84 | @functools.cached_property 85 | def stamps(self): 86 | stamps = np.loadtxt(self.dir / "stamps.txt", dtype=np.int64) 87 | img_exists = np.logical_and( 88 | [(self.dir / f"left/{s}.png").exists() for s in stamps], 89 | [(self.dir / f"right/{s}.png").exists() for s in stamps], 90 | ) 91 | return stamps[img_exists] 92 | 93 | @functools.cache 94 | def data(self, sensor: Sensor) -> BaseData: 95 | d = self.dir / f"{sensor.name.lower()}.txt" 96 | 97 | if sensor == Sensor.IMU: 98 | t = np.loadtxt(d, usecols=0, dtype=np.int64) 99 | data = np.loadtxt(d, usecols=range(1, 7)) 100 | w = data[:, 0:3] 101 | a = data[:, 3:6] 102 | return IMUData(t=t, w=w, a=a, noise=self.noise(Sensor.IMU)) 103 | 104 | elif sensor == Sensor.CAM: 105 | stamps = self.stamps 106 | left = [self.dir / f"left/{str(s)}.png" for s in stamps] 107 | right = [self.dir / f"right/{str(s)}.png" for s in stamps] 108 | disp = [self.dir / f"disp/{str(s)}.png" for s in stamps] 109 | mask_file = self.dir / "mask.txt" 110 | if mask_file.exists(): 111 | mask = np.loadtxt(self.dir / "mask.txt", dtype=bool) 112 | else: 113 | mask = None 114 | return CameraData( 115 | t=stamps, 116 | left=left, 117 | right=right, 118 | disparity=disp, 119 | mask=mask, 120 | extrinsics=self.extrinsics(Sensor.CAM), 121 | intrinsics=self.intrinsics(Sensor.CAM), 122 | noise=self.noise(Sensor.CAM), 123 | ) 124 | 125 | elif sensor == Sensor.GT: 126 | t = np.loadtxt(d, usecols=0, dtype=np.int64) 127 | x = np.loadtxt(d, usecols=range(1, 13)).reshape((-1, 3, 4)) 128 | return GTData(t=t, x=x, extrinsics=self.extrinsics(Sensor.GT)) 129 | 130 | elif sensor == Sensor.WHEEL: 131 | t = np.loadtxt(d, usecols=0, dtype=np.int64) 132 | wl, wr = np.loadtxt(d, usecols=range(1, 3)).T 133 | 134 | return WheelData( 135 | t=t, 136 | wl=wl, 137 | wr=wr, 138 | extrinsics=self.extrinsics(Sensor.WHEEL), 139 | intrinsics=self.intrinsics(Sensor.WHEEL), 140 | noise=self.noise(Sensor.WHEEL), 141 | ) 142 | 143 | @functools.cache 144 | def noise(self, sensor: Sensor) -> BaseNoise: 145 | if sensor in self.noise_override: 146 | noise = self.noise_override[sensor].dict() 147 | else: 148 | d = self.dir / f"noise/{sensor.name.lower()}.yaml" 149 | noise = self.loadyaml(d) 150 | if sensor == Sensor.IMU: 151 | return IMUNoise(**noise) 152 | 153 | elif sensor == Sensor.CAM: 154 | return CamNoise(**noise) 155 | 156 | elif sensor == Sensor.WHEEL: 157 | return WheelNoise(**noise) 158 | 159 | elif sensor == Sensor.PRIOR: 160 | return PriorNoise(**noise) 161 | -------------------------------------------------------------------------------- /python/rose/datasets/kaist.py: -------------------------------------------------------------------------------- 1 | import functools 2 | from pathlib import Path 3 | from typing import Union 4 | 5 | import cv2 6 | import gtsam 7 | import numpy as np 8 | from rose.dataset import ( 9 | BaseIntrinsics, 10 | CameraData, 11 | CameraIntrinsics, 12 | CamNoise, 13 | Dataset, 14 | GTData, 15 | IMUData, 16 | IMUNoise, 17 | Sensor, 18 | WheelData, 19 | WheelIntrinsics, 20 | WheelNoise, 21 | ) 22 | from rose.rose_python import PreintegratedWheelParams 23 | 24 | # https://www.xsens.com/hubfs/Downloads/Leaflets/MTi-300.pdf 25 | SIGMA_A = 60 * (1 / 10**6) * (1 / 9.81) 26 | SIGMA_G = 0.01 * np.pi / 180 27 | # this is not correct parameter, but should be close 28 | SIGMA_BA = 15 * (1 / 10**6) * (1 / 9.81) 29 | # again not the correct parameter, but should be close 30 | SIGMA_BG = 10 * (np.pi / 180) * (1 / 3600) 31 | PREINT_COV = 1.0e-8 32 | PREINT_BIAS_COV = 1.0e-5 33 | 34 | SIGMA_PIXEL = 1 35 | 36 | 37 | class KaistDataset(Dataset): 38 | def __init__(self, dir: Path) -> None: 39 | self.dir = dir 40 | self.name = dir.stem 41 | 42 | self.noise_override = {} 43 | 44 | self.calibration_files = { 45 | Sensor.IMU: dir / "calibration/Vehicle2IMU.txt", 46 | Sensor.CAM: dir / "calibration/Vehicle2Stereo.txt", 47 | # Wheel & GT data is at origin of vehicle (See openVINS) 48 | Sensor.GT: None, 49 | Sensor.WHEEL: None, 50 | } 51 | 52 | self.intrinsics_file = { 53 | Sensor.CAM: { 54 | "l": dir / "calibration/left.yaml", 55 | "r": dir / "calibration/right.yaml", 56 | }, 57 | Sensor.WHEEL: dir / "calibration/EncoderParameter.txt", 58 | } 59 | 60 | self.stamp_file = dir / "sensor_data/stereo_stamp.csv" 61 | self.data_files = { 62 | Sensor.IMU: dir / "sensor_data/xsens_imu.csv", 63 | Sensor.CAM: { 64 | "l": dir / "image/stereo_left/", 65 | "r": dir / "image/stereo_right/", 66 | "d": dir / "image/stereo_disp/", 67 | }, 68 | Sensor.GT: dir / "global_pose.csv", 69 | Sensor.WHEEL: dir / "sensor_data/encoder.csv", 70 | } 71 | 72 | def add_noise(self, sensor: Sensor, noise): 73 | self.noise_override[sensor] = noise 74 | self.noise.cache_clear() 75 | 76 | @functools.cache 77 | def _calfile2pose(self, sensor: Sensor) -> gtsam.Pose3: 78 | """ 79 | Load various vehicle sensor extrinsics 80 | """ 81 | cal_file = self.calibration_files[sensor] 82 | if cal_file is None: 83 | return gtsam.Pose3.Identity() 84 | 85 | with open(cal_file, "r") as f: 86 | lines = f.readlines() 87 | 88 | R = np.array([float(i) for i in lines[3].split()[1:]]).reshape((3, 3)) 89 | t = np.array([float(i) for i in lines[4].split()[1:]]) 90 | return gtsam.Pose3(gtsam.Rot3(R), t) 91 | 92 | @functools.cache 93 | def extrinsics(self, sensor: Sensor) -> gtsam.Pose3: 94 | vc_T_imu = self._calfile2pose(Sensor.IMU) 95 | vc_T_sens = self._calfile2pose(sensor) 96 | 97 | imu_T_sens = vc_T_imu.inverse() * vc_T_sens 98 | 99 | # If it's a camera pose, we also want to add rectification rotation on 100 | if sensor == Sensor.CAM: 101 | left = cv2.FileStorage( 102 | str(self.intrinsics_file[sensor]["l"]), cv2.FILE_STORAGE_READ 103 | ) 104 | # after_R_before rectification 105 | a_R_b = left.getNode("rectification_matrix").mat() 106 | b_T_a = gtsam.Pose3(gtsam.Rot3(a_R_b).inverse(), [0, 0, 0]) 107 | imu_T_sens = imu_T_sens * b_T_a 108 | 109 | return imu_T_sens 110 | 111 | @functools.cache 112 | def intrinsics(self, sensor: Sensor) -> BaseIntrinsics: 113 | """ 114 | Load various vehicle sensor intrinsics 115 | """ 116 | if sensor not in self.intrinsics_file: 117 | raise ValueError("Intrinsics not defined for this sensor") 118 | 119 | if sensor == Sensor.CAM: 120 | left = cv2.FileStorage( 121 | str(self.intrinsics_file[sensor]["l"]), cv2.FILE_STORAGE_READ 122 | ) 123 | right = cv2.FileStorage( 124 | str(self.intrinsics_file[sensor]["r"]), cv2.FILE_STORAGE_READ 125 | ) 126 | w = int(left.getNode("image_width").real()) 127 | h = int(left.getNode("image_height").real()) 128 | K_l = left.getNode("camera_matrix").mat() 129 | K_r = right.getNode("camera_matrix").mat() 130 | R_l = left.getNode("rectification_matrix").mat() 131 | R_r = right.getNode("rectification_matrix").mat() 132 | P_l = left.getNode("projection_matrix").mat() 133 | P_r = right.getNode("projection_matrix").mat() 134 | dist_l = left.getNode("distortion_coefficients").mat() 135 | dist_r = right.getNode("distortion_coefficients").mat() 136 | 137 | mapx_l, mapy_l = cv2.initUndistortRectifyMap( 138 | K_l, dist_l, R_l, P_l, (w, h), 5 139 | ) 140 | mapx_r, mapy_r = cv2.initUndistortRectifyMap( 141 | K_r, dist_r, R_r, P_r, (w, h), 5 142 | ) 143 | 144 | baseline = -P_r[0, 3] / P_r[1, 1] 145 | return CameraIntrinsics( 146 | fx=float(P_r[0, 0]), 147 | fy=float(P_r[1, 1]), 148 | cx=float(P_r[0, 2]), 149 | cy=float(P_r[1, 2]), 150 | baseline=float(baseline), 151 | mapx_l=mapx_l, 152 | mapy_l=mapy_l, 153 | mapx_r=mapx_r, 154 | mapy_r=mapy_r, 155 | ) 156 | 157 | elif sensor == Sensor.WHEEL: 158 | with open(self.intrinsics_file[sensor], "r") as f: 159 | lines = f.readlines() 160 | self.wheel_resolution = int(lines[1].split()[-1]) 161 | radius_l = float(lines[2].split()[-1]) / 2 162 | radius_r = float(lines[3].split()[-1]) / 2 163 | baseline = float(lines[4].split()[-1]) 164 | return WheelIntrinsics( 165 | baseline=baseline, 166 | radius_l=radius_l, 167 | radius_r=radius_r, 168 | ) 169 | 170 | @functools.cached_property 171 | def stamps(self): 172 | stamps = np.loadtxt(self.stamp_file, dtype=np.int64) 173 | dirs = self.data_files[Sensor.CAM] 174 | img_exists = np.logical_and( 175 | [(dirs["l"] / f"{s}.png").exists() for s in stamps], 176 | [(dirs["r"] / f"{s}.png").exists() for s in stamps], 177 | ) 178 | return stamps[img_exists] 179 | 180 | @functools.cache 181 | def data(self, sensor: Sensor) -> Union[IMUData, CameraData, GTData, WheelData]: 182 | if sensor == Sensor.IMU: 183 | t = np.loadtxt( 184 | self.data_files[sensor], delimiter=",", usecols=0, dtype=np.int64 185 | ) 186 | data = np.loadtxt( 187 | self.data_files[sensor], delimiter=",", usecols=range(8, 14) 188 | ) 189 | w = data[:, 0:3] 190 | a = data[:, 3:6] 191 | return IMUData(t=t, w=w, a=a, noise=self.noise(Sensor.IMU)) 192 | 193 | elif sensor == Sensor.CAM: 194 | dirs = self.data_files[sensor] 195 | stamps = self.stamps 196 | left = [dirs["l"] / f"{s}.png" for s in stamps] 197 | right = [dirs["r"] / f"{s}.png" for s in stamps] 198 | disp = [dirs["d"] / f"{s}.png" for s in stamps] 199 | return CameraData( 200 | t=stamps, 201 | left=left, 202 | right=right, 203 | disparity=disp, 204 | extrinsics=self.extrinsics(Sensor.CAM), 205 | intrinsics=self.intrinsics(Sensor.CAM), 206 | noise=self.noise(Sensor.CAM), 207 | ) 208 | 209 | elif sensor == Sensor.GT: 210 | t = np.loadtxt( 211 | self.data_files[sensor], delimiter=",", usecols=0, dtype=np.int64 212 | ) 213 | x = np.loadtxt( 214 | self.data_files[sensor], delimiter=",", usecols=range(1, 13) 215 | ).reshape((-1, 3, 4)) 216 | 217 | return GTData(t=t, x=x, extrinsics=self.extrinsics(Sensor.GT)) 218 | 219 | elif sensor == Sensor.WHEEL: 220 | # Load wheel resolution 221 | self.intrinsics(Sensor.WHEEL) 222 | 223 | t = np.loadtxt( 224 | self.data_files[sensor], delimiter=",", usecols=0, dtype=np.int64 225 | ) 226 | data = np.loadtxt( 227 | self.data_files[sensor], 228 | delimiter=",", 229 | usecols=range(1, 3), 230 | dtype=np.int64, 231 | ) 232 | 233 | # convert encoders into velocities 234 | dt = np.diff(t).astype(np.float32) / 1e9 235 | rps_r = np.diff(data[:, 1]).astype(np.float32) / self.wheel_resolution / dt 236 | rps_l = np.diff(data[:, 0]).astype(np.float32) / self.wheel_resolution / dt 237 | 238 | w_l = 2 * np.pi * rps_l 239 | w_r = 2 * np.pi * rps_r 240 | 241 | return WheelData( 242 | t=t[1:], 243 | wl=w_l, 244 | wr=w_r, 245 | extrinsics=self.extrinsics(Sensor.WHEEL), 246 | intrinsics=self.intrinsics(Sensor.WHEEL), 247 | noise=self.noise(Sensor.WHEEL), 248 | ) 249 | 250 | @functools.cache 251 | def noise( 252 | self, sensor: Sensor 253 | ) -> Union[ 254 | gtsam.PreintegratedCombinedMeasurements, 255 | gtsam.noiseModel.Base, 256 | PreintegratedWheelParams, 257 | ]: 258 | if sensor == Sensor.IMU: 259 | return IMUNoise( 260 | sigma_a=SIGMA_A, 261 | sigma_w=SIGMA_G, 262 | sigma_ba=SIGMA_BA, 263 | sigma_bw=SIGMA_BG, 264 | preint_cov=PREINT_COV, 265 | preint_bias_cov=PREINT_BIAS_COV, 266 | ) 267 | 268 | elif sensor == Sensor.CAM: 269 | return CamNoise(sig_pix=SIGMA_PIXEL) 270 | 271 | elif sensor == Sensor.WHEEL: 272 | wheel_noise = self.noise_override.get( 273 | Sensor.WHEEL, WheelNoise(sigma_rad_s=25) 274 | ) 275 | # Convert raw encoder sigma to continuous time sigma 276 | # enc -> wheel % -> radians -> radians / second -> (radians / second) (1 / \sqrt{Hz}) 277 | wheel_noise.sigma_rad_s = ( 278 | (wheel_noise.sigma_rad_s / self.wheel_resolution) 279 | * (2 * np.pi) 280 | / (1 / 100) 281 | / np.sqrt(100) 282 | ) 283 | return wheel_noise 284 | -------------------------------------------------------------------------------- /python/rose/jrl.py: -------------------------------------------------------------------------------- 1 | import gtsam 2 | import jrl 3 | 4 | # ------------------------- Helpers for Wrapping GTSAM containers ------------------------- # 5 | from rose.rose_python import ( 6 | IMUBiasTag, 7 | StereoPoint2Tag, 8 | StereoFactorPose3Point3Tag, 9 | CombinedIMUTag, 10 | PriorFactorIMUBiasTag, 11 | WheelRoseTag, 12 | WheelRoseSlipTag, 13 | WheelRoseIntrTag, 14 | WheelRoseIntrSlipTag, 15 | WheelBaselineTag, 16 | PlanarPriorTag, 17 | ZPriorTag, 18 | makeRoseParser, 19 | makeRoseWriter, 20 | computeATEPose3, 21 | computeATEPose2, 22 | ) 23 | 24 | 25 | def values2results( 26 | values: gtsam.Values, name: str = "", dataset: str = "" 27 | ) -> jrl.Results: 28 | type_values = values2typedvalues(values) 29 | return jrl.Results(dataset, name, ["a"], {"a": type_values}) 30 | 31 | 32 | def values2typedvalues(values: gtsam.Values) -> jrl.TypedValues: 33 | types = {} 34 | for k in values.keys(): 35 | char = chr(gtsam.Symbol(k).chr()) 36 | if char in ["x", "w"]: 37 | types[k] = jrl.Pose3Tag 38 | elif char in ["l", "v", "i"]: 39 | types[k] = jrl.Point3Tag 40 | elif char == "b": 41 | types[k] = IMUBiasTag 42 | elif char == "s": 43 | types[k] = jrl.Point2Tag 44 | else: 45 | raise ValueError(f"Unknown character {char} in values") 46 | 47 | return jrl.TypedValues(values, types) 48 | 49 | 50 | __all__ = [ 51 | "IMUBiasTag", 52 | "StereoPoint2Tag", 53 | "StereoFactorPose3Point3Tag", 54 | "CombinedIMUTag", 55 | "PriorFactorIMUBiasTag", 56 | "WheelRoseTag", 57 | "WheelRoseSlipTag", 58 | "WheelRoseIntrTag", 59 | "WheelRoseIntrSlipTag", 60 | "WheelBaselineTag", 61 | "PlanarPriorTag", 62 | "ZPriorTag", 63 | "makeRoseParser", 64 | "makeRoseWriter", 65 | "computeATEPose3", 66 | "computeATEPose2", 67 | ] 68 | -------------------------------------------------------------------------------- /python/rose/plot.py: -------------------------------------------------------------------------------- 1 | from enum import Enum 2 | 3 | import gtsam 4 | import jrl 5 | import matplotlib 6 | import matplotlib.patheffects as pe 7 | import matplotlib.pyplot as plt 8 | import numpy as np 9 | import pandas as pd 10 | import seaborn as sns 11 | from gtsam.symbol_shorthand import B, I, S, V, X 12 | from matplotlib.lines import Line2D 13 | from rose.jrl import WheelBaselineTag, WheelRoseIntrSlipTag, WheelRoseTag 14 | 15 | 16 | # https://stackoverflow.com/a/43343934 17 | class AnchoredHScaleBar(matplotlib.offsetbox.AnchoredOffsetbox): 18 | """size: length of bar in data units 19 | extent : height of bar ends in axes units""" 20 | 21 | def __init__( 22 | self, 23 | size=1, # number of units to show 24 | extent=0.03, # length of vertical bar 25 | label="", # label to insert 26 | loc=2, # which corner in should be on 27 | ax=None, # which axes 28 | pad=0.4, # not really sure tbh 29 | borderpad=0.5, # padding to outside edge 30 | ppad=0, # space between lines and outside of box 31 | sep=2, # distance between words and line 32 | prop=None, 33 | frameon=True, 34 | linekw={}, 35 | label_outline=0, 36 | framecolor="black", 37 | **kwargs, 38 | ): 39 | if not ax: 40 | ax = plt.gca() 41 | trans = ax.get_xaxis_transform() 42 | size_bar = matplotlib.offsetbox.AuxTransformBox(trans) 43 | line = Line2D([0, size], [0, 0], **linekw) 44 | vline1 = Line2D([0, 0], [-extent / 2.0, extent / 2.0], **linekw) 45 | vline2 = Line2D([size, size], [-extent / 2.0, extent / 2.0], **linekw) 46 | size_bar.add_artist(line) 47 | size_bar.add_artist(vline1) 48 | size_bar.add_artist(vline2) 49 | txt = matplotlib.offsetbox.TextArea( 50 | label, 51 | textprops={ 52 | "path_effects": [ 53 | pe.withStroke(linewidth=label_outline, foreground="white") 54 | ] 55 | }, 56 | ) 57 | self.vpac = matplotlib.offsetbox.VPacker( 58 | children=[size_bar, txt], align="center", pad=ppad, sep=sep 59 | ) 60 | matplotlib.offsetbox.AnchoredOffsetbox.__init__( 61 | self, 62 | loc, 63 | pad=pad, 64 | borderpad=borderpad, 65 | child=self.vpac, 66 | prop=prop, 67 | frameon=frameon, 68 | **kwargs, 69 | ) 70 | self.patch.set_edgecolor(framecolor) 71 | 72 | 73 | class WheelType(Enum): 74 | GT = "GT" 75 | SVO = "SVO" 76 | WHEEL = "WO" 77 | WHEEL_PLANAR = "SVO + Planar" 78 | WHEEL_UNDER = "SVO + Under" 79 | WHEEL_ROSE = "SVO + ROSE--" 80 | WHEEL_ROSE_INTR_SLIP = "SVO + ROSE" 81 | 82 | 83 | def tags_to_names(): 84 | return { 85 | "GT": WheelType.GT.value, 86 | "stereo": WheelType.SVO.value, 87 | "wheel": WheelType.WHEEL.value, 88 | WheelRoseTag: WheelType.WHEEL_ROSE.value, 89 | WheelRoseIntrSlipTag: WheelType.WHEEL_ROSE_INTR_SLIP.value, 90 | WheelBaselineTag: WheelType.WHEEL_PLANAR.value, 91 | "under": WheelType.WHEEL_UNDER.value, 92 | } 93 | 94 | 95 | def setup_plot(): 96 | matplotlib.rc("pdf", fonttype=42) 97 | sns.set_context("paper") 98 | sns.set_style("whitegrid") 99 | sns.set_palette("colorblind") 100 | c = sns.color_palette("colorblind") 101 | 102 | # Make sure you install times & clear matplotlib cache 103 | # https://stackoverflow.com/a/49884009 104 | plt.rcParams["font.family"] = "Times New Roman" 105 | plt.rcParams["mathtext.fontset"] = "stix" 106 | 107 | map_colors = { 108 | WheelType.GT.value: (0.2, 0.2, 0.2), 109 | WheelType.SVO.value: c[0], 110 | WheelType.WHEEL.value: c[1], 111 | WheelType.WHEEL_ROSE.value: c[2], 112 | WheelType.WHEEL_ROSE_INTR_SLIP.value: c[3], 113 | WheelType.WHEEL_PLANAR.value: c[4], 114 | WheelType.WHEEL_UNDER.value: c[-1], 115 | } 116 | return map_colors 117 | 118 | 119 | def load_state(values, idx, use_body_velocity=False, offset=gtsam.Pose3.Identity()): 120 | state = np.zeros(23) 121 | x = gtsam.Pose3.Identity() 122 | if values.exists(X(idx)): 123 | x = offset * values.atPose3(X(idx)) 124 | state[:3] = x.rotation().rpy() * 180 / np.pi 125 | state[3:6] = x.translation() 126 | if values.exists(V(idx)): 127 | v = values.atPoint3(V(idx)) 128 | if use_body_velocity: 129 | v = x.rotation().matrix().T @ v 130 | state[6:9] = v 131 | if values.exists(B(idx)): 132 | b = values.atConstantBias(B(idx)) 133 | state[9:15] = b.vector() 134 | if values.exists(S(idx)): 135 | s = values.atPoint2(S(idx)) 136 | state[18:20] = s 137 | if values.exists(I(idx)): 138 | i = values.atPoint3(I(idx)) 139 | state[20:23] = i 140 | return state 141 | 142 | 143 | def load_full_state(values, n=None, pandas=True, offset=gtsam.Pose3.Identity()): 144 | if n is None: 145 | n = max_pose(values) 146 | 147 | state = np.zeros((n, 23)) 148 | for i in range(n): 149 | state[i] = load_state(values, i, offset=offset) 150 | 151 | if pandas: 152 | columns = [ 153 | "roll (deg)", 154 | "pitch (deg)", 155 | "yaw (deg)", 156 | r"$p_x$", 157 | r"$p_y$", 158 | r"$p_z$", 159 | r"$v_x$", 160 | r"$v_y$", 161 | r"$v_z$", 162 | r"$b_{ax}$", 163 | r"$b_{ay}$", 164 | r"$b_{az}$", 165 | r"$b_{gx}$", 166 | r"$b_{gy}$", 167 | r"$b_{gz}$", 168 | r"$m_1$", 169 | r"$m_2$", 170 | r"$m_3$", 171 | r"$s_l$", 172 | r"$s_r$", 173 | r"$b$", 174 | r"$r_l$", 175 | r"$r_r$", 176 | ] 177 | df = pd.DataFrame(state, columns=columns) 178 | 179 | return df 180 | else: 181 | return state 182 | 183 | 184 | def max_pose(values): 185 | return ( 186 | max([gtsam.Symbol(k).index() for k in gtsam.utilities.allPose3s(values).keys()]) 187 | + 1 188 | ) 189 | 190 | 191 | def plot_3d_trajectory( 192 | figtitle=None, filename=None, show=False, align=False, **solutions 193 | ): 194 | import open3d as o3d 195 | 196 | # ------------------------- Plot in open3D ------------------------- # 197 | geo = [] 198 | for traj_idx, (name, values) in enumerate(solutions.items()): 199 | poses = gtsam.utilities.allPose3s(values) 200 | for k in poses.keys(): 201 | mesh = o3d.geometry.TriangleMesh.create_coordinate_frame() 202 | p = poses.atPose3(k) 203 | mesh.transform(p.matrix()) 204 | geo.append(mesh) 205 | 206 | o3d.visualization.draw_geometries(geo) 207 | 208 | 209 | def plot_xy_trajectory( 210 | figtitle=None, 211 | filename=None, 212 | show=False, 213 | align=False, 214 | N=None, 215 | states=None, 216 | **solutions, 217 | ): 218 | c = list(setup_plot().values()) 219 | 220 | fig, ax = plt.subplots( 221 | 2, 222 | 2, 223 | layout="constrained", 224 | figsize=(8, 6), 225 | dpi=147, 226 | gridspec_kw={"width_ratios": [2, 1], "height_ratios": [2, 1]}, 227 | ) 228 | ax = ax.T.flatten() 229 | 230 | if figtitle is not None: 231 | fig.suptitle(figtitle) 232 | 233 | # ------------------------- Plot lines ------------------------- # 234 | if N is None: 235 | N = min([max_pose(values) for name, values in solutions.items()]) 236 | 237 | for traj_idx, (name, values) in enumerate(solutions.items()): 238 | plot_values = ( 239 | jrl.alignPose3(gtsam.utilities.allPose3s(values), solutions["GT"], False) 240 | if align 241 | else values 242 | ) 243 | 244 | state = np.zeros((N, 23)) 245 | for i in range(N): 246 | state[i] = load_state(plot_values, i) 247 | 248 | c_idx = traj_idx % len(c) 249 | 250 | ax[0].plot(state[:, 3], state[:, 4], label=name, c=c[c_idx]) 251 | ax[1].plot(state[:, 3], state[:, 5], label=name, c=c[c_idx]) 252 | ax[2].plot(state[:, 5], state[:, 4], label=name, c=c[c_idx]) 253 | 254 | ax[0].legend() 255 | ax[0].set_xlabel("x") 256 | ax[0].set_ylabel("y") 257 | ax[0].set_aspect("equal", adjustable="box") 258 | 259 | ax[1].set_xlabel("x") 260 | ax[1].set_ylabel("z") 261 | ax[1].set_aspect("equal", adjustable="box") 262 | 263 | ax[2].set_xlabel("z") 264 | ax[2].set_ylabel("y") 265 | ax[2].invert_xaxis() 266 | ax[2].set_aspect("equal", adjustable="box") 267 | 268 | ax[3].axis("off") 269 | 270 | if filename is not None: 271 | plt.savefig(filename) 272 | if show: 273 | plt.show() 274 | 275 | return fig, ax 276 | 277 | 278 | def plot_error_state( 279 | figtitle=None, filename=None, show=False, align=False, **solutions 280 | ): 281 | c = list(setup_plot().values()) 282 | 283 | fig, ax = plt.subplots(3, 2, layout="constrained", figsize=(10, 5), dpi=147) 284 | ax = ax.T.flatten() 285 | names = [ 286 | "error - roll (deg)", 287 | "error - pitch (deg)", 288 | "error - yaw (deg)", 289 | r"error - $p_x$", 290 | r"error - $p_y$", 291 | r"error - $p_z$", 292 | ] 293 | for i in range(6): 294 | ax[i].set_title(names[i]) 295 | 296 | if figtitle is not None: 297 | fig.suptitle(figtitle) 298 | 299 | # ------------------------- Plot lines ------------------------- # 300 | N = min([max_pose(values) for name, values in solutions.items()]) 301 | 302 | # Find gt first 303 | gt = solutions["GT"] 304 | solutions.pop("GT") 305 | state_gt = np.zeros((N, 23)) 306 | for i in range(N): 307 | state_gt[i] = load_state(gt, i) 308 | 309 | for traj_idx, (name, values) in enumerate(solutions.items()): 310 | plot_values = ( 311 | jrl.alignPose3(values, solutions["GT"], False) if align else values 312 | ) 313 | 314 | state = np.zeros((N, 23)) 315 | for i in range(N): 316 | state[i] = load_state(plot_values, i) 317 | 318 | c_idx = traj_idx % len(c) 319 | for i in range(6): 320 | if i < 6 or not np.all(state[:, i] == 0): 321 | ax[i].plot(np.abs(state[:, i] - state_gt[:, i]), label=name, c=c[c_idx]) 322 | 323 | ax[0].legend() 324 | if filename is not None: 325 | plt.savefig(filename) 326 | if show: 327 | plt.show() 328 | 329 | return fig, ax 330 | 331 | 332 | def plot_state( 333 | figtitle=None, 334 | filename=None, 335 | show=False, 336 | align=False, 337 | states="rpv", 338 | N=None, 339 | **solutions, 340 | ): 341 | c = list(setup_plot().values()) 342 | 343 | names = [] 344 | if "r" in states: 345 | names.extend(["roll (deg)", "pitch (deg)", "yaw (deg)"]) 346 | if "p" in states: 347 | names.extend([r"$p_x$", r"$p_y$", r"$p_z$"]) 348 | if "v" in states: 349 | names.extend([r"$v_x$", r"$v_y$", r"$v_z$"]) 350 | if "b" in states: 351 | names.extend([r"$b_{ax}$", r"$b_{ay}$", r"$b_{az}$"]) 352 | names.extend([r"$b_{gx}$", r"$b_{gy}$", r"$b_{gz}$"]) 353 | if "m" in states: 354 | names.extend([r"$m_1$", r"$m_2$", r"$m_3$"]) 355 | if "i" in states: 356 | names.extend([r"$b$", r"$r_l$", r"$r_r$"]) 357 | if "s" in states: 358 | names.extend([r"$s_l$", r"$s_r$", ""]) 359 | 360 | always_show = ["roll (deg)", "pitch (deg)", "yaw (deg)"] 361 | 362 | n_states = len(names) 363 | fig, ax = plt.subplots( 364 | 3, n_states // 3, layout="constrained", figsize=(10, 5), dpi=147 365 | ) 366 | ax = ax.T.flatten() 367 | 368 | for i in range(n_states): 369 | ax[i].set_title(names[i]) 370 | 371 | if figtitle is not None: 372 | fig.suptitle(figtitle) 373 | 374 | # ------------------------- Plot lines ------------------------- # 375 | if N is None: 376 | N = min([max_pose(values) for name, values in solutions.items()]) 377 | 378 | for traj_idx, (name, values) in enumerate(solutions.items()): 379 | plot_values = ( 380 | jrl.alignPose3(values, solutions["GT"], False) if align else values 381 | ) 382 | 383 | state = load_full_state(plot_values, N) 384 | 385 | c_idx = traj_idx % len(c) 386 | zorder = 100 if name == "GT" else 0 387 | alpha = 0.75 if name == "GT" else 1 388 | for i, n in enumerate(names): 389 | if n in state and (not np.all(state[n][1:] == 0) or n in always_show): 390 | ax[i].plot(state[n], label=name, c=c[c_idx], zorder=zorder, alpha=alpha) 391 | 392 | for a in ax: 393 | a.ticklabel_format(useOffset=False) 394 | 395 | ax[0].legend().set_zorder(102) 396 | if filename is not None: 397 | plt.savefig(filename) 398 | if show: 399 | plt.show() 400 | 401 | return fig, ax 402 | -------------------------------------------------------------------------------- /python/setup.py.in: -------------------------------------------------------------------------------- 1 | """Setup file to install the rose package.""" 2 | 3 | try: 4 | from setuptools import setup, find_packages 5 | except ImportError: 6 | from distutils.core import setup, find_packages 7 | 8 | packages = find_packages(where=".") 9 | print("PACKAGES: ", packages) 10 | 11 | package_data = { 12 | '': [ 13 | "./*.so", 14 | "./*.dll", 15 | ] 16 | } 17 | 18 | setup( 19 | name='rose', 20 | version='0.0.1', 21 | description='Robust Off-road wheel odometry with Slip Estimation', 22 | author='Easton Potokar', 23 | author_email='epotokar@cmu.edu', 24 | keywords='slam sam robotics vio rose localization optimization', 25 | # https://pypi.org/pypi?%3Aaction=list_classifiers 26 | packages=packages, 27 | include_package_data=True, 28 | package_data=package_data, 29 | zip_safe=False, 30 | ) 31 | -------------------------------------------------------------------------------- /requirements.in: -------------------------------------------------------------------------------- 1 | # Not included: C++ builds of 2 | # gtsam 3 | # jrl 4 | 5 | numpy 6 | opencv 7 | pyyaml 8 | matplotlib 9 | tqdm 10 | yourdfpy 11 | pandas 12 | seaborn 13 | tabulate 14 | sympy 15 | pre-commit 16 | rasterio -------------------------------------------------------------------------------- /rose/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.11) 2 | 3 | # Create Library 4 | add_library(rose 5 | src/WheelBaseline.cpp 6 | src/WheelFactorBase.cpp 7 | src/WheelRose.cpp 8 | ) 9 | 10 | # Set Library Properties 11 | target_include_directories(rose PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include") 12 | target_link_libraries(rose PUBLIC gtsam) -------------------------------------------------------------------------------- /rose/include/rose/PlanarPriorFactor.h: -------------------------------------------------------------------------------- 1 | /* ---------------------------------------------------------------------------- 2 | 3 | Modified from PlanarPriorFactor from gtsam 4 | 5 | * -------------------------------------------------------------------------- */ 6 | #pragma once 7 | 8 | #include 9 | #include 10 | 11 | #include 12 | 13 | namespace rose { 14 | 15 | /** 16 | * A class for a soft prior on any Value type 17 | * @ingroup SLAM 18 | */ 19 | class PlanarPriorFactor : public gtsam::NoiseModelFactor1 { 20 | 21 | public: 22 | typedef gtsam::Pose3 T; 23 | 24 | private: 25 | typedef NoiseModelFactor1 Base; 26 | gtsam::Pose3 body_T_sensor_; 27 | 28 | public: 29 | /// shorthand for a smart pointer to a factor 30 | typedef typename boost::shared_ptr shared_ptr; 31 | 32 | /// Typedef to this class 33 | typedef PlanarPriorFactor This; 34 | 35 | /** default constructor - only use for serialization */ 36 | PlanarPriorFactor() {} 37 | 38 | ~PlanarPriorFactor() override {} 39 | 40 | /** Constructor */ 41 | PlanarPriorFactor(gtsam::Key key, const gtsam::Matrix2 &covariance, 42 | gtsam::Pose3 body_T_sensor = gtsam::Pose3::Identity()) 43 | : Base(gtsam::noiseModel::Gaussian::Covariance(covariance), key), body_T_sensor_(body_T_sensor) {} 44 | 45 | /// @return a deep copy of this factor 46 | gtsam::NonlinearFactor::shared_ptr clone() const override { 47 | return boost::static_pointer_cast(gtsam::NonlinearFactor::shared_ptr(new This(*this))); 48 | } 49 | 50 | /** implement functions needed for Testable */ 51 | 52 | /** print */ 53 | void print(const std::string &s, 54 | const gtsam::KeyFormatter &keyFormatter = gtsam::DefaultKeyFormatter) const override { 55 | std::cout << s << "PlanarPriorFactor on " << keyFormatter(this->key()) << "\n"; 56 | if (this->noiseModel_) 57 | this->noiseModel_->print(" noise model: "); 58 | else 59 | std::cout << "no noise model" << std::endl; 60 | } 61 | 62 | /** equals */ 63 | bool equals(const gtsam::NonlinearFactor &expected, double tol = 1e-9) const override { 64 | const This *e = dynamic_cast(&expected); 65 | return e != nullptr && Base::equals(*e, tol) && 66 | gtsam::traits::Equals(body_T_sensor_, e->body_T_sensor_, tol); 67 | } 68 | 69 | /** implement functions needed to derive from Factor */ 70 | 71 | /** vector of errors */ 72 | gtsam::Vector evaluateError(const T &x, boost::optional H = boost::none) const override { 73 | // manifold equivalent of z-x -> Local(x,z) 74 | gtsam::Matrix H_comp, H_log; 75 | gtsam::Vector e = 76 | gtsam::Rot3::Logmap(x.rotation().compose(body_T_sensor_.rotation(), H_comp), H_log).segment<2>(0); 77 | 78 | if (H) { 79 | H->resize(2, 6); 80 | H->setZero(); 81 | H->block<2, 3>(0, 0) = (H_log * H_comp).block<2, 3>(0, 0); 82 | } 83 | 84 | return e; 85 | } 86 | 87 | const gtsam::Pose3 &body_T_sensor() const { return body_T_sensor_; } 88 | 89 | private: 90 | /** Serialization function */ 91 | friend class boost::serialization::access; 92 | template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { 93 | ar &boost::serialization::make_nvp("NoiseModelFactor1", boost::serialization::base_object(*this)); 94 | } 95 | }; 96 | 97 | } // namespace rose -------------------------------------------------------------------------------- /rose/include/rose/WheelBaseline.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "gtsam/base/numericalDerivative.h" 4 | #include "gtsam/base/types.h" 5 | #include "gtsam/geometry/Pose3.h" 6 | #include "gtsam/geometry/Rot2.h" 7 | #include "gtsam/linear/NoiseModel.h" 8 | #include "gtsam/navigation/NavState.h" 9 | #include "gtsam/nonlinear/NonlinearFactor.h" 10 | 11 | #include "jrl/IOMeasurements.h" 12 | #include "jrl/IOValues.h" 13 | 14 | #include "rose/WheelFactorBase.h" 15 | 16 | // ------------------------- Wheel Factors ------------------------- // 17 | 18 | namespace rose { 19 | 20 | class PreintegratedWheelBaseline : public PreintegratedWheelBase { 21 | public: 22 | typedef PreintegratedWheelBaseline This; 23 | typedef PreintegratedWheelBase Base; 24 | typedef typename boost::shared_ptr shared_ptr; 25 | 26 | PreintegratedWheelBaseline(const boost::shared_ptr &p); 27 | PreintegratedWheelBaseline(Base base); 28 | 29 | // This are inherited, overriden functions 30 | void integrateVelocities(double omega, double v, double dt) override; 31 | 32 | size_t dimension2() const override { return 3; } 33 | gtsam::Pose3 predict(const gtsam::Pose3 &x_i, boost::optional H1 = boost::none) const override; 34 | gtsam::Vector evaluateError(const gtsam::Pose3 &, const gtsam::Pose3 &, 35 | boost::optional H1 = boost::none, 36 | boost::optional H2 = boost::none) const override; 37 | 38 | // Additional functionality 39 | This::shared_ptr copy() { return boost::make_shared(*this); } 40 | 41 | GTSAM_MAKE_ALIGNED_OPERATOR_NEW 42 | }; 43 | 44 | } // namespace rose -------------------------------------------------------------------------------- /rose/include/rose/WheelFactorBase.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "gtsam/base/numericalDerivative.h" 4 | #include "gtsam/base/types.h" 5 | #include "gtsam/geometry/Pose3.h" 6 | #include "gtsam/geometry/Rot2.h" 7 | #include "gtsam/linear/NoiseModel.h" 8 | #include "gtsam/navigation/NavState.h" 9 | #include "gtsam/nonlinear/NonlinearFactor.h" 10 | 11 | // ------------------------- Preintegration Base ------------------------- // 12 | namespace rose { 13 | 14 | class NotImplemented : public std::logic_error { 15 | public: 16 | NotImplemented() : std::logic_error("Function not yet implemented"){}; 17 | }; 18 | 19 | struct PreintegratedWheelParams { 20 | double wxCov = 1; 21 | double wyCov = 1; 22 | double vyCov = 1; 23 | double vzCov = 1; 24 | 25 | gtsam::Matrix2 omegaVelCov = gtsam::I_2x2; 26 | 27 | // baseline, radiusL, radiusR 28 | gtsam::Vector3 intrinsics = gtsam::Vector3::Ones(); 29 | gtsam::Matrix3 intrinsicsBetweenCov = gtsam::Matrix3::Identity(); 30 | 31 | static boost::shared_ptr MakeShared() { 32 | return boost::shared_ptr(new PreintegratedWheelParams()); 33 | } 34 | 35 | gtsam::Matrix2 intrinsicsMat() { 36 | double baseline = intrinsics[0]; 37 | double radiusL = intrinsics[1]; 38 | double radiusR = intrinsics[2]; 39 | gtsam::Matrix2 wheel2body; 40 | wheel2body << -radiusL / baseline, radiusR / baseline, radiusL / 2, radiusR / 2; 41 | return wheel2body; 42 | } 43 | 44 | void setWVCovFromWheel(double wlCov, double wrCov) { 45 | gtsam::Matrix2 wheel2body = intrinsicsMat(); 46 | gtsam::Matrix2 wlwrCov; 47 | wlwrCov << wlCov, 0, 0, wrCov; 48 | omegaVelCov = wheel2body * wlwrCov * wheel2body.transpose(); 49 | } 50 | 51 | void setWVCovFromWV(double wCov, double vCov) { omegaVelCov << wCov, 0, 0, vCov; } 52 | 53 | gtsam::Matrix2 make2DCov() { return omegaVelCov; } 54 | 55 | gtsam::Matrix6 make3DCov() { 56 | gtsam::Matrix6 cov = gtsam::Matrix6::Zero(); 57 | cov(0, 0) = wxCov; 58 | cov(1, 1) = wyCov; 59 | cov.block<2, 2>(2, 2) = omegaVelCov; 60 | cov(4, 4) = vyCov; 61 | cov(5, 5) = vzCov; 62 | return cov; 63 | } 64 | }; 65 | 66 | class PreintegratedWheelBase { 67 | protected: 68 | boost::shared_ptr p_; 69 | gtsam::Vector6 preint_; 70 | Eigen::Matrix preintMeasCov_; 71 | double deltaTij_; 72 | 73 | public: 74 | typedef typename boost::shared_ptr shared_ptr; 75 | 76 | PreintegratedWheelBase(const boost::shared_ptr &p); 77 | PreintegratedWheelBase(gtsam::Vector6 preint, Eigen::Matrix preintMeasCov, double deltaTij); 78 | 79 | boost::shared_ptr params() const { return p_; } 80 | gtsam::Vector6 preint() const { return preint_; } 81 | double deltaTij() const { return deltaTij_; } 82 | virtual Eigen::Matrix preintMeasCov() const { return preintMeasCov_; } 83 | 84 | virtual void resetIntegration() { 85 | preint_.setZero(); 86 | preintMeasCov_.setZero(); 87 | deltaTij_ = 0; 88 | } 89 | 90 | // In Inherited Classes, implement any/all of these 91 | virtual void integrateMeasurements(double wl, double wr, double dt); 92 | virtual void integrateVelocities(double omega, double v, double dt) { throw NotImplemented(); } 93 | 94 | // Used in WheelFactor2 95 | virtual size_t dimension2() const { throw NotImplemented(); } 96 | virtual gtsam::Pose3 predict(const gtsam::Pose3 &, boost::optional H1 = boost::none) const { 97 | throw NotImplemented(); 98 | } 99 | virtual gtsam::Vector evaluateError(const gtsam::Pose3 &, const gtsam::Pose3 &, 100 | boost::optional = boost::none, 101 | boost::optional = boost::none) const { 102 | throw NotImplemented(); 103 | } 104 | 105 | // Used in WheelFactor3 w/ Slip 106 | virtual size_t dimension3() const { throw NotImplemented(); } 107 | virtual gtsam::Pose3 predict(const gtsam::Pose3 &, const gtsam::Vector2 &, 108 | boost::optional H1 = boost::none, 109 | boost::optional H2 = boost::none) const { 110 | throw NotImplemented(); 111 | } 112 | virtual gtsam::Vector evaluateError(const gtsam::Pose3 &, const gtsam::Vector2 &, const gtsam::Pose3 &, 113 | boost::optional = boost::none, 114 | boost::optional = boost::none, 115 | boost::optional = boost::none) const { 116 | throw NotImplemented(); 117 | } 118 | 119 | // Used in WheelFactor4 w/ Intrinsics 120 | virtual size_t dimension4() const { throw NotImplemented(); } 121 | virtual gtsam::Pose3 predict(const gtsam::Pose3 &, const gtsam::Vector3 &, 122 | boost::optional H1 = boost::none, 123 | boost::optional H2 = boost::none) const { 124 | throw NotImplemented(); 125 | } 126 | virtual gtsam::Vector evaluateError(const gtsam::Pose3 &, const gtsam::Vector3 &, const gtsam::Pose3 &, 127 | const gtsam::Vector3 &, boost::optional = boost::none, 128 | boost::optional = boost::none, 129 | boost::optional = boost::none, 130 | boost::optional = boost::none) const { 131 | throw NotImplemented(); 132 | } 133 | 134 | // Used in WheelFactor5 135 | virtual size_t dimension5() const { throw NotImplemented(); } 136 | virtual gtsam::Pose3 predict(const gtsam::Pose3 &, const gtsam::Vector3 &, const gtsam::Vector2 &, 137 | boost::optional H1 = boost::none, 138 | boost::optional H2 = boost::none, 139 | boost::optional H3 = boost::none) const { 140 | throw NotImplemented(); 141 | } 142 | virtual gtsam::Vector evaluateError(const gtsam::Pose3 &, const gtsam::Vector3 &, const gtsam::Pose3 &, 143 | const gtsam::Vector3 &, const gtsam::Vector2 &, 144 | boost::optional = boost::none, 145 | boost::optional = boost::none, 146 | boost::optional = boost::none, 147 | boost::optional = boost::none, 148 | boost::optional = boost::none) const { 149 | throw NotImplemented(); 150 | } 151 | 152 | GTSAM_MAKE_ALIGNED_OPERATOR_NEW 153 | }; 154 | 155 | // ------------------------- Factors ------------------------- // 156 | class WheelFactor2 : public gtsam::NoiseModelFactor2 { 157 | private: 158 | typedef WheelFactor2 This; 159 | typedef gtsam::NoiseModelFactor2 Base; 160 | 161 | PreintegratedWheelBase::shared_ptr pwm_; 162 | gtsam::Pose3 body_T_sensor_; 163 | 164 | public: 165 | // shorthand for a smart pointer to a factor 166 | typedef typename boost::shared_ptr shared_ptr; 167 | 168 | WheelFactor2(gtsam::Key key1, gtsam::Key key2, PreintegratedWheelBase::shared_ptr pwm, 169 | gtsam::Pose3 body_T_sensor = gtsam::Pose3::Identity()); 170 | 171 | gtsam::Vector evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Pose3 &pose_j, 172 | boost::optional H1 = boost::none, 173 | boost::optional H2 = boost::none) const override; 174 | 175 | void print(const std::string &s, 176 | const gtsam::KeyFormatter &keyFormatter = gtsam::DefaultKeyFormatter) const override; 177 | 178 | PreintegratedWheelBase::shared_ptr pwm() const { return pwm_; } 179 | gtsam::Pose3 body_T_sensor() const { return body_T_sensor_; } 180 | gtsam::Pose3 predict(const gtsam::Pose3 &) const; 181 | }; 182 | 183 | class WheelFactor3 : public gtsam::NoiseModelFactor3 { 184 | private: 185 | typedef WheelFactor3 This; 186 | typedef gtsam::NoiseModelFactor3 Base; 187 | 188 | PreintegratedWheelBase::shared_ptr pwm_; 189 | gtsam::Pose3 body_T_sensor_; 190 | 191 | public: 192 | // shorthand for a smart pointer to a factor 193 | typedef typename boost::shared_ptr shared_ptr; 194 | 195 | WheelFactor3(gtsam::Key key1, gtsam::Key key2, gtsam::Key key3, PreintegratedWheelBase::shared_ptr pwm, 196 | gtsam::Pose3 body_T_sensor = gtsam::Pose3::Identity()); 197 | 198 | gtsam::Vector evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Pose3 &pose_j, const gtsam::Vector2 &slip, 199 | boost::optional H1 = boost::none, 200 | boost::optional H2 = boost::none, 201 | boost::optional H3 = boost::none) const override; 202 | 203 | void print(const std::string &s, 204 | const gtsam::KeyFormatter &keyFormatter = gtsam::DefaultKeyFormatter) const override; 205 | 206 | PreintegratedWheelBase::shared_ptr pwm() const { return pwm_; } 207 | gtsam::Pose3 body_T_sensor() const { return body_T_sensor_; } 208 | gtsam::Pose3 predict(const gtsam::Pose3 &, const gtsam::Vector2 &) const; 209 | }; 210 | 211 | class WheelFactor4 : public gtsam::NoiseModelFactor4 { 212 | private: 213 | PreintegratedWheelBase::shared_ptr pwm_; 214 | gtsam::Pose3 body_T_sensor_; 215 | 216 | typedef WheelFactor4 This; 217 | typedef gtsam::NoiseModelFactor4 Base; 218 | 219 | public: 220 | // shorthand for a smart pointer to a factor 221 | typedef typename boost::shared_ptr shared_ptr; 222 | 223 | WheelFactor4(gtsam::Key pose_i, gtsam::Key intr_i, gtsam::Key pose_j, gtsam::Key intr_j, 224 | PreintegratedWheelBase::shared_ptr pwm, gtsam::Pose3 body_T_sensor = gtsam::Pose3::Identity()); 225 | 226 | gtsam::Vector evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Vector3 &intr_i, const gtsam::Pose3 &pose_j, 227 | const gtsam::Vector3 &intr_j, boost::optional H1 = boost::none, 228 | boost::optional H2 = boost::none, 229 | boost::optional H3 = boost::none, 230 | boost::optional H4 = boost::none) const override; 231 | 232 | void print(const std::string &s, 233 | const gtsam::KeyFormatter &keyFormatter = gtsam::DefaultKeyFormatter) const override; 234 | 235 | PreintegratedWheelBase::shared_ptr pwm() const { return pwm_; } 236 | gtsam::Pose3 body_T_sensor() const { return body_T_sensor_; } 237 | gtsam::Pose3 predict(const gtsam::Pose3 &, const gtsam::Vector3 &) const; 238 | }; 239 | 240 | class WheelFactor5 241 | : public gtsam::NoiseModelFactor5 { 242 | private: 243 | PreintegratedWheelBase::shared_ptr pwm_; 244 | gtsam::Pose3 body_T_sensor_; 245 | 246 | typedef WheelFactor5 This; 247 | typedef gtsam::NoiseModelFactor5 Base; 248 | 249 | public: 250 | // shorthand for a smart pointer to a factor 251 | typedef typename boost::shared_ptr shared_ptr; 252 | 253 | WheelFactor5(gtsam::Key pose_i, gtsam::Key intr_i, gtsam::Key pose_j, gtsam::Key intr_j, gtsam::Key slip, 254 | PreintegratedWheelBase::shared_ptr pwm, gtsam::Pose3 body_T_sensor = gtsam::Pose3::Identity()); 255 | 256 | gtsam::Vector evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Vector3 &intr_i, const gtsam::Pose3 &pose_j, 257 | const gtsam::Vector3 &intr_j, const gtsam::Vector2 &slip, 258 | boost::optional H1 = boost::none, 259 | boost::optional H2 = boost::none, 260 | boost::optional H3 = boost::none, 261 | boost::optional H4 = boost::none, 262 | boost::optional H5 = boost::none) const override; 263 | 264 | void print(const std::string &s, 265 | const gtsam::KeyFormatter &keyFormatter = gtsam::DefaultKeyFormatter) const override; 266 | 267 | PreintegratedWheelBase::shared_ptr pwm() const { return pwm_; } 268 | gtsam::Pose3 body_T_sensor() const { return body_T_sensor_; } 269 | gtsam::Pose3 predict(const gtsam::Pose3 &, const gtsam::Vector3 &, const gtsam::Vector2 &) const; 270 | }; 271 | 272 | } // namespace rose -------------------------------------------------------------------------------- /rose/include/rose/WheelRose.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "gtsam/base/numericalDerivative.h" 4 | #include "gtsam/base/types.h" 5 | #include "gtsam/geometry/Pose3.h" 6 | #include "gtsam/geometry/Rot2.h" 7 | #include "gtsam/linear/NoiseModel.h" 8 | #include "gtsam/navigation/NavState.h" 9 | #include "gtsam/nonlinear/NonlinearFactor.h" 10 | 11 | #include "rose/WheelFactorBase.h" 12 | 13 | namespace rose { 14 | // ------------------------- Wheel Factors ------------------------- // 15 | 16 | // TODO: Make equals functions for these classes 17 | class PreintegratedWheelRose : public PreintegratedWheelBase { 18 | protected: 19 | gtsam::Matrix62 H_slip_; 20 | gtsam::Matrix63 H_intr_; 21 | gtsam::Vector3 intr_est_; 22 | 23 | gtsam::Matrix2 intrinsicsMat() { 24 | double baseline = intr_est_[0]; 25 | double radiusL = intr_est_[1]; 26 | double radiusR = intr_est_[2]; 27 | gtsam::Matrix2 wheel2body; 28 | wheel2body << -radiusL / baseline, radiusR / baseline, radiusL / 2, radiusR / 2; 29 | return wheel2body; 30 | } 31 | 32 | public: 33 | typedef PreintegratedWheelRose This; 34 | typedef PreintegratedWheelBase Base; 35 | typedef typename boost::shared_ptr shared_ptr; 36 | 37 | PreintegratedWheelRose(const boost::shared_ptr &p); 38 | PreintegratedWheelRose(Base base, gtsam::Matrix62 H_slip, gtsam::Matrix63 H_intr, gtsam::Vector3 intr_est); 39 | 40 | // This are inherited, overriden functions 41 | void integrateMeasurements(double wl, double wr, double dt) override; 42 | void resetIntegration() override; 43 | 44 | size_t dimension2() const override { return 6; } 45 | gtsam::Pose3 predict(const gtsam::Pose3 &x_i, boost::optional H1 = boost::none) const override; 46 | gtsam::Vector evaluateError(const gtsam::Pose3 &, const gtsam::Pose3 &, 47 | boost::optional H1 = boost::none, 48 | boost::optional H2 = boost::none) const override; 49 | 50 | size_t dimension3() const override { return 6; } 51 | gtsam::Pose3 predict(const gtsam::Pose3 &, const gtsam::Vector2 &, 52 | boost::optional H1 = boost::none, 53 | boost::optional H2 = boost::none) const override; 54 | gtsam::Vector evaluateError(const gtsam::Pose3 &, const gtsam::Vector2 &, const gtsam::Pose3 &, 55 | boost::optional = boost::none, 56 | boost::optional = boost::none, 57 | boost::optional = boost::none) const override; 58 | 59 | size_t dimension4() const override { return 9; } 60 | gtsam::Pose3 predict(const gtsam::Pose3 &, const gtsam::Vector3 &, 61 | boost::optional H1 = boost::none, 62 | boost::optional H2 = boost::none) const override; 63 | gtsam::Vector evaluateError(const gtsam::Pose3 &, const gtsam::Vector3 &, const gtsam::Pose3 &, 64 | const gtsam::Vector3 &, boost::optional = boost::none, 65 | boost::optional = boost::none, 66 | boost::optional = boost::none, 67 | boost::optional = boost::none) const override; 68 | 69 | size_t dimension5() const override { return 9; } 70 | gtsam::Pose3 predict(const gtsam::Pose3 &, const gtsam::Vector3 &, const gtsam::Vector2 &, 71 | boost::optional H1 = boost::none, 72 | boost::optional H2 = boost::none, 73 | boost::optional H3 = boost::none) const override; 74 | gtsam::Vector evaluateError(const gtsam::Pose3 &, const gtsam::Vector3 &, const gtsam::Pose3 &, 75 | const gtsam::Vector3 &, const gtsam::Vector2 &, 76 | boost::optional = boost::none, 77 | boost::optional = boost::none, 78 | boost::optional = boost::none, 79 | boost::optional = boost::none, 80 | boost::optional = boost::none) const override; 81 | 82 | gtsam::Matrix62 preint_H_slip() const { return H_slip_; } 83 | gtsam::Matrix63 preint_H_intr() const { return H_intr_; } 84 | gtsam::Vector3 intr_est() const { return intr_est_; } 85 | 86 | // Additional functionality 87 | This::shared_ptr copy() { return boost::make_shared(*this); } 88 | 89 | GTSAM_MAKE_ALIGNED_OPERATOR_NEW 90 | }; 91 | 92 | } // namespace rose -------------------------------------------------------------------------------- /rose/include/rose/ZPriorFactor.h: -------------------------------------------------------------------------------- 1 | /* ---------------------------------------------------------------------------- 2 | 3 | Modified from ZPriorFactor from gtsam 4 | 5 | * -------------------------------------------------------------------------- */ 6 | #pragma once 7 | 8 | #include 9 | #include 10 | 11 | #include 12 | 13 | namespace rose { 14 | /** 15 | * A class for a soft prior on any Value type 16 | * @ingroup SLAM 17 | */ 18 | class ZPriorFactor : public gtsam::NoiseModelFactor1 { 19 | 20 | public: 21 | typedef gtsam::Pose3 T; 22 | 23 | private: 24 | typedef NoiseModelFactor1 Base; 25 | gtsam::Pose3 body_T_sensor_; 26 | 27 | public: 28 | /// shorthand for a smart pointer to a factor 29 | typedef typename boost::shared_ptr shared_ptr; 30 | 31 | /// Typedef to this class 32 | typedef ZPriorFactor This; 33 | 34 | /** default constructor - only use for serialization */ 35 | ZPriorFactor() {} 36 | 37 | ~ZPriorFactor() override {} 38 | 39 | /** Constructor */ 40 | ZPriorFactor(gtsam::Key key, const gtsam::Matrix1 &covariance, 41 | gtsam::Pose3 body_T_sensor = gtsam::Pose3::Identity()) 42 | : Base(gtsam::noiseModel::Gaussian::Covariance(covariance), key), body_T_sensor_(body_T_sensor) {} 43 | 44 | /// @return a deep copy of this factor 45 | gtsam::NonlinearFactor::shared_ptr clone() const override { 46 | return boost::static_pointer_cast(gtsam::NonlinearFactor::shared_ptr(new This(*this))); 47 | } 48 | 49 | /** implement functions needed for Testable */ 50 | 51 | /** print */ 52 | void print(const std::string &s, 53 | const gtsam::KeyFormatter &keyFormatter = gtsam::DefaultKeyFormatter) const override { 54 | std::cout << s << "ZPriorFactor on " << keyFormatter(this->key()) << "\n"; 55 | if (this->noiseModel_) 56 | this->noiseModel_->print(" noise model: "); 57 | else 58 | std::cout << "no noise model" << std::endl; 59 | } 60 | 61 | /** equals */ 62 | bool equals(const gtsam::NonlinearFactor &expected, double tol = 1e-9) const override { 63 | const This *e = dynamic_cast(&expected); 64 | return e != nullptr && Base::equals(*e, tol) && 65 | gtsam::traits::Equals(body_T_sensor_, e->body_T_sensor_, tol); 66 | } 67 | 68 | /** implement functions needed to derive from Factor */ 69 | 70 | /** vector of errors */ 71 | gtsam::Vector evaluateError(const T &x, boost::optional H = boost::none) const override { 72 | gtsam::Matrix H_comp; 73 | gtsam::Pose3 x_sensor = x.compose(body_T_sensor_, H_comp); 74 | gtsam::Vector e = x_sensor.translation().tail<1>(); 75 | 76 | if (H) { 77 | gtsam::Matrix H_z; 78 | x_sensor.transformFrom(gtsam::Vector::Zero(3), H_z); 79 | 80 | H->resize(1, 6); 81 | H->setZero(); 82 | *H = H_z.block<1, 6>(2, 0) * H_comp; 83 | } 84 | 85 | return e; 86 | } 87 | 88 | const gtsam::Pose3 &body_T_sensor() const { return body_T_sensor_; } 89 | 90 | private: 91 | /** Serialization function */ 92 | friend class boost::serialization::access; 93 | template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { 94 | ar &boost::serialization::make_nvp("NoiseModelFactor1", boost::serialization::base_object(*this)); 95 | } 96 | }; 97 | 98 | } // namespace rose -------------------------------------------------------------------------------- /rose/src/WheelBaseline.cpp: -------------------------------------------------------------------------------- 1 | #include "rose/WheelBaseline.h" 2 | 3 | // ------------------------- Preintegrated Wheel Measurements ------------------------- // 4 | namespace rose { 5 | 6 | PreintegratedWheelBaseline::PreintegratedWheelBaseline(const boost::shared_ptr &p) : Base(p) { 7 | resetIntegration(); 8 | } 9 | 10 | PreintegratedWheelBaseline::PreintegratedWheelBaseline(Base base) : Base(base) {} 11 | 12 | void PreintegratedWheelBaseline::integrateVelocities(double w, double v, double dt) { 13 | // Find change in states 14 | double deltaTheta = w * dt; 15 | double deltaD = v * dt; 16 | double thetaCov_ = (p_->omegaVelCov(0, 0) / dt) * dt * dt; // -> discrete -> not rates 17 | double posCov_ = (p_->omegaVelCov(1, 1) / dt) * dt * dt; // -> discrete -> not rates 18 | 19 | gtsam::Vector2 deltaP; 20 | deltaP << deltaD * std::cos(deltaTheta / 2), deltaD * std::sin(deltaTheta / 2); 21 | 22 | // Preintegrate states 23 | gtsam::Rot2 deltaRik(preint_[0]); 24 | // Since preint is all in SE(2) can simply add thetas 25 | preint_[0] += deltaTheta; 26 | preint_.segment<2>(1) += deltaRik * deltaP; 27 | 28 | // Find all gradients for covariance propagation 29 | gtsam::Vector2 dPdd; 30 | dPdd << std::cos(deltaTheta / 2), std::sin(deltaTheta / 2); 31 | gtsam::Vector2 dPdTheta; 32 | dPdTheta << -deltaD * std::sin(deltaTheta / 2), deltaD * std::cos(deltaTheta / 2); 33 | gtsam::Vector2 Pcross; 34 | Pcross << deltaP[1], -deltaP[0]; 35 | 36 | // Update covariance 37 | preintMeasCov_.block<2, 2>(1, 1) += dPdd * dPdd.transpose() * posCov_ + 38 | dPdTheta * dPdTheta.transpose() * thetaCov_ + 39 | Pcross * Pcross.transpose() * preintMeasCov_(0, 0); 40 | preintMeasCov_(0, 0) += thetaCov_; 41 | 42 | // Handle degeneracy in case of no movement 43 | if (preintMeasCov_(2, 2) <= 1e-8) { 44 | preintMeasCov_(2, 2) = 1e-8; 45 | } 46 | 47 | deltaTij_ += dt; 48 | } 49 | 50 | // TODO: Implement Jacobians for WheelBaseline 51 | gtsam::Pose3 PreintegratedWheelBaseline::predict(const gtsam::Pose3 &x_i, boost::optional H1) const { 52 | gtsam::Pose3 delta(gtsam::Rot3::Rz(preint_[0]), gtsam::Vector3(preint_[1], preint_[2], 0)); 53 | return x_i.compose(delta, H1); 54 | } 55 | 56 | gtsam::Vector PreintegratedWheelBaseline::evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Pose3 &pose_j, 57 | boost::optional H1, 58 | boost::optional H2) const { 59 | gtsam::Matrix H1_comp, H2_comp, H_yaw, H_trans; 60 | gtsam::Pose3 measured = predict(gtsam::Pose3::Identity()); 61 | gtsam::Pose3 pose_ij = pose_i.between(pose_j, H1_comp, H2_comp); 62 | 63 | gtsam::Vector3 error; 64 | // yaw error 65 | error[0] = measured.localCoordinates(pose_ij, boost::none, H_yaw)[2]; 66 | // positional error 67 | error.tail<2>() = pose_ij.translation(H_trans).head<2>() - measured.translation().head<2>(); 68 | 69 | if (H1) { 70 | H1->resize(3, 6); 71 | H1->setZero(); 72 | H1->block<1, 6>(0, 0) = H_yaw.block<1, 6>(2, 0) * H1_comp; 73 | H1->block<2, 6>(1, 0) = H_trans.block<2, 6>(0, 0) * H1_comp; 74 | } 75 | 76 | if (H2) { 77 | H2->resize(3, 6); 78 | H2->setZero(); 79 | H2->block<1, 6>(0, 0) = H_yaw.block<1, 6>(2, 0) * H2_comp; 80 | H2->block<2, 6>(1, 0) = H_trans.block<2, 6>(0, 0) * H2_comp; 81 | } 82 | 83 | return error; 84 | } 85 | 86 | } // namespace rose -------------------------------------------------------------------------------- /rose/src/WheelFactorBase.cpp: -------------------------------------------------------------------------------- 1 | #include "rose/WheelFactorBase.h" 2 | 3 | namespace rose { 4 | 5 | // ------------------------- Preintegration Base ------------------------- // 6 | PreintegratedWheelBase::PreintegratedWheelBase(gtsam::Vector6 preint, Eigen::Matrix preintMeasCov, 7 | double deltaTij) 8 | : preint_(preint), preintMeasCov_(preintMeasCov), deltaTij_(deltaTij) {} 9 | 10 | PreintegratedWheelBase::PreintegratedWheelBase(const boost::shared_ptr &p) : p_(p) {} 11 | 12 | void PreintegratedWheelBase::integrateMeasurements(double wl, double wr, double dt) { 13 | double baseline = p_->intrinsics[0]; 14 | double radiusL = p_->intrinsics[1]; 15 | double radiusR = p_->intrinsics[2]; 16 | double w = (radiusR * wr - radiusL * wl) / baseline; 17 | double v = (radiusR * wr + radiusL * wl) / 2; 18 | integrateVelocities(w, v, dt); 19 | } 20 | 21 | // ------------------------- Factor between 2 poses ------------------------- // 22 | WheelFactor2::WheelFactor2(gtsam::Key key1, gtsam::Key key2, PreintegratedWheelBase::shared_ptr pwm, 23 | gtsam::Pose3 body_T_sensor) 24 | : pwm_(pwm), body_T_sensor_(body_T_sensor), Base(gtsam::noiseModel::Gaussian::Covariance(pwm->preintMeasCov().block( 25 | 0, 0, pwm->dimension2(), pwm->dimension2())), 26 | key1, key2) {} 27 | 28 | gtsam::Vector WheelFactor2::evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Pose3 &pose_j, 29 | boost::optional H1, 30 | boost::optional H2) const { 31 | 32 | if (H1) 33 | H1->setZero(); 34 | if (H2) 35 | H2->setZero(); 36 | gtsam::Matrix H1_comp, H2_comp; 37 | gtsam::Vector e = 38 | pwm_->evaluateError(pose_i.compose(body_T_sensor_, H1_comp), pose_j.compose(body_T_sensor_, H2_comp), H1, H2); 39 | 40 | // Combine with body_T_sensor composition 41 | if (H1) { 42 | *H1 *= H1_comp; 43 | } 44 | if (H2) { 45 | *H2 *= H2_comp; 46 | } 47 | 48 | return e; 49 | } 50 | 51 | gtsam::Pose3 WheelFactor2::predict(const gtsam::Pose3 &x_i) const { 52 | gtsam::Pose3 predict = pwm_->predict(x_i.compose(body_T_sensor_)); 53 | return predict * body_T_sensor_.inverse(); 54 | } 55 | 56 | void WheelFactor2::print(const std::string &s, const gtsam::KeyFormatter &keyFormatter) const { 57 | std::cout << s << "WheelFactor2(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n" 58 | << " measured: " << pwm_->preint().transpose() << "\n"; 59 | this->noiseModel_->print(" noise model: "); 60 | } 61 | 62 | // ------------------------- Factor between 2 poses & slip ------------------------- // 63 | WheelFactor3::WheelFactor3(gtsam::Key key1, gtsam::Key key2, gtsam::Key key3, PreintegratedWheelBase::shared_ptr pwm, 64 | gtsam::Pose3 body_T_sensor) 65 | : pwm_(pwm), body_T_sensor_(body_T_sensor), Base(gtsam::noiseModel::Gaussian::Covariance(pwm->preintMeasCov().block( 66 | 0, 0, pwm->dimension3(), pwm->dimension3())), 67 | key1, key2, key3) {} 68 | 69 | gtsam::Vector WheelFactor3::evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Pose3 &pose_j, 70 | const gtsam::Vector2 &slip, boost::optional H1, 71 | boost::optional H2, 72 | boost::optional H3) const { 73 | 74 | if (H1) 75 | H1->setZero(); 76 | if (H2) 77 | H2->setZero(); 78 | if (H3) 79 | H3->setZero(); 80 | gtsam::Matrix H1_comp, H2_comp; 81 | gtsam::Vector e = pwm_->evaluateError(pose_i.compose(body_T_sensor_, H1_comp), slip, 82 | pose_j.compose(body_T_sensor_, H2_comp), H1, H3, H2); 83 | 84 | // If we got Jacobians out 85 | // Combine with body_T_sensor_ composition 86 | if (H1) { 87 | *H1 *= H1_comp; 88 | } 89 | if (H2) { 90 | *H2 *= H2_comp; 91 | } 92 | 93 | return e; 94 | } 95 | 96 | gtsam::Pose3 WheelFactor3::predict(const gtsam::Pose3 &x_i, const gtsam::Vector2 &slip) const { 97 | gtsam::Pose3 predict = pwm_->predict(x_i.compose(body_T_sensor_), slip); 98 | return predict * body_T_sensor_.inverse(); 99 | } 100 | 101 | void WheelFactor3::print(const std::string &s, const gtsam::KeyFormatter &keyFormatter) const { 102 | std::cout << s << "WheelFactor3(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << "," 103 | << keyFormatter(this->key3()) << ")\n" 104 | << " measured: " << pwm_->preint().transpose() << "\n"; 105 | this->noiseModel_->print(" noise model: "); 106 | } 107 | 108 | // ------------------------- Factor between 2 poses / 2 intrinsics ------------------------- // 109 | WheelFactor4::WheelFactor4(gtsam::Key pose_i, gtsam::Key intr_i, gtsam::Key pose_j, gtsam::Key intr_j, 110 | PreintegratedWheelBase::shared_ptr pwm, gtsam::Pose3 body_T_sensor) 111 | : pwm_(pwm), body_T_sensor_(body_T_sensor), Base(gtsam::noiseModel::Gaussian::Covariance(pwm->preintMeasCov().block( 112 | 0, 0, pwm->dimension4(), pwm->dimension4())), 113 | pose_i, intr_i, pose_j, intr_j) {} 114 | 115 | gtsam::Vector WheelFactor4::evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Vector3 &intr_i, 116 | const gtsam::Pose3 &pose_j, const gtsam::Vector3 &intr_j, 117 | boost::optional H1, boost::optional H2, 118 | boost::optional H3, 119 | boost::optional H4) const { 120 | 121 | if (H1) 122 | H1->setZero(); 123 | if (H2) 124 | H2->setZero(); 125 | if (H3) 126 | H3->setZero(); 127 | if (H4) 128 | H4->setZero(); 129 | gtsam::Matrix H1_comp, H3_comp; 130 | gtsam::Vector e = pwm_->evaluateError(pose_i.compose(body_T_sensor_, H1_comp), intr_i, 131 | pose_j.compose(body_T_sensor_, H3_comp), intr_j, H1, H2, H3, H4); 132 | 133 | // If we got Jacobians out 134 | // Combine with body_T_sensor_ composition 135 | if (H1) { 136 | *H1 *= H1_comp; 137 | } 138 | if (H3) { 139 | *H3 *= H3_comp; 140 | } 141 | 142 | return e; 143 | } 144 | 145 | gtsam::Pose3 WheelFactor4::predict(const gtsam::Pose3 &x_i, const gtsam::Vector3 &intr) const { 146 | gtsam::Pose3 predict = pwm_->predict(x_i.compose(body_T_sensor_), intr); 147 | return predict * body_T_sensor_.inverse(); 148 | } 149 | 150 | void WheelFactor4::print(const std::string &s, const gtsam::KeyFormatter &keyFormatter) const { 151 | std::cout << s << "WheelFactor4(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << "," 152 | << keyFormatter(this->key3()) << "," << keyFormatter(this->key4()) << ")\n" 153 | << " measured: " << pwm_->preint().transpose() << "\n"; 154 | this->noiseModel_->print(" noise model: "); 155 | } 156 | 157 | // ------------------------- Factor between 2 poses / 2 intrinsics / slip ------------------------- // 158 | WheelFactor5::WheelFactor5(gtsam::Key pose_i, gtsam::Key intr_i, gtsam::Key pose_j, gtsam::Key intr_j, gtsam::Key slip, 159 | PreintegratedWheelBase::shared_ptr pwm, gtsam::Pose3 body_T_sensor) 160 | : pwm_(pwm), body_T_sensor_(body_T_sensor), Base(gtsam::noiseModel::Gaussian::Covariance(pwm->preintMeasCov().block( 161 | 0, 0, pwm->dimension4(), pwm->dimension5())), 162 | pose_i, intr_i, pose_j, intr_j, slip) {} 163 | 164 | gtsam::Vector WheelFactor5::evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Vector3 &intr_i, 165 | const gtsam::Pose3 &pose_j, const gtsam::Vector3 &intr_j, 166 | const gtsam::Vector2 &slip, boost::optional H1, 167 | boost::optional H2, boost::optional H3, 168 | boost::optional H4, 169 | boost::optional H5) const { 170 | if (H1) 171 | H1->setZero(); 172 | if (H2) 173 | H2->setZero(); 174 | if (H3) 175 | H3->setZero(); 176 | if (H4) 177 | H4->setZero(); 178 | if (H5) 179 | H5->setZero(); 180 | gtsam::Matrix H1_comp, H3_comp; 181 | gtsam::Vector e = pwm_->evaluateError(pose_i.compose(body_T_sensor_, H1_comp), intr_i, 182 | pose_j.compose(body_T_sensor_, H3_comp), intr_j, slip, H1, H2, H3, H4, H5); 183 | 184 | // If we got Jacobians out 185 | // Combine with body_T_sensor_ composition 186 | if (H1) { 187 | *H1 *= H1_comp; 188 | } 189 | if (H3) { 190 | *H3 *= H3_comp; 191 | } 192 | 193 | return e; 194 | } 195 | 196 | gtsam::Pose3 WheelFactor5::predict(const gtsam::Pose3 &x_i, const gtsam::Vector3 &intr, 197 | const gtsam::Vector2 &slip) const { 198 | gtsam::Pose3 predict = pwm_->predict(x_i.compose(body_T_sensor_), intr, slip); 199 | return predict * body_T_sensor_.inverse(); 200 | } 201 | 202 | void WheelFactor5::print(const std::string &s, const gtsam::KeyFormatter &keyFormatter) const { 203 | std::cout << s << "WheelFactor5(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << "," 204 | << keyFormatter(this->key3()) << "," << keyFormatter(this->key4()) << "," << keyFormatter(this->key4()) 205 | << ")\n" 206 | << " measured: " << pwm_->preint().transpose() << "\n"; 207 | this->noiseModel_->print(" noise model: "); 208 | } 209 | 210 | } // namespace rose -------------------------------------------------------------------------------- /rose/src/WheelRose.cpp: -------------------------------------------------------------------------------- 1 | #include "rose/WheelRose.h" 2 | 3 | namespace rose { 4 | 5 | // ------------------------- Preintegrated Wheel Measurements ------------------------- // 6 | PreintegratedWheelRose::PreintegratedWheelRose(const boost::shared_ptr &p) : Base(p) { 7 | resetIntegration(); 8 | intr_est_ = p_->intrinsics; 9 | } 10 | 11 | PreintegratedWheelRose::PreintegratedWheelRose(Base base, gtsam::Matrix62 H_slip, gtsam::Matrix63 H_intr, 12 | gtsam::Vector3 intr_est) 13 | : Base(base), H_slip_(H_slip), H_intr_(H_intr), intr_est_(intr_est) {} 14 | 15 | void PreintegratedWheelRose::resetIntegration() { 16 | H_slip_.setZero(); 17 | H_intr_.setZero(); 18 | Base::resetIntegration(); 19 | } 20 | 21 | // TODO Reset integration & reset intrinsics 22 | 23 | void PreintegratedWheelRose::integrateMeasurements(double wl, double wr, double dt) { 24 | // Convert angular rates to w, v 25 | gtsam::Matrix2 T = intrinsicsMat(); 26 | gtsam::Vector2 wl_wr; 27 | wl_wr << wl, wr; 28 | 29 | gtsam::Matrix62 E = gtsam::Matrix62::Zero(); 30 | E.block<2, 2>(2, 0) = gtsam::Matrix2::Identity(); 31 | 32 | // This functor allows for saving computation when exponential map and its 33 | // derivatives are needed at the same location in so<3> 34 | const gtsam::Matrix6 Htinv = gtsam::Pose3::ExpmapDerivative(preint_).inverse(); 35 | 36 | // Covariance propagation 37 | // A = partial f / partial x 38 | std::function f = [E, T, wl_wr, dt](const gtsam::Vector6 &x) { 39 | return gtsam::Pose3::ExpmapDerivative(x).inverse() * E * T * wl_wr * dt; 40 | }; 41 | gtsam::Matrix6 A = gtsam::I_6x6 + gtsam::numericalDerivative11(f, preint_); 42 | 43 | // B = partial f / partial eta 44 | gtsam::Matrix66 B = Htinv * dt; 45 | 46 | double b = intr_est_[0]; 47 | double rl = intr_est_[1]; 48 | double rr = intr_est_[2]; 49 | gtsam::Matrix23 C; 50 | C << -(wr * rr - wl * rl) / (b * b), -wl / b, wr / b, 0, wl / 2, wr / 2; 51 | 52 | // Move everything into place 53 | preint_ = preint_ + Htinv * E * T * wl_wr * dt; 54 | H_slip_ = A * H_slip_ + Htinv * E * T * dt; 55 | H_intr_ = A * H_intr_ + Htinv * E * C * dt; 56 | 57 | preintMeasCov_.block<6, 6>(0, 0) = 58 | A * preintMeasCov_.block<6, 6>(0, 0) * A.transpose() + B * (p_->make3DCov() / dt) * B.transpose(); 59 | 60 | preintMeasCov_.block<3, 3>(6, 6) = p_->intrinsicsBetweenCov; 61 | 62 | deltaTij_ += dt; 63 | } 64 | 65 | // ------------------------- For WheelFactor2 ------------------------- // 66 | gtsam::Pose3 PreintegratedWheelRose::predict(const gtsam::Pose3 &x_i, boost::optional H1) const { 67 | gtsam::Vector6 preintCorr = preint_; 68 | gtsam::Pose3 delta = gtsam::Pose3::Expmap(preint_); 69 | return x_i.compose(delta, H1); 70 | } 71 | 72 | gtsam::Vector PreintegratedWheelRose::evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Pose3 &pose_j, 73 | boost::optional H1, 74 | boost::optional H2) const { 75 | gtsam::Pose3 pose_j_est = predict(pose_i, H1); 76 | gtsam::Matrix H1_comp; 77 | gtsam::Vector error = pose_j_est.localCoordinates(pose_j, H1_comp, H2); 78 | 79 | if (H1) { 80 | *H1 = H1_comp * (*H1); 81 | } 82 | return error; 83 | } 84 | 85 | // ------------------------- For WheelFactor3 ------------------------- // 86 | gtsam::Pose3 PreintegratedWheelRose::predict(const gtsam::Pose3 &x_i, const gtsam::Vector2 &slip, 87 | boost::optional H1, 88 | boost::optional H2) const { 89 | 90 | gtsam::Matrix H_comp, H_exp; 91 | 92 | gtsam::Vector6 preintCorr = preint_ - H_slip_ * slip; 93 | gtsam::Pose3 delta = gtsam::Pose3::Expmap(preintCorr, H_exp); 94 | gtsam::Pose3 x_j_hat = x_i.compose(delta, H1, H_comp); 95 | 96 | if (H2) { 97 | *H2 = -H_comp * H_exp * H_slip_; 98 | } 99 | 100 | return x_j_hat; 101 | } 102 | 103 | gtsam::Vector PreintegratedWheelRose::evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Vector2 &slip, 104 | const gtsam::Pose3 &pose_j, boost::optional H1, 105 | boost::optional H2, 106 | boost::optional H3) const { 107 | gtsam::Matrix H1_comp; 108 | 109 | gtsam::Pose3 pose_j_est = predict(pose_i, slip, H1, H2); 110 | gtsam::Vector error = pose_j_est.localCoordinates(pose_j, H1_comp, H3); 111 | 112 | if (H1) { 113 | *H1 = H1_comp * (*H1); 114 | } 115 | if (H2) { 116 | *H2 = H1_comp * (*H2); 117 | } 118 | 119 | return error; 120 | } 121 | 122 | // ------------------------- For WheelFactor4 ------------------------- // 123 | gtsam::Pose3 PreintegratedWheelRose::predict(const gtsam::Pose3 &x_i, const gtsam::Vector3 &intr, 124 | boost::optional H1, 125 | boost::optional H2) const { 126 | gtsam::Matrix H_comp, H_exp; 127 | 128 | gtsam::Vector6 preintCorr = preint_ + H_intr_ * (intr - intr_est_); 129 | gtsam::Pose3 delta = gtsam::Pose3::Expmap(preintCorr, H_exp); 130 | gtsam::Pose3 x_j_hat = x_i.compose(delta, H1, H_comp); 131 | 132 | if (H2) { 133 | *H2 = H_comp * H_exp * H_intr_; 134 | } 135 | 136 | return x_j_hat; 137 | } 138 | 139 | gtsam::Vector PreintegratedWheelRose::evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Vector3 &intr_i, 140 | const gtsam::Pose3 &pose_j, const gtsam::Vector3 &intr_j, 141 | boost::optional H1, 142 | boost::optional H2, 143 | boost::optional H3, 144 | boost::optional H4) const { 145 | gtsam::Matrix H1_comp; 146 | 147 | gtsam::Vector9 error; 148 | gtsam::Pose3 pose_j_est = predict(pose_i, intr_i, H1, H2); 149 | error.head<6>() = pose_j_est.localCoordinates(pose_j, H1_comp, H3); 150 | error.tail<3>() = intr_i - intr_j; 151 | 152 | if (H1) { 153 | *H1 = H1_comp * (*H1); 154 | } 155 | if (H2) { 156 | *H2 = H1_comp * (*H2); 157 | } 158 | 159 | if (H1) { 160 | gtsam::Matrix H1_pose = H1.value(); 161 | H1->resize(9, 6); 162 | H1->setZero(); 163 | H1->block<6, 6>(0, 0) = H1_pose; 164 | } 165 | if (H2) { 166 | gtsam::Matrix H2_pose = H2.value(); 167 | H2->resize(9, 3); 168 | H2->setZero(); 169 | H2->block<6, 3>(0, 0) = H2_pose; 170 | H2->block<3, 3>(6, 0) = gtsam::I_3x3; 171 | } 172 | if (H3) { 173 | gtsam::Matrix H3_pose = H3.value(); 174 | H3->resize(9, 6); 175 | H3->setZero(); 176 | H3->block<6, 6>(0, 0) = H3_pose; 177 | } 178 | if (H4) { 179 | H4->resize(9, 3); 180 | H4->setZero(); 181 | H4->block<3, 3>(6, 0) = -gtsam::I_3x3; 182 | } 183 | 184 | return error; 185 | } 186 | 187 | // ------------------------- For WheelFactor5 ------------------------- // 188 | gtsam::Pose3 PreintegratedWheelRose::predict(const gtsam::Pose3 &x_i, const gtsam::Vector3 &intr, 189 | const gtsam::Vector2 &slip, boost::optional H1, 190 | boost::optional H2, 191 | boost::optional H3) const { 192 | gtsam::Matrix H_comp, H_exp; 193 | 194 | gtsam::Vector6 preintCorr = preint_ + H_intr_ * (intr - intr_est_) - H_slip_ * slip; 195 | gtsam::Pose3 delta = gtsam::Pose3::Expmap(preintCorr, H_exp); 196 | gtsam::Pose3 x_j_hat = x_i.compose(delta, H1, H_comp); 197 | 198 | if (H2) { 199 | *H2 = H_comp * H_exp * H_intr_; 200 | } 201 | if (H3) { 202 | *H3 = -H_comp * H_exp * H_slip_; 203 | } 204 | 205 | return x_j_hat; 206 | } 207 | 208 | gtsam::Vector PreintegratedWheelRose::evaluateError(const gtsam::Pose3 &pose_i, const gtsam::Vector3 &intr_i, 209 | const gtsam::Pose3 &pose_j, const gtsam::Vector3 &intr_j, 210 | const gtsam::Vector2 &slip, boost::optional H1, 211 | boost::optional H2, 212 | boost::optional H3, 213 | boost::optional H4, 214 | boost::optional H5) const { 215 | gtsam::Matrix H1_comp; 216 | 217 | gtsam::Vector9 error; 218 | gtsam::Pose3 pose_j_est = predict(pose_i, intr_i, slip, H1, H2, H5); 219 | error.head<6>() = pose_j_est.localCoordinates(pose_j, H1_comp, H3); 220 | error.tail<3>() = intr_i - intr_j; 221 | 222 | if (H1) { 223 | *H1 = H1_comp * (*H1); 224 | } 225 | if (H2) { 226 | *H2 = H1_comp * (*H2); 227 | } 228 | if (H5) { 229 | *H5 = H1_comp * (*H5); 230 | } 231 | 232 | if (H1) { 233 | gtsam::Matrix H1_pose = H1.value(); 234 | H1->resize(9, 6); 235 | H1->setZero(); 236 | H1->block<6, 6>(0, 0) = H1_pose; 237 | } 238 | if (H2) { 239 | gtsam::Matrix H2_pose = H2.value(); 240 | H2->resize(9, 3); 241 | H2->setZero(); 242 | H2->block<6, 3>(0, 0) = H2_pose; 243 | H2->block<3, 3>(6, 0) = gtsam::I_3x3; 244 | } 245 | if (H3) { 246 | gtsam::Matrix H3_pose = H3.value(); 247 | H3->resize(9, 6); 248 | H3->setZero(); 249 | H3->block<6, 6>(0, 0) = H3_pose; 250 | } 251 | if (H4) { 252 | H4->resize(9, 3); 253 | H4->setZero(); 254 | H4->block<3, 3>(6, 0) = -gtsam::I_3x3; 255 | } 256 | if (H5) { 257 | gtsam::Matrix H5_pose = H5.value(); 258 | H5->resize(9, 2); 259 | H5->setZero(); 260 | H5->block<6, 2>(0, 0) = H5_pose; 261 | } 262 | 263 | return error; 264 | } 265 | 266 | } // namespace rose -------------------------------------------------------------------------------- /scripts/2jrl_run.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | from pathlib import Path 3 | 4 | import gtsam 5 | import jrl 6 | import numpy as np 7 | from rose.dataset import CamNoise, Dataset2JRL, Sensor, WheelNoise 8 | from rose.jrl import ( 9 | CombinedIMUTag, 10 | PlanarPriorTag, 11 | PriorFactorIMUBiasTag, 12 | StereoFactorPose3Point3Tag, 13 | WheelBaselineTag, 14 | WheelRoseIntrSlipTag, 15 | WheelRoseIntrTag, 16 | WheelRoseSlipTag, 17 | WheelRoseTag, 18 | ZPriorTag, 19 | computeATEPose3, 20 | ) 21 | 22 | from rose import FlatDataset, GrizzlyBag, KaistDataset, SabercatBag, makeFrontend 23 | 24 | np.set_printoptions(suppress=False, precision=4, linewidth=400) 25 | 26 | 27 | def compute_traj_length(values: gtsam.Values): 28 | poses = gtsam.utilities.allPose3s(values) 29 | keys = sorted(list(poses.keys())) 30 | dist = 0 31 | x_prev = poses.atPose3(keys[0]) 32 | for k in keys[1:]: 33 | x_curr = poses.atPose3(k) 34 | dist += np.linalg.norm(x_curr.translation() - x_prev.translation()) 35 | x_prev = x_curr 36 | 37 | return dist 38 | 39 | 40 | if __name__ == "__main__": 41 | np.random.seed(0) 42 | 43 | # ------------------------- Parse Args ------------------------- # 44 | parser = argparse.ArgumentParser(description="Convert 2 jrl factor graph") 45 | parser.add_argument( 46 | "-k", 47 | "--kaist", 48 | type=Path, 49 | default=None, 50 | help="Dataset folder to be read in.", 51 | ) 52 | parser.add_argument( 53 | "-f", 54 | "--flat", 55 | type=Path, 56 | default=None, 57 | help="Dataset folder to be read in.", 58 | ) 59 | parser.add_argument( 60 | "-g", 61 | "--grizzly", 62 | type=Path, 63 | default=None, 64 | help="Dataset folder to be read in.", 65 | ) 66 | parser.add_argument( 67 | "-s", 68 | "--sabercat", 69 | type=Path, 70 | default=None, 71 | help="Dataset folder to be read in.", 72 | ) 73 | parser.add_argument( 74 | "--resave-data", 75 | action="store_true", 76 | help="Dataset folder to be read in.", 77 | ) 78 | parser.add_argument( 79 | "--resave-params", 80 | action="store_true", 81 | help="Dataset folder to be read in.", 82 | ) 83 | parser.add_argument( 84 | "-o", 85 | "--flat_out", 86 | type=Path, 87 | default=Path("/mnt/data/flat"), 88 | help="Where to convert datasets to.", 89 | ) 90 | 91 | d = WheelNoise.__dict__ 92 | wheel_noise_params = {k: d[k] for k in d["__annotations__"].keys()} 93 | for k, v in wheel_noise_params.items(): 94 | parser.add_argument(f"--{k}", type=float, default=v) 95 | 96 | d = CamNoise.__dict__ 97 | cam_noise_params = {k: d[k] for k in d["__annotations__"].keys()} 98 | for k, v in cam_noise_params.items(): 99 | parser.add_argument(f"--{k}", type=float, default=v) 100 | 101 | parser.add_argument("--meta", type=str, default="") 102 | 103 | parser.add_argument( 104 | "-n", 105 | "--iter", 106 | type=int, 107 | default=None, 108 | help="How many iterations to store. Defaults to all", 109 | ) 110 | parser.add_argument( 111 | "--show", 112 | action="store_true", 113 | help="Whether to watch camera feed", 114 | ) 115 | parser.add_argument( 116 | "--no-cache", 117 | action="store_true", 118 | help="Don't use camera stash.", 119 | ) 120 | args = parser.parse_args() 121 | args_dict = vars(args) 122 | 123 | # ------------------------- Run everything ------------------------- # 124 | wheel_noise_params = {k: args_dict[k] for k in wheel_noise_params.keys()} 125 | wheel_noise = WheelNoise(**wheel_noise_params) 126 | cam_noise_params = {k: args_dict[k] for k in cam_noise_params.keys()} 127 | cam_noise = CamNoise(**cam_noise_params) 128 | 129 | if args.grizzly is not None: 130 | bag = GrizzlyBag(args.grizzly) 131 | flat_path = args.flat_out / bag.name 132 | if args.resave_data or args.resave_params or not flat_path.exists(): 133 | print(f"Saving grizzly bag to flat dataset at {flat_path}...") 134 | bag.to_flat(args.flat_out) 135 | dataset = FlatDataset(flat_path) 136 | 137 | elif args.sabercat is not None: 138 | bag = SabercatBag(args.sabercat) 139 | flat_path = args.flat_out / bag.name 140 | if not flat_path.exists(): 141 | print(f"Saving sabercat bag to flat dataset at {flat_path}...") 142 | bag.to_flat(args.flat_out) 143 | if args.resave_data: 144 | print(f"Resaving data for {bag.name}...") 145 | bag.to_flat_data(args.flat_out) 146 | if args.resave_params: 147 | print(f"Resaving params for {bag.name}...") 148 | bag.to_flat_params(args.flat_out) 149 | dataset = FlatDataset(flat_path) 150 | 151 | elif args.kaist is not None: 152 | dataset = KaistDataset(args.kaist) 153 | 154 | elif args.flat is not None: 155 | dataset = FlatDataset(args.flat) 156 | 157 | # dataset.add_noise(Sensor.WHEEL, wheel_noise) 158 | # dataset.add_noise(Sensor.CAM, cam_noise) 159 | 160 | data = Dataset2JRL(dataset, args.iter) 161 | 162 | out_dir = Path(f"data/{dataset.name}/") 163 | out_dir.mkdir(exist_ok=True) 164 | 165 | # First check if we need to make & save camera factors 166 | if not (out_dir / "cam.jrl").exists() or args.no_cache: 167 | print("Adding stereo camera factors...") 168 | data.add_factors(Sensor.CAM, show=args.show) 169 | data.save_dataset(out_dir / "cam.jrl") 170 | data.clear_factors() 171 | 172 | print("Adding priors...") 173 | data.add_factors(Sensor.PRIOR) 174 | 175 | print("Adding IMU...") 176 | data.add_factors(Sensor.IMU) 177 | 178 | print("Adding Wheel...") 179 | data.add_factors(Sensor.WHEEL) 180 | 181 | print("Loading camera factors...") 182 | data.load_cache(out_dir / "cam.jrl") 183 | 184 | print("Getting ground truth...") 185 | data.get_ground_truth() 186 | 187 | data.save_traj(Sensor.GT, out_dir / "_gt.jrr") 188 | data.save_traj(Sensor.WHEEL, out_dir / "_wheel.jrr") 189 | gt = data.traj[Sensor.GT] 190 | km = compute_traj_length(gt) / 1000 191 | print("Ground truth length:", km) 192 | 193 | out_file = out_dir / f"data{args.meta}.jrl" 194 | 195 | def run(*kinds): 196 | factors = { 197 | "base": [jrl.PriorFactorPose3Tag, StereoFactorPose3Point3Tag], 198 | "imu": [ 199 | jrl.PriorFactorPoint3Tag, 200 | PriorFactorIMUBiasTag, 201 | CombinedIMUTag, 202 | ], 203 | "wheel_rose": [WheelRoseTag], 204 | "wheel_intr": [WheelRoseIntrTag, jrl.PriorFactorPoint3Tag], 205 | "wheel_slip": [WheelRoseSlipTag, jrl.PriorFactorPoint2Tag], 206 | "wheel_intr_slip": [ 207 | WheelRoseIntrSlipTag, 208 | jrl.PriorFactorPoint3Tag, 209 | jrl.PriorFactorPoint2Tag, 210 | ], 211 | "wheel_baseline": [WheelBaselineTag], 212 | "planar_prior": [ZPriorTag, PlanarPriorTag], 213 | } 214 | 215 | factors_these = sum([factors[k] for k in kinds], []) 216 | filename = out_dir / f"f-{'.'.join(kinds)}.jrr" 217 | 218 | try: 219 | frontend = makeFrontend() 220 | sol = frontend.run( 221 | data.to_dataset(), 222 | factors_these, 223 | str(filename), 224 | 0, 225 | True, 226 | ) 227 | ate = computeATEPose3(gt, sol, False, False)[0] / km 228 | print(f"{kinds} got {ate}") 229 | except Exception as e: 230 | print(f"{kinds} Failed. {e}") 231 | 232 | # run("base") 233 | 234 | # run("base", "imu") 235 | # run("base", "imu", "wheel_rose") 236 | run("base", "imu", "wheel_intr_slip") 237 | # run("base", "imu", "wheel_baseline") 238 | # run("base", "imu", "wheel_baseline", "planar_prior") 239 | 240 | # run("base", "wheel_rose") 241 | run("base", "wheel_intr_slip") 242 | # run("base", "wheel_baseline") 243 | # run("base", "wheel_baseline", "planar_prior") 244 | -------------------------------------------------------------------------------- /scripts/optimize_cov.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | import os 3 | from pathlib import Path 4 | from typing import Optional 5 | 6 | import gtsam 7 | import jrl 8 | import numpy as np 9 | from rose.dataset import Dataset2JRL, Sensor, WheelNoise 10 | from rose.datasets import FlatDataset, KaistDataset 11 | from rose.ros import GrizzlyBag 12 | from rose.rose_python import ( 13 | WheelRoseIntrSlipTag, 14 | makeFrontend, 15 | ) 16 | from scipy.optimize import shgo 17 | from tabulate import tabulate 18 | 19 | import rose 20 | 21 | np.set_printoptions(suppress=False, precision=5, linewidth=400) 22 | 23 | 24 | def compute_traj_length(values: gtsam.Values): 25 | poses = gtsam.utilities.allPose3s(values) 26 | keys = sorted(list(poses.keys())) 27 | dist = 0 28 | x_prev = poses.atPose3(keys[0]) 29 | for k in keys[1:]: 30 | x_curr = poses.atPose3(k) 31 | dist += np.linalg.norm(x_curr.translation() - x_prev.translation()) 32 | x_prev = x_curr 33 | 34 | return dist 35 | 36 | 37 | if __name__ == "__main__": 38 | np.random.seed(0) 39 | 40 | # ------------------------- Parse Args ------------------------- # 41 | parser = argparse.ArgumentParser(description="Convert Kaist 2 jrl factor graph") 42 | parser.add_argument( 43 | "-k", 44 | "--kaist", 45 | type=Path, 46 | nargs="+", 47 | default=None, 48 | help="Dataset folder to be read in.", 49 | ) 50 | parser.add_argument( 51 | "-f", 52 | "--flat", 53 | type=Path, 54 | nargs="+", 55 | default=None, 56 | help="Dataset folder to be read in.", 57 | ) 58 | parser.add_argument( 59 | "-g", 60 | "--grizzly", 61 | type=Path, 62 | nargs="+", 63 | default=None, 64 | help="Dataset folder to be read in.", 65 | ) 66 | parser.add_argument( 67 | "--resave_grizzly", 68 | action="store_true", 69 | help="Dataset folder to be read in.", 70 | ) 71 | parser.add_argument( 72 | "-o", 73 | "--flat_out", 74 | type=Path, 75 | default=Path("/mnt/data/flat"), 76 | help="Where to convert datasets to.", 77 | ) 78 | parser.add_argument( 79 | "-n", 80 | "--iter", 81 | type=int, 82 | default=None, 83 | help="How many iterations to store. Defaults to all", 84 | ) 85 | parser.add_argument( 86 | "--no-cache", 87 | action="store_true", 88 | help="Don't use camera stash.", 89 | ) 90 | args = parser.parse_args() 91 | 92 | # ------------------------- Set everything up ------------------------- # 93 | i = 0 94 | all_datasets = [] 95 | if args.grizzly is not None: 96 | for g in args.grizzly: 97 | bag = GrizzlyBag(g) 98 | path = args.flat_out / bag.name 99 | 100 | if args.resave_grizzly or not path.exists(): 101 | print(f"Saving grizzly bag to flat dataset at {path}...") 102 | bag.to_flat(args.flat_out) 103 | 104 | all_datasets.append(FlatDataset(path)) 105 | 106 | if args.kaist is not None: 107 | for k in args.kaist: 108 | all_datasets.append(KaistDataset(k)) 109 | 110 | elif args.flat is not None: 111 | for f in args.flat: 112 | all_datasets.append(FlatDataset(f)) 113 | 114 | # ------------------------- Add camera factors ------------------------- # 115 | print("Adding stereo camera factors...") 116 | all_cams = [] 117 | for dataset in all_datasets: 118 | cam = Dataset2JRL(dataset, args.iter) 119 | 120 | out_dir = f"data/{dataset.name}/" 121 | os.makedirs(out_dir, exist_ok=True) 122 | 123 | # First load up camera factors 124 | if not os.path.exists(out_dir + "cam.jrl") or args.no_cache: 125 | cam.add_factors(Sensor.CAM) 126 | cam.save_dataset(out_dir + "cam.jrl") 127 | else: 128 | cam.load_cache(out_dir + "cam.jrl") 129 | 130 | all_cams.append(cam) 131 | 132 | # ------------------------- Run everything ------------------------- # 133 | print("Beginning optimization...") 134 | 135 | def objective(x, arg=""): 136 | global i 137 | ates = [["Dataset", "IMU+Wheel", "Wheel"]] 138 | ate_total = 0 139 | for flat, cam in zip(all_datasets, all_cams): 140 | wheel_noise = flat.noise(Sensor.WHEEL) 141 | wheel_noise = vec2noise(x, wheel_noise) 142 | 143 | flat.add_noise(Sensor.WHEEL, wheel_noise) 144 | flat.clear_cache() 145 | 146 | data = Dataset2JRL(flat, args.iter) 147 | data.clear_factors() 148 | 149 | data.add_factors(Sensor.PRIOR) 150 | data.add_factors(Sensor.IMU) 151 | data.get_ground_truth() 152 | data.add_factors(Sensor.WHEEL) 153 | data += cam 154 | 155 | gt = data.traj[Sensor.GT] 156 | km = compute_traj_length(gt) / 1000 157 | 158 | # WheelRoseIntrSlipTag, # wheel factor 159 | # jrl.PriorFactorPoint2Tag, # slip prior throughout 160 | # PriorFactorIntrinsicsTag, # intrinsics prior throughout 161 | # jrl.PriorFactorPoint3Tag, # intrinsics prior 162 | 163 | frontend = makeFrontend() 164 | 165 | # try: 166 | # # Run w/ IMU 167 | # sol = frontend.run( 168 | # data.to_dataset(), 169 | # [ 170 | # jrl.PriorFactorPoint3Tag, 171 | # jrl.PriorFactorIMUBiasTag, 172 | # jrl.CombinedIMUTag, 173 | # # 174 | # WheelRoseIntrTag, 175 | # PriorFactorIntrinsicsTag, 176 | # jrl.PriorFactorPoint3Tag, 177 | # # 178 | # jrl.PriorFactorPose3Tag, # pose prior 179 | # jrl.StereoFactorPose3Point3Tag, 180 | # ], 181 | # f"opt.jrr", 182 | # 0, 183 | # True, 184 | # ) 185 | # ate_imu = jrl.computeATEPose3(gt, sol, False, False)[0] 186 | # except: 187 | # ate_imu = 500 188 | ate_imu = 0 189 | 190 | try: 191 | # Run w/o IMU 192 | sol = frontend.run( 193 | data.to_dataset(), 194 | [ 195 | WheelRoseIntrSlipTag, 196 | jrl.PriorFactorPoint3Tag, 197 | jrl.PriorFactorPoint2Tag, 198 | jrl.PriorFactorPoint3Tag, 199 | # 200 | jrl.PriorFactorPose3Tag, # pose prior 201 | jrl.StereoFactorPose3Point3Tag, 202 | ], 203 | "opt.jrr", 204 | 0, 205 | True, 206 | ) 207 | ate_none = rose.jrl.computeATEPose3(gt, sol, False, False)[0] / km 208 | except Exception as _: 209 | ate_none = 500 210 | 211 | ate_total += ate_none 212 | ate_total += ate_imu 213 | ates.append([flat.name, ate_imu, ate_none]) 214 | 215 | del frontend 216 | del data 217 | 218 | i += 1 219 | print(i, np.array(10**x), ate_total) 220 | print(tabulate(ates, headers="firstrow", tablefmt="github")) 221 | return ate_total 222 | 223 | def vec2noise(x, wheel_noise: Optional[WheelNoise] = None): 224 | if wheel_noise is None: 225 | wheel_noise = WheelNoise() 226 | 227 | x = 10**x 228 | # wheel_noise.sigma_rad_s = float(x[0]) 229 | # wheel_noise.sigma_vy = float(x[1]) 230 | # wheel_noise.sigma_vz = float(x[1]) 231 | # wheel_noise.sigma_wx = float(x[2]) 232 | # wheel_noise.sigma_wy = float(x[2]) 233 | 234 | wheel_noise.sig_intr_baseline = float(x[0]) 235 | wheel_noise.sig_intr_radius = float(x[1]) 236 | 237 | # wheel_noise.sig_slip_prior = float(x[1]) 238 | 239 | return wheel_noise 240 | 241 | bounds = np.array( 242 | [ 243 | [1e-5, 1e-3], 244 | # 245 | # [0.01, 0.1], 246 | # [0.005, 0.05], 247 | # 248 | [1e-6, 1e-4], 249 | # 250 | # [-7, -1], 251 | # [-7, -1], 252 | # [-2, 0], 253 | # [1e-2, 1e0], 254 | ] 255 | ) 256 | bounds = np.log10(bounds) 257 | 258 | out = shgo(objective, bounds, workers=10) 259 | print(out) 260 | 261 | # out = dual_annealing( 262 | # objective, 263 | # bounds, 264 | # maxfun=100, 265 | # no_local_search=False, 266 | # x0=[0.05, 0.1, 0.01], 267 | # ) 268 | 269 | # print(out) 270 | # noise = vec2noise(out.x, all_datasets[0].noise(Sensor.WHEEL)) 271 | # noise.save("intr_wheel_rose.yaml") 272 | 273 | # print( 274 | # direct( 275 | # objective, 276 | # bounds, 277 | # locally_biased=False, 278 | # ) 279 | # ) 280 | 281 | # print( 282 | # brute( 283 | # objective, 284 | # ranges=bounds, 285 | # args=("brute",), 286 | # full_output=False, 287 | # workers=5, 288 | # Ns=10, 289 | # ) 290 | # ) 291 | -------------------------------------------------------------------------------- /scripts/results.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | import os 3 | 4 | import gtsam 5 | import numpy as np 6 | import rose.jrl 7 | from gtsam.symbol_shorthand import X 8 | from rose.plot import ( 9 | plot_3d_trajectory, 10 | plot_error_state, 11 | plot_state, 12 | plot_xy_trajectory, 13 | ) 14 | from tabulate import tabulate 15 | 16 | 17 | def compute_traj_length(values: gtsam.Values): 18 | poses = gtsam.utilities.allPose3s(values) 19 | keys = sorted(list(poses.keys())) 20 | dist = 0 21 | x_prev = poses.atPose3(keys[0]) 22 | for k in keys[1:]: 23 | x_curr = poses.atPose3(k) 24 | dist += np.linalg.norm(x_curr.translation() - x_prev.translation()) 25 | x_prev = x_curr 26 | 27 | return dist 28 | 29 | 30 | def get_subset(values: gtsam.Values, N: int): 31 | if N is None: 32 | return values 33 | 34 | values_pose3 = gtsam.Values() 35 | for i in range(N): 36 | values_pose3.insert(X(i), values.atPose3(X(i))) 37 | return values_pose3 38 | 39 | 40 | def cbor(s): 41 | return "cbor" in s 42 | 43 | 44 | if __name__ == "__main__": 45 | func = { 46 | "state": plot_state, 47 | "xy": plot_xy_trajectory, 48 | "3d": plot_3d_trajectory, 49 | "error": plot_error_state, 50 | } 51 | 52 | # For loading 53 | parser = argparse.ArgumentParser(description="Plot results of trajectory") 54 | parser.add_argument("--gt", type=str, help="Ground truth data to plot.") 55 | parser.add_argument("--traj", type=str, nargs="+", help="Result folders to plot") 56 | parser.add_argument( 57 | "--type", 58 | type=str, 59 | choices=list(func.keys()), 60 | default=list(func.keys())[0], 61 | help="Type of plot to generate", 62 | ) 63 | parser.add_argument( 64 | "-n", 65 | "--iter", 66 | type=int, 67 | default=None, 68 | help="How many iterations to store. Defaults to all", 69 | ) 70 | parser.add_argument( 71 | "--align", 72 | action="store_true", 73 | help="Whether to align trajectories when plotting", 74 | ) 75 | 76 | # for plotting 77 | parser.add_argument( 78 | "--show", action="store_true", help="Whether to display figure at end" 79 | ) 80 | parser.add_argument( 81 | "--filename", type=str, default=None, help="Where to save the resulting figure" 82 | ) 83 | parser.add_argument( 84 | "-s", 85 | "--states", 86 | type=str, 87 | default="rpv", 88 | help="Which states to plot. Defaults to rpv", 89 | ) 90 | 91 | # for computing 92 | parser.add_argument("--compute", action="store_true", help="Whether to compute ATE") 93 | parser.add_argument( 94 | "--norm", 95 | action="store_true", 96 | help="Whether to normalized by length of trajectory", 97 | ) 98 | 99 | args = parser.parse_args() 100 | 101 | # ------------------------- Load gt values ------------------------- # 102 | jrl_parser = rose.jrl.makeRoseParser() 103 | 104 | trajs = {} 105 | if args.gt: 106 | print("Loading GT...") 107 | dataset = jrl_parser.parseDataset(args.gt, cbor(args.gt)) 108 | trajs["GT"] = dataset.groundTruth("a") 109 | name = dataset.name() 110 | 111 | # ------------------------- Load all trajectories ------------------------- # 112 | if args.traj: 113 | print("Loading Trajectories...", end="") 114 | for f in sorted(args.traj): 115 | results = jrl_parser.parseResults(f, cbor(f)) 116 | 117 | result_name = os.path.splitext(os.path.basename(f))[0] 118 | 119 | if result_name == "_gt": 120 | result_name = "GT" 121 | elif result_name == "_wheel": 122 | result_name = "Wheel" 123 | print(f"\n\t{result_name}...", end="") 124 | 125 | values = results.robot_solutions["a"].values 126 | trajs[result_name] = values 127 | name = results.dataset_name 128 | 129 | print("\tDone!\n") 130 | 131 | # ------------------------- Compute ------------------------- # 132 | if args.compute: 133 | print("Computing GT length...", end="") 134 | km = compute_traj_length(get_subset(trajs["GT"], args.iter)) / 1000 135 | print(f"\t{km} km") 136 | 137 | km = km if args.norm else 1 138 | print("Computing ATE...") 139 | data = [] 140 | for name, values in trajs.items(): 141 | error = rose.jrl.computeATEPose3( 142 | trajs["GT"], get_subset(values, args.iter), align=args.align 143 | ) 144 | data.append([name, error[0] / km, error[1] * 180 / np.pi]) 145 | 146 | atet = "ATEt" 147 | if args.norm: 148 | atet += " / km" 149 | data = sorted(data, key=lambda x: x[1]) 150 | data.insert(0, ["Run", atet, "ATEr"]) 151 | 152 | print(tabulate(data, headers="firstrow", tablefmt="github")) 153 | print() 154 | 155 | # ------------------------- Plot ------------------------- # 156 | if args.show or args.filename: 157 | print("Plotting...", end="") 158 | func[args.type]( 159 | figtitle=name, 160 | filename=args.filename, 161 | show=args.show, 162 | align=args.align, 163 | N=args.iter, 164 | states=args.states, 165 | **trajs, 166 | ) 167 | print("\tDone!") 168 | -------------------------------------------------------------------------------- /scripts/run_sabercat.sh: -------------------------------------------------------------------------------- 1 | 2 | for bag in /mnt/bags/best/*; do 3 | echo "\033[0;31m ${bag}\033[0m" 4 | python scripts/2jrl_run.py --sabercat ${bag} 5 | done 6 | 7 | curl -d "Finished running sabercat data" ntfy.sh/easton_work -------------------------------------------------------------------------------- /scripts/sim.py: -------------------------------------------------------------------------------- 1 | import gtsam 2 | import jrl 3 | import numpy as np 4 | from rose.dataset import Dataset2JRL, Sensor 5 | from rose.jrl import ( 6 | PlanarPriorTag, 7 | StereoFactorPose3Point3Tag, 8 | WheelBaselineTag, 9 | WheelRoseIntrSlipTag, 10 | WheelRoseIntrTag, 11 | WheelRoseSlipTag, 12 | WheelRoseTag, 13 | ZPriorTag, 14 | makeRoseWriter, 15 | values2results, 16 | ) 17 | from rose.sim import SimParameters, Simulation 18 | from tabulate import tabulate 19 | 20 | import rose 21 | 22 | np.set_printoptions(suppress=False, precision=3) 23 | 24 | 25 | def compute_traj_length(values: gtsam.Values): 26 | poses = gtsam.utilities.allPose3s(values) 27 | keys = sorted(list(poses.keys())) 28 | dist = 0 29 | x_prev = poses.atPose3(keys[0]) 30 | for k in keys[1:]: 31 | x_curr = poses.atPose3(k) 32 | dist += np.linalg.norm(x_curr.translation() - x_prev.translation()) 33 | x_prev = x_curr 34 | 35 | return dist 36 | 37 | 38 | if __name__ == "__main__": 39 | np.random.seed(3) 40 | params = SimParameters() 41 | 42 | params.slip_num = 10 43 | params.slip_length = 0.5 44 | params.slip_duration = 0.5 45 | 46 | params.w_intr_init_perturb = 1.1 47 | # params.w_intr_perturb_time = [50, 80] 48 | params.time = 100 49 | params.num_feats = 50 50 | params.sigma_pix = 1 51 | 52 | v = 2 53 | w = lambda t: np.cos(t * 1.5) # noqa: E731 54 | sim = Simulation(params, np.pi / 6, v=2) 55 | sim.run_all(w, v) 56 | 57 | dataset = Dataset2JRL(sim) 58 | dataset.add_factors(Sensor.PRIOR, use_gt_orien=True) 59 | dataset.add_factors(Sensor.IMU) 60 | dataset.add_factors(Sensor.WHEEL) 61 | dataset.add_factors(Sensor.FEAT) 62 | gt = dataset.get_ground_truth() 63 | 64 | writer = makeRoseWriter() 65 | writer.writeResults(values2results(gt), "figures/data/GT.jrr", False) 66 | 67 | traj = {"GT": dataset.traj[Sensor.GT], "Wheel": dataset.traj[Sensor.WHEEL]} 68 | data = [["Kind", "ATEt", "ATEr"]] 69 | names = { 70 | WheelRoseTag: "6DoF Cov Prop", 71 | WheelBaselineTag: "Planar", 72 | WheelRoseSlipTag: "Slip", 73 | WheelRoseIntrTag: "Intrinsics", 74 | WheelRoseIntrSlipTag: "Intrinsics + Slip", 75 | None: "No Wheel", 76 | } 77 | for tag in [ 78 | WheelBaselineTag, 79 | WheelRoseTag, 80 | WheelRoseSlipTag, 81 | WheelRoseIntrTag, 82 | WheelRoseIntrSlipTag, 83 | None, 84 | ]: 85 | sensors = [ 86 | StereoFactorPose3Point3Tag, 87 | jrl.PriorFactorPose3Tag, 88 | # jrl.PriorFactorPoint3Tag, 89 | # PriorFactorIMUBiasTag, 90 | # CombinedIMUTag, 91 | ] 92 | if tag is not None: 93 | sensors.append(tag) 94 | if tag == WheelBaselineTag: 95 | sensors.append(PlanarPriorTag) 96 | sensors.append(ZPriorTag) 97 | if WheelRoseSlipTag in sensors: 98 | sensors.append(jrl.PriorFactorPoint2Tag) 99 | if WheelRoseIntrTag in sensors: 100 | sensors.append(jrl.PriorFactorPoint3Tag) 101 | if WheelRoseIntrSlipTag in sensors: 102 | sensors.append(jrl.PriorFactorPoint2Tag) 103 | sensors.append(jrl.PriorFactorPoint3Tag) 104 | frontend = rose.makeFrontend(kf=5) 105 | sol = frontend.run( 106 | dataset.to_dataset(), sensors, f"figures/data/{tag}.jrr", 0, False 107 | ) 108 | 109 | d = dataset.to_dataset() 110 | graph = gtsam.NonlinearFactorGraph() 111 | for mm in d.measurements("a"): 112 | graph.push_back(mm.filter(sensors).measurements) 113 | 114 | # Compute error 115 | km = compute_traj_length(gt) / 1000 116 | et, er = rose.jrl.computeATEPose3(gt, sol, False) 117 | data.append([names[tag], et, er * 180 / np.pi]) 118 | traj[names[tag]] = sol 119 | print(f"\tFinished {tag}, e: {graph.error(sol):.2E}...") 120 | 121 | print("\nDist\t", km, "\n") 122 | print(tabulate(data, headers="firstrow", tablefmt="github")) 123 | 124 | # ------------------------- Plot States ------------------------- # 125 | # fig, ax = rose.plot.plot_error_state(GT=gt, **traj) 126 | # plt.savefig("sim_error.png") 127 | # fig, ax = rose.plot.plot_xy_trajectory(states="rpis", show=True, **traj) 128 | fig, ax = rose.plot.plot_state(states="rpis", show=True, filename="sim.png", **traj) 129 | -------------------------------------------------------------------------------- /scripts/sim_monte_carlo.py: -------------------------------------------------------------------------------- 1 | import gtsam 2 | import jrl 3 | import matplotlib.pyplot as plt 4 | import numpy as np 5 | import pandas as pd 6 | import rose.plot 7 | from rose.dataset import Dataset2JRL, Sensor 8 | from rose.jrl import ( 9 | CombinedIMUTag, 10 | PlanarPriorTag, 11 | PriorFactorIMUBiasTag, 12 | StereoFactorPose3Point3Tag, 13 | WheelBaselineTag, 14 | WheelRoseIntrSlipTag, 15 | WheelRoseIntrTag, 16 | WheelRoseSlipTag, 17 | WheelRoseTag, 18 | ZPriorTag, 19 | ) 20 | from rose.sim import SimParameters, Simulation 21 | from tqdm import trange 22 | 23 | from rose import makeFrontend 24 | 25 | 26 | def compute_traj_length(values: gtsam.Values): 27 | poses = gtsam.utilities.allPose3s(values) 28 | keys = sorted(list(poses.keys())) 29 | dist = 0 30 | x_prev = poses.atPose3(keys[0]) 31 | for k in keys[1:]: 32 | x_curr = poses.atPose3(k) 33 | dist += np.linalg.norm(x_curr.translation() - x_prev.translation()) 34 | x_prev = x_curr 35 | 36 | return dist 37 | 38 | 39 | def main(ideal: bool): 40 | kind = "ideal" if ideal else "real" 41 | print(f"Running Monte Carlo for {kind}...") 42 | 43 | np.random.seed(0) 44 | params = SimParameters() 45 | 46 | runs = 10 47 | 48 | params.slip_num = 0 if ideal else 10 49 | params.slip_length = 0.5 50 | params.slip_duration = 0.5 51 | 52 | params.w_intr_init_perturb = 1.0 if ideal else 1.1 53 | params.time = 100 54 | params.num_feats = 50 55 | params.sigma_pix = 1 56 | 57 | v = 2 58 | w = lambda t: np.cos(t * 1.5) # noqa: E731 59 | 60 | traj = {} 61 | data = [] 62 | for i in trange(runs, leave=False): 63 | sim = Simulation(params, yaw=np.pi / 6, v=v) 64 | sim.run_all(w, v) 65 | 66 | dataset = Dataset2JRL(sim) 67 | dataset.add_factors(Sensor.PRIOR, use_gt_orien=True) 68 | dataset.add_factors(Sensor.IMU) 69 | dataset.add_factors(Sensor.WHEEL) 70 | dataset.add_factors(Sensor.FEAT) 71 | 72 | gt = dataset.get_ground_truth() 73 | km = compute_traj_length(gt) / 1000 74 | 75 | wheel = dataset.traj[Sensor.WHEEL] 76 | et, er = rose.jrl.computeATEPose3(gt, wheel, False) 77 | data.append(["wheel", False, et, er * 180 / np.pi]) 78 | 79 | for use_imu in [False]: 80 | for tag in [ 81 | WheelBaselineTag, 82 | WheelRoseTag, 83 | WheelRoseIntrSlipTag, 84 | "stereo", 85 | ]: 86 | sensors = [ 87 | jrl.PriorFactorPose3Tag, 88 | StereoFactorPose3Point3Tag, 89 | ] 90 | if tag != "stereo": 91 | sensors.append(tag) 92 | if WheelBaselineTag in sensors: 93 | sensors.append(PlanarPriorTag) 94 | sensors.append(ZPriorTag) 95 | if WheelRoseSlipTag in sensors: 96 | sensors.append(jrl.PriorFactorPoint2Tag) 97 | if WheelRoseIntrTag in sensors: 98 | sensors.append(jrl.PriorFactorPoint3Tag) 99 | if WheelRoseIntrSlipTag in sensors: 100 | sensors.append(jrl.PriorFactorPoint2Tag) 101 | sensors.append(jrl.PriorFactorPoint3Tag) 102 | if use_imu: 103 | sensors.extend( 104 | [ 105 | jrl.PriorFactorPoint3Tag, 106 | PriorFactorIMUBiasTag, 107 | CombinedIMUTag, 108 | ] 109 | ) 110 | 111 | frontend = makeFrontend(kf=5) 112 | sol = frontend.run(dataset.to_dataset(), sensors, "temp.jrr", 0, False) 113 | 114 | # Compute error 115 | name = f"{tag}{i}" 116 | et, er = rose.jrl.computeATEPose3(gt, sol, False) 117 | data.append([tag, use_imu, et, er * 180 / np.pi]) 118 | traj[name] = sol 119 | # print(f"\tFinished {name}...") 120 | 121 | rose.plot.plot_state( 122 | GT=gt, 123 | states="rpis", 124 | show=False, 125 | filename=f"sim_{i}.png", 126 | baseline=traj[f"{WheelBaselineTag}{i}"], 127 | rose_minus=traj[f"{WheelRoseTag}{i}"], 128 | rose=traj[f"{WheelRoseIntrSlipTag}{i}"], 129 | ) 130 | plt.close() 131 | 132 | print("\nDist\t", km, "\n") 133 | 134 | # ------------------------- Plot States ------------------------- # 135 | df = pd.DataFrame( 136 | data, 137 | columns=["WheelFactor", "IMU", "ATEt", "ATEr"], 138 | ) 139 | df.to_pickle(f"figures/data/sim_monte_carlo_{kind}.pkl") 140 | 141 | 142 | if __name__ == "__main__": 143 | # main(True) 144 | main(False) 145 | -------------------------------------------------------------------------------- /tests/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # Setup gtest 2 | include(FetchContent) 3 | FetchContent_Declare( 4 | googletest 5 | GIT_REPOSITORY https://github.com/google/googletest.git 6 | GIT_TAG origin/main 7 | ) 8 | option(INSTALL_GTEST OFF) 9 | FetchContent_MakeAvailable(googletest) 10 | enable_testing() # enable ctest 11 | 12 | # Make test target 13 | file(GLOB_RECURSE tests_srcs *.cpp) 14 | add_executable(rose-tests ${tests_srcs}) 15 | target_link_libraries(rose-tests PUBLIC experiments gtest) 16 | add_test(NAME rose-tests COMMAND rose-tests) 17 | 18 | # Make runnable from "make check" or "make test" 19 | add_custom_target(check COMMAND rose-tests) 20 | add_custom_target(test COMMAND rose-tests) -------------------------------------------------------------------------------- /tests/main.cpp: -------------------------------------------------------------------------------- 1 | #include "gtest/gtest.h" 2 | 3 | int main(int argc, char **argv) { 4 | ::testing::InitGoogleTest(&argc, argv); 5 | return RUN_ALL_TESTS(); 6 | } -------------------------------------------------------------------------------- /tests/test_CombinedIMUFactor.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | #include "JRL-custom.h" 11 | #include "JRL.h" 12 | 13 | #include "gtest/gtest.h" 14 | 15 | using gtsam::symbol_shorthand::B; 16 | using gtsam::symbol_shorthand::V; 17 | using gtsam::symbol_shorthand::X; 18 | 19 | #define EXPECT_MATRICES_EQ(M_actual, M_expected) \ 20 | EXPECT_TRUE(M_actual.isApprox(M_expected, 1e-6)) << " Actual:\n" << M_actual << "\nExpected:\n" << M_expected 21 | 22 | TEST(Factor, CombinedIMU) { 23 | // Setup nonstandard params 24 | boost::shared_ptr params = gtsam::PreintegrationCombinedParams::MakeSharedU(); 25 | params->accelerometerCovariance = Eigen::Matrix3d::Identity() * 2; 26 | params->gyroscopeCovariance = Eigen::Matrix3d::Identity() * 3; 27 | params->biasAccCovariance = Eigen::Matrix3d::Identity() * 4; 28 | params->biasOmegaCovariance = Eigen::Matrix3d::Identity() * 5; 29 | params->biasAccOmegaInt = Eigen::Matrix::Identity() * 6; 30 | params->integrationCovariance = Eigen::Matrix3d::Identity() * 7; 31 | 32 | // Setup measurements 33 | gtsam::imuBias::ConstantBias b(gtsam::Vector3::Constant(6), gtsam::Vector3::Constant(7)); 34 | gtsam::PreintegratedCombinedMeasurements pim(params, b); 35 | gtsam::Vector3 accel{1, 2, 3}; 36 | gtsam::Vector3 omega{4, 5, 6}; 37 | double dt = 0.1; 38 | pim.integrateMeasurement(accel, omega, dt); 39 | pim.integrateMeasurement(accel, omega, dt); 40 | 41 | // Setup factor 42 | int i = 0; 43 | int j = 1; 44 | gtsam::CombinedImuFactor write_factor(X(i), V(i), X(j), V(j), B(i), B(j), pim); 45 | 46 | // Save it 47 | gtsam::NonlinearFactorGraph graph; 48 | graph.push_back(write_factor); 49 | 50 | jrl::DatasetBuilder builder("test", {'a'}); 51 | builder.addEntry('a', 0, graph, {jrl_rose::CombinedIMUTag}); 52 | 53 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 54 | writer.writeDataset(builder.build(), "combined_imu.jrl"); 55 | 56 | // Load it back in! 57 | jrl::Parser parser = jrl_rose::makeRoseParser(); 58 | jrl::Dataset dataset = parser.parseDataset("combined_imu.jrl"); 59 | gtsam::CombinedImuFactor::shared_ptr read_factor = 60 | boost::dynamic_pointer_cast(dataset.factorGraph()[0]); 61 | 62 | // Check to make sure they're the same 63 | EXPECT_TRUE(write_factor.equals(*read_factor)); 64 | gtsam::Pose3 x = gtsam::Pose3::Identity(); 65 | gtsam::Vector3 v(1, 2, 3); 66 | EXPECT_MATRICES_EQ(write_factor.evaluateError(x, v, x, v, b, b), read_factor->evaluateError(x, v, x, v, b, b)); 67 | } -------------------------------------------------------------------------------- /tests/test_Factors.cpp: -------------------------------------------------------------------------------- 1 | #include "gtsam/geometry/Pose3.h" 2 | #include "gtsam/inference/Symbol.h" 3 | #include "gtsam/linear/NoiseModel.h" 4 | #include "gtsam/navigation/NavState.h" 5 | #include "gtsam/nonlinear/NonlinearFactorGraph.h" 6 | #include 7 | #include 8 | 9 | #include "rose/WheelBaseline.h" 10 | #include "rose/WheelRose.h" 11 | 12 | #include "gtest/gtest.h" 13 | 14 | using gtsam::symbol_shorthand::M; 15 | using gtsam::symbol_shorthand::V; 16 | using gtsam::symbol_shorthand::X; 17 | using namespace rose; 18 | 19 | #define EXPECT_MATRICES_EQ(M_actual, M_expected) \ 20 | EXPECT_TRUE(M_actual.isApprox(M_expected, 1e-1)) << " Actual:\n" << M_actual << "\nExpected:\n" << M_expected 21 | 22 | #define EXPECT_ZERO(v) EXPECT_TRUE(v.isZero(1e-4)) << " Actual is not zero:\n" << v 23 | 24 | TEST(Factor, WheelRose) { 25 | double wl = 0.4; 26 | double wr = 0.2; 27 | double dt = 0.1; 28 | 29 | // Setup pwm 30 | auto pwm_params = PreintegratedWheelParams::MakeShared(); 31 | pwm_params->setWVCovFromWV(1e-4, 1e-4); 32 | pwm_params->wxCov = 1e-2; 33 | pwm_params->wyCov = 1e-2; 34 | pwm_params->vyCov = 1e-4; 35 | pwm_params->vzCov = 1e-4; 36 | PreintegratedWheelRose pwm(pwm_params); 37 | for (int i = 0; i < 10; ++i) { 38 | pwm.integrateMeasurements(wl, wr, dt); 39 | } 40 | 41 | gtsam::Pose3 b_T_s = gtsam::Pose3(gtsam::Rot3(0, 1, 0, 0), {1, 2, 3}); 42 | 43 | // Setup states 44 | gtsam::Pose3 x0 = gtsam::Pose3::Identity(); 45 | gtsam::Pose3 delta = pwm.predict(gtsam::Pose3::Identity()); 46 | gtsam::Pose3 x1 = b_T_s * delta * b_T_s.inverse(); 47 | gtsam::Pose3 x1_init = gtsam::Pose3(gtsam::Rot3::RzRyRx(1, 2, 3), {1, 2, 3}); 48 | 49 | WheelFactor2 factor(X(0), X(1), pwm.copy(), b_T_s); 50 | 51 | // Make graph 52 | gtsam::NonlinearFactorGraph graph; 53 | graph.addPrior(X(0), x0, gtsam::noiseModel::Isotropic::Sigma(6, 1e-5)); 54 | graph.push_back(factor); 55 | 56 | // Make Values 57 | gtsam::Values values; 58 | values.insert(X(0), x0); 59 | values.insert(X(1), x1_init); 60 | 61 | // Solve 62 | gtsam::LevenbergMarquardtParams params; 63 | gtsam::LevenbergMarquardtOptimizer optimizer(graph, values, params); 64 | gtsam::Values results = optimizer.optimize(); 65 | gtsam::Pose3 x1_final = results.at(X(1)); 66 | 67 | EXPECT_ZERO(factor.evaluateError(x0, x1_final)); 68 | } 69 | 70 | TEST(Factor, WheelFactorBaseline) { 71 | double w = 0.1; 72 | double v = 1; 73 | double dt = 0.1; 74 | 75 | // Setup pwm 76 | auto pwm_params = PreintegratedWheelParams::MakeShared(); 77 | pwm_params->setWVCovFromWV(1e-4, 1e-4); 78 | pwm_params->wxCov = 1e-2; 79 | pwm_params->wyCov = 1e-2; 80 | pwm_params->vyCov = 1e-4; 81 | pwm_params->vzCov = 1e-4; 82 | PreintegratedWheelBaseline pwm(pwm_params); 83 | for (int i = 0; i < 1; ++i) { 84 | pwm.integrateVelocities(w, v, dt); 85 | } 86 | 87 | // Setup states 88 | gtsam::Pose3 x0 = gtsam::Pose3::Identity(); 89 | gtsam::Pose3 x1 = pwm.predict(gtsam::Pose3::Identity()); 90 | gtsam::Pose3 x1_init = gtsam::Pose3(gtsam::Rot3::RzRyRx(1, 2, 3), {1, 2, 3}); 91 | 92 | WheelFactor2 factor(X(0), X(1), pwm.copy()); 93 | 94 | // Make graph 95 | gtsam::NonlinearFactorGraph graph; 96 | graph.addPrior(X(0), x0, gtsam::noiseModel::Isotropic::Sigma(6, 1e-5)); 97 | graph.push_back(factor); 98 | 99 | // Make Values 100 | gtsam::Values values; 101 | values.insert(X(0), x0); 102 | values.insert(X(1), x1_init); 103 | 104 | // Solve 105 | gtsam::LevenbergMarquardtParams params; 106 | gtsam::LevenbergMarquardtOptimizer optimizer(graph, values, params); 107 | gtsam::Values results = optimizer.optimize(); 108 | gtsam::Pose3 x1_final = results.at(X(1)); 109 | 110 | EXPECT_ZERO(factor.evaluateError(x0, x1_final)); 111 | } -------------------------------------------------------------------------------- /tests/test_IMUBias.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | #include "JRL-custom.h" 12 | #include "JRL.h" 13 | 14 | #include "gtest/gtest.h" 15 | 16 | using gtsam::symbol_shorthand::B; 17 | using gtsam::symbol_shorthand::V; 18 | using gtsam::symbol_shorthand::X; 19 | 20 | #define EXPECT_MATRICES_EQ(M_actual, M_expected) \ 21 | EXPECT_TRUE(M_actual.isApprox(M_expected, 1e-6)) << " Actual:\n" << M_actual << "\nExpected:\n" << M_expected 22 | 23 | TEST(Value, IMUBias) { 24 | // Item to save 25 | gtsam::imuBias::ConstantBias b(gtsam::Vector3::Constant(6), gtsam::Vector3::Constant(7)); 26 | 27 | // Save it 28 | gtsam::NonlinearFactorGraph graph; 29 | gtsam::Values theta; 30 | jrl::ValueTypes types; 31 | 32 | theta.insert(B(0), b); 33 | types[B(0)] = jrl_rose::IMUBiasTag; 34 | 35 | jrl::DatasetBuilder builder("test", {'a'}); 36 | builder.addEntry('a', 0, graph, {}, {}, jrl::TypedValues(theta, types)); 37 | 38 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 39 | writer.writeDataset(builder.build(), "imu_bias.jrl"); 40 | 41 | // Load it back in! 42 | jrl::Parser parser = jrl_rose::makeRoseParser(); 43 | jrl::Dataset dataset = parser.parseDataset("imu_bias.jrl"); 44 | gtsam::imuBias::ConstantBias b_read = dataset.initialization('a').at(B(0)); 45 | 46 | // Check to make sure they're the same 47 | EXPECT_MATRICES_EQ(b.vector(), b_read.vector()); 48 | } -------------------------------------------------------------------------------- /tests/test_JRL.cpp: -------------------------------------------------------------------------------- 1 | #include "gtsam/geometry/Pose3.h" 2 | #include "gtsam/linear/NoiseModel.h" 3 | #include "gtsam/nonlinear/NonlinearFactorGraph.h" 4 | #include "jrl/Dataset.h" 5 | #include "jrl/DatasetBuilder.h" 6 | 7 | #include "JRL.h" 8 | #include "rose/WheelBaseline.h" 9 | #include "rose/WheelRose.h" 10 | 11 | #include "gtest/gtest.h" 12 | 13 | using gtsam::symbol_shorthand::I; 14 | using gtsam::symbol_shorthand::M; 15 | using gtsam::symbol_shorthand::S; 16 | using gtsam::symbol_shorthand::V; 17 | using gtsam::symbol_shorthand::W; 18 | using gtsam::symbol_shorthand::X; 19 | using namespace rose; 20 | 21 | #define EXPECT_MATRICES_EQ(M_actual, M_expected) \ 22 | EXPECT_TRUE(M_actual.isApprox(M_expected, 1e-6)) << " Actual:\n" << M_actual << "\nExpected:\n" << M_expected 23 | 24 | TEST(JRL, WheelFactorBaseline) { 25 | double w = 1; 26 | double v = 1; 27 | double dt = 0.1; 28 | 29 | // Setup states 30 | gtsam::Pose3 x0 = gtsam::Pose3::Identity(); 31 | gtsam::Pose3 x1 = gtsam::Pose3(gtsam::Rot3::RzRyRx(1, 2, 3), {1, 2, 3}); 32 | 33 | // Setup factors 34 | auto pwm_params = PreintegratedWheelParams::MakeShared(); 35 | PreintegratedWheelBaseline pwm(pwm_params); 36 | pwm.integrateVelocities(w, v, dt); 37 | WheelFactor2 write_factor(X(0), X(1), pwm.copy()); 38 | 39 | // Save it 40 | gtsam::NonlinearFactorGraph graph; 41 | graph.push_back(write_factor); 42 | 43 | jrl::DatasetBuilder builder("test", {'a'}); 44 | builder.addEntry('a', 0, graph, {jrl_rose::WheelBaselineTag}); 45 | 46 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 47 | writer.writeDataset(builder.build(), "wheel_baseline.jrl"); 48 | 49 | // Load it back in! 50 | jrl::Parser parser = jrl_rose::makeRoseParser(); 51 | jrl::Dataset dataset = parser.parseDataset("wheel_baseline.jrl"); 52 | WheelFactor2::shared_ptr read_factor = boost::dynamic_pointer_cast(dataset.factorGraph('a')[0]); 53 | 54 | EXPECT_MATRICES_EQ(write_factor.evaluateError(x0, x1), read_factor->evaluateError(x0, x1)); 55 | } 56 | 57 | TEST(JRL, WheelRose) { 58 | double wl = 1; 59 | double wr = 1; 60 | double dt = 0.1; 61 | 62 | // Setup states 63 | gtsam::Pose3 x0 = gtsam::Pose3::Identity(); 64 | gtsam::Pose3 x1 = gtsam::Pose3(gtsam::Rot3::RzRyRx(1, 2, 3), {1, 2, 3}); 65 | 66 | // Setup factors 67 | auto pwm_params = PreintegratedWheelParams::MakeShared(); 68 | PreintegratedWheelRose pwm(pwm_params); 69 | pwm.integrateMeasurements(wl, wr, dt); 70 | WheelFactor2 write_factor(X(0), X(1), pwm.copy()); 71 | 72 | // Save it 73 | gtsam::NonlinearFactorGraph graph; 74 | graph.push_back(write_factor); 75 | 76 | jrl::DatasetBuilder builder("test", {'a'}); 77 | builder.addEntry('a', 0, graph, {jrl_rose::WheelRoseTag}); 78 | 79 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 80 | writer.writeDataset(builder.build(), "wheel_rose.jrl"); 81 | 82 | // Load it back in! 83 | jrl::Parser parser = jrl_rose::makeRoseParser(); 84 | jrl::Dataset dataset = parser.parseDataset("wheel_rose.jrl"); 85 | WheelFactor2::shared_ptr read_factor = boost::dynamic_pointer_cast(dataset.factorGraph('a')[0]); 86 | 87 | EXPECT_MATRICES_EQ(write_factor.evaluateError(x0, x1), read_factor->evaluateError(x0, x1)); 88 | } 89 | 90 | TEST(JRL, WheelRose3) { 91 | double wl = 1; 92 | double wr = 1; 93 | double dt = 0.1; 94 | 95 | // Setup states 96 | gtsam::Pose3 x0 = gtsam::Pose3::Identity(); 97 | gtsam::Pose3 x1 = gtsam::Pose3(gtsam::Rot3::RzRyRx(1, 2, 3), {1, 2, 3}); 98 | gtsam::Pose3 b_T_w = gtsam::Pose3(gtsam::Rot3::RzRyRx(4, 5, 6), {4, 5, 6}); 99 | gtsam::Vector2 slip = gtsam::Vector2::Ones(); 100 | 101 | // Setup factors 102 | auto pwm_params = PreintegratedWheelParams::MakeShared(); 103 | PreintegratedWheelRose pwm(pwm_params); 104 | pwm.integrateMeasurements(wl, wr, dt); 105 | WheelFactor3 write_factor(X(0), X(1), W(0), pwm.copy(), b_T_w); 106 | 107 | // Save it 108 | gtsam::NonlinearFactorGraph graph; 109 | graph.push_back(write_factor); 110 | 111 | jrl::DatasetBuilder builder("test", {'a'}); 112 | builder.addEntry('a', 0, graph, {jrl_rose::WheelRoseSlipTag}); 113 | 114 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 115 | writer.writeDataset(builder.build(), "wheel_rose_slip.jrl"); 116 | 117 | // Load it back in! 118 | jrl::Parser parser = jrl_rose::makeRoseParser(); 119 | jrl::Dataset dataset = parser.parseDataset("wheel_rose_slip.jrl"); 120 | WheelFactor3::shared_ptr read_factor = boost::dynamic_pointer_cast(dataset.factorGraph('a')[0]); 121 | 122 | EXPECT_MATRICES_EQ(write_factor.evaluateError(x0, x1, slip), read_factor->evaluateError(x0, x1, slip)); 123 | } 124 | 125 | TEST(JRL, WheelRose4) { 126 | double wl = 1; 127 | double wr = 1; 128 | double dt = 0.1; 129 | 130 | // Setup states 131 | gtsam::Pose3 x0 = gtsam::Pose3::Identity(); 132 | gtsam::Pose3 x1 = gtsam::Pose3(gtsam::Rot3::RzRyRx(1, 2, 3), {1, 2, 3}); 133 | gtsam::Pose3 b_T_w = gtsam::Pose3(gtsam::Rot3::RzRyRx(4, 5, 6), {4, 5, 6}); 134 | gtsam::Vector3 intr = gtsam::Vector3::Ones(); 135 | 136 | // Setup factors 137 | auto pwm_params = PreintegratedWheelParams::MakeShared(); 138 | PreintegratedWheelRose pwm(pwm_params); 139 | pwm.integrateMeasurements(wl, wr, dt); 140 | WheelFactor4 write_factor(X(0), I(0), X(1), I(1), pwm.copy(), b_T_w); 141 | 142 | // Save it 143 | gtsam::NonlinearFactorGraph graph; 144 | graph.push_back(write_factor); 145 | 146 | jrl::DatasetBuilder builder("test", {'a'}); 147 | builder.addEntry('a', 0, graph, {jrl_rose::WheelRoseIntrTag}); 148 | 149 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 150 | writer.writeDataset(builder.build(), "wheel_rose_intr.jrl"); 151 | 152 | // Load it back in! 153 | jrl::Parser parser = jrl_rose::makeRoseParser(); 154 | jrl::Dataset dataset = parser.parseDataset("wheel_rose_intr.jrl"); 155 | WheelFactor4::shared_ptr read_factor = boost::dynamic_pointer_cast(dataset.factorGraph('a')[0]); 156 | EXPECT_MATRICES_EQ(write_factor.evaluateError(x0, intr, x1, intr), read_factor->evaluateError(x0, intr, x1, intr)); 157 | } 158 | 159 | TEST(JRL, WheelRose5) { 160 | double wl = 1; 161 | double wr = 1; 162 | double dt = 0.1; 163 | 164 | // Setup states 165 | gtsam::Pose3 x0 = gtsam::Pose3::Identity(); 166 | gtsam::Pose3 x1 = gtsam::Pose3(gtsam::Rot3::RzRyRx(1, 2, 3), {1, 2, 3}); 167 | gtsam::Pose3 b_T_w = gtsam::Pose3(gtsam::Rot3::RzRyRx(4, 5, 6), {4, 5, 6}); 168 | gtsam::Vector3 intr = gtsam::Vector3::Ones(); 169 | gtsam::Vector2 slip = gtsam::Vector2::Zero(); 170 | 171 | // Setup factors 172 | auto pwm_params = PreintegratedWheelParams::MakeShared(); 173 | PreintegratedWheelRose pwm(pwm_params); 174 | pwm.integrateMeasurements(wl, wr, dt); 175 | WheelFactor5 write_factor(X(0), I(0), X(1), I(1), S(0), pwm.copy(), b_T_w); 176 | 177 | // Save it 178 | gtsam::NonlinearFactorGraph graph; 179 | graph.push_back(write_factor); 180 | 181 | jrl::DatasetBuilder builder("test", {'a'}); 182 | builder.addEntry('a', 0, graph, {jrl_rose::WheelRoseIntrSlipTag}); 183 | 184 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 185 | writer.writeDataset(builder.build(), "wheel_rose_intr_slip.jrl"); 186 | 187 | // Load it back in! 188 | jrl::Parser parser = jrl_rose::makeRoseParser(); 189 | jrl::Dataset dataset = parser.parseDataset("wheel_rose_intr_slip.jrl"); 190 | WheelFactor5::shared_ptr read_factor = boost::dynamic_pointer_cast(dataset.factorGraph('a')[0]); 191 | EXPECT_MATRICES_EQ(write_factor.evaluateError(x0, intr, x1, intr, slip), 192 | read_factor->evaluateError(x0, intr, x1, intr, slip)); 193 | } 194 | 195 | TEST(JRL, PlanarPriorFactor) { 196 | // make factor 197 | gtsam::Pose3 b_T_s = gtsam::Pose3(gtsam::Rot3(0, 1, 0, 0), {1, 2, 3}); 198 | gtsam::Pose3 x0 = gtsam::Pose3(gtsam::Rot3::RzRyRx(1, 2, 3), {1, 2, 3}); 199 | PlanarPriorFactor write_factor(X(0), gtsam::I_2x2, b_T_s); 200 | 201 | // Save it 202 | gtsam::NonlinearFactorGraph graph; 203 | graph.push_back(write_factor); 204 | 205 | jrl::DatasetBuilder builder("test", {'a'}); 206 | builder.addEntry('a', 0, graph, {jrl_rose::PlanarPriorTag}); 207 | 208 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 209 | writer.writeDataset(builder.build(), "planar_prior.jrl"); 210 | 211 | // Load it back in! 212 | jrl::Parser parser = jrl_rose::makeRoseParser(); 213 | jrl::Dataset dataset = parser.parseDataset("planar_prior.jrl"); 214 | PlanarPriorFactor::shared_ptr read_factor = 215 | boost::dynamic_pointer_cast(dataset.factorGraph('a')[0]); 216 | 217 | EXPECT_MATRICES_EQ(write_factor.evaluateError(x0), read_factor->evaluateError(x0)); 218 | } 219 | 220 | TEST(JRL, ZPriorFactor) { 221 | // make factor 222 | gtsam::Pose3 b_T_s = gtsam::Pose3(gtsam::Rot3(0, 1, 0, 0), {1, 2, 3}); 223 | gtsam::Pose3 x0 = gtsam::Pose3(gtsam::Rot3::RzRyRx(1, 2, 3), {1, 2, 3}); 224 | ZPriorFactor write_factor(X(0), gtsam::I_1x1, b_T_s); 225 | 226 | // Save it 227 | gtsam::NonlinearFactorGraph graph; 228 | graph.push_back(write_factor); 229 | 230 | jrl::DatasetBuilder builder("test", {'a'}); 231 | builder.addEntry('a', 0, graph, {jrl_rose::ZPriorTag}); 232 | 233 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 234 | writer.writeDataset(builder.build(), "z_prior.jrl"); 235 | 236 | // Load it back in! 237 | jrl::Parser parser = jrl_rose::makeRoseParser(); 238 | jrl::Dataset dataset = parser.parseDataset("z_prior.jrl"); 239 | ZPriorFactor::shared_ptr read_factor = boost::dynamic_pointer_cast(dataset.factorGraph('a')[0]); 240 | 241 | EXPECT_MATRICES_EQ(write_factor.evaluateError(x0), read_factor->evaluateError(x0)); 242 | } -------------------------------------------------------------------------------- /tests/test_StereoFactor.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | #include "JRL-custom.h" 11 | #include "JRL.h" 12 | 13 | #include "gtest/gtest.h" 14 | 15 | using gtsam::symbol_shorthand::L; 16 | using gtsam::symbol_shorthand::X; 17 | 18 | #define EXPECT_MATRICES_EQ(M_actual, M_expected) \ 19 | EXPECT_TRUE(M_actual.isApprox(M_expected, 1e-6)) << " Actual:\n" << M_actual << "\nExpected:\n" << M_expected 20 | 21 | typedef typename gtsam::GenericStereoFactor StereoFactor; 22 | 23 | TEST(Factor, StereoFactor) { 24 | // Make everything for the stereo factor 25 | gtsam::Cal3_S2Stereo::shared_ptr m_stereoCalibration = 26 | boost::make_shared(6, 8, 0.0, 3, 4, 0.1); 27 | auto m_stereoNoiseModel = gtsam::noiseModel::Isotropic::Sigma(3, 1); 28 | gtsam::Symbol landmarkKey = L(0); 29 | gtsam::Symbol poseKey = X(0); 30 | gtsam::StereoCamera camera(gtsam::Pose3(), m_stereoCalibration); 31 | gtsam::StereoPoint2 stereoPoint(1, 2, 3); 32 | gtsam::Point3 estimate = camera.backproject(stereoPoint); 33 | 34 | StereoFactor write_factor(stereoPoint, m_stereoNoiseModel, poseKey, landmarkKey, m_stereoCalibration); 35 | 36 | // Save it 37 | gtsam::NonlinearFactorGraph graph; 38 | graph.push_back(write_factor); 39 | 40 | jrl::DatasetBuilder builder("test", {'a'}); 41 | builder.addEntry('a', 0, graph, {jrl_rose::StereoFactorPose3Point3Tag}); 42 | 43 | jrl::Writer writer = jrl_rose::makeRoseWriter(); 44 | writer.writeDataset(builder.build(), "stereo.jrl"); 45 | 46 | // Load it back in! 47 | jrl::Parser parser = jrl_rose::makeRoseParser(); 48 | jrl::Dataset dataset = parser.parseDataset("stereo.jrl"); 49 | StereoFactor::shared_ptr read_factor = boost::dynamic_pointer_cast(dataset.factorGraph()[0]); 50 | 51 | gtsam::Pose3 x0 = gtsam::Pose3::Identity(); 52 | gtsam::Point3 l0(3, 2, 1); 53 | EXPECT_TRUE(write_factor.equals(*read_factor)); 54 | EXPECT_MATRICES_EQ(write_factor.evaluateError(x0, l0), read_factor->evaluateError(x0, l0)); 55 | } --------------------------------------------------------------------------------