├── .gitignore ├── LICENSE ├── README.md ├── curves ├── .gitignore ├── CMakeLists.txt ├── doc │ └── doxygen │ │ ├── CMakeLists.txt │ │ ├── doxygen.config.in │ │ └── mainpage.dox ├── etc │ └── notes.md ├── include │ └── curves │ │ ├── CubicHermiteE3Curve.hpp │ │ ├── CubicHermiteE3Curve.hpp.gch │ │ ├── CubicHermiteSE3Curve.hpp │ │ ├── Curve.hpp │ │ ├── DiscreteSE3Curve.hpp │ │ ├── KeyGenerator.hpp │ │ ├── LinearInterpolationVectorSpaceCurve-inl.hpp │ │ ├── LinearInterpolationVectorSpaceCurve.hpp │ │ ├── LocalSupport2CoefficientManager-inl.hpp │ │ ├── LocalSupport2CoefficientManager.hpp │ │ ├── PolynomialSpline.hpp │ │ ├── PolynomialSplineContainer.hpp │ │ ├── PolynomialSplineContainer.tpp │ │ ├── PolynomialSplineScalarCurve.hpp │ │ ├── PolynomialSplineVectorSpaceCurve.hpp │ │ ├── Pose2_Expressions.hpp │ │ ├── SE2Config.hpp │ │ ├── SE2Curve.hpp │ │ ├── SE3CompositionCurve-inl.hpp │ │ ├── SE3CompositionCurve.hpp │ │ ├── SE3Config.hpp │ │ ├── SE3Curve.hpp │ │ ├── SE3CurveFactory.hpp │ │ ├── SamplingPolicy.hpp │ │ ├── ScalarCurveConfig.hpp │ │ ├── SemiDiscreteSE3Curve.hpp │ │ ├── SlerpSE2Curve.hpp │ │ ├── SlerpSE3Curve.hpp │ │ ├── VectorSpaceConfig.hpp │ │ ├── VectorSpaceCurve.hpp │ │ ├── helpers.hpp │ │ ├── polynomial_splines.hpp │ │ ├── polynomial_splines_containers.hpp │ │ └── polynomial_splines_traits.hpp ├── matlab │ └── readCubicHermiteSE3Curve.m ├── package.xml ├── src │ ├── CubicHermiteE3Curve.cpp │ ├── CubicHermiteSE3Curve.cpp │ ├── DiscreteSE3Curve.cpp │ ├── KeyGenerator.cpp │ ├── SE2Curve.cpp │ ├── SE3Curve.cpp │ ├── SE3CurveFactory.cpp │ ├── SemiDiscreteSE3Curve.cpp │ ├── SlerpSE2Curve.cpp │ ├── SlerpSE3Curve.cpp │ ├── helpers.cpp │ └── polynomial_splines_traits.cpp └── test │ ├── .gitignore │ ├── CubicHermiteSE3CurveTest.cpp │ ├── PolynomialSplineContainerTest.cpp │ ├── PolynomialSplineQuinticScalarCurveTest.cpp │ ├── PolynomialSplineVectorSpaceCurveTest.cpp │ ├── PolynomialSplinesTest.cpp │ ├── test_Hermite.cpp │ ├── test_LocalSupport2CoefficientManager.cpp │ ├── test_SE3Coefficient.cpp │ └── test_main.cpp └── curves_ros ├── CMakeLists.txt ├── include └── curves_ros │ ├── RosJointTrajectoryInterface.hpp │ ├── RosMultiDOFJointTrajectoryInterface.hpp │ └── RosMultiDOFJointTrajectoryTranslationInterface.hpp ├── package.xml └── src ├── RosJointTrajectoryInterface.cpp ├── RosMultiDOFJointTrajectoryInterface.cpp └── RosMultiDOFJointTrajectoryTranslationInterface.cpp /.gitignore: -------------------------------------------------------------------------------- 1 | # Compiled Object files 2 | *.slo 3 | *.lo 4 | *.o 5 | *.obj 6 | 7 | # Compiled Dynamic libraries 8 | *.so 9 | *.dylib 10 | *.dll 11 | 12 | # Compiled Static libraries 13 | *.lai 14 | *.la 15 | *.a 16 | *.lib 17 | 18 | # Executables 19 | *.exe 20 | *.out 21 | *.app 22 | *~ 23 | .DS_Store 24 | .project 25 | .cproject 26 | .settings 27 | 28 | # Result files 29 | *optimized* 30 | 31 | # Python 32 | *.pydevproject 33 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Copyright (c) 2014-2017, ETH Zurich 2 | All rights reserved. 3 | 4 | Redistribution and use in source and binary forms, with or without 5 | modification, are permitted provided that the following conditions are met: 6 | 7 | * Redistributions of source code must retain the above copyright notice, this 8 | list of conditions and the following disclaimer. 9 | 10 | * Redistributions in binary form must reproduce the above copyright notice, 11 | this list of conditions and the following disclaimer in the documentation 12 | and/or other materials provided with the distribution. 13 | 14 | * Neither the name of the {organization} nor the names of its 15 | contributors may be used to endorse or promote products derived from 16 | this software without specific prior written permission. 17 | 18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 19 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 20 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 22 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 23 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 24 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 25 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 26 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 27 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 28 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Curves 2 | 3 | A library for curves generation and estimation. 4 | 5 | The source code is released under a [BSD 3-Clause license](ros_package_template/LICENSE). 6 | 7 | **Authors: Renaud Dubé, Abel Gawel, Péter Fankhauser, Dario Bellicoso, Christian Gehring, Mike Bosse, Paul Furgale, Gabriel Agamennoni** 8 | 9 | **Maintainer: Péter Fankhauser, pfankhauser@anybotics.com** 10 | 11 | ## Installation 12 | 13 | ### Installation from Packages 14 | 15 | TODO 16 | 17 | ### Building from Source 18 | 19 | #### Dependencies 20 | 21 | - [Eigen](http://eigen.tuxfamily.org) (linear algebra library) 22 | - [Kindr](https://github.com/ethz-asl/kindr.git) (kinematics library) 23 | - [Glog](https://github.com/google/glog) (logging library) 24 | 25 | sudo apt-get install libgoogle-glog-dev 26 | 27 | #### Building 28 | 29 | To build from source, clone the latest version from this repository into your catkin workspace and compile the package using 30 | 31 | cd catkin_workspace/src 32 | git clone https://github.com/ethz-asl/curves.git 33 | cd ../ 34 | catkin_make 35 | 36 | ### Unit Tests 37 | 38 | Run the unit tests with 39 | 40 | catkin_make run_tests_curves run_tests_curves 41 | 42 | ## Bugs & Feature Requests 43 | 44 | Please report bugs and request features using the [Issue Tracker](https://github.com/ethz-asl/curves/issues). 45 | -------------------------------------------------------------------------------- /curves/.gitignore: -------------------------------------------------------------------------------- 1 | # Created by .ignore support plugin (hsz.mobi) 2 | 3 | doc/html/* 4 | doc/doxygen.config -------------------------------------------------------------------------------- /curves/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.1.3) 2 | project(curves) 3 | 4 | set(CMAKE_CXX_STANDARD 11) 5 | add_compile_options(-Wall -Wextra -Wpedantic) 6 | 7 | find_package(catkin REQUIRED COMPONENTS 8 | ) 9 | 10 | find_package(Eigen3 REQUIRED) 11 | find_package(Boost REQUIRED COMPONENTS system thread) 12 | 13 | # Glog 14 | find_package(PkgConfig REQUIRED) 15 | pkg_check_modules(glog libglog REQUIRED) 16 | 17 | # Attempt to find catkinized kindr 18 | find_package(kindr QUIET) 19 | if(NOT kindr_FOUND) 20 | # Attempt to find package-based kindr 21 | pkg_check_modules(kindr kindr REQUIRED) 22 | endif() 23 | 24 | # Add Doxygen documentation 25 | add_subdirectory(doc/doxygen) 26 | 27 | catkin_package( 28 | INCLUDE_DIRS 29 | include 30 | ${EIGEN3_INCLUDE_DIR} 31 | LIBRARIES 32 | ${PROJECT_NAME} 33 | CATKIN_DEPENDS 34 | DEPENDS 35 | Boost 36 | glog 37 | kindr 38 | ) 39 | 40 | include_directories( 41 | include 42 | ${catkin_INCLUDE_DIRS} 43 | ${EIGEN3_INCLUDE_DIR} 44 | ${kindr_INCLUDE_DIRS} 45 | ) 46 | 47 | add_library(${PROJECT_NAME} 48 | src/KeyGenerator.cpp 49 | src/CubicHermiteSE3Curve.cpp 50 | src/CubicHermiteE3Curve.cpp 51 | src/SlerpSE3Curve.cpp 52 | src/SE3Curve.cpp 53 | src/polynomial_splines_traits.cpp 54 | src/helpers.cpp 55 | # src/SE2Curve.cpp 56 | # src/SlerpSE2Curve.cpp 57 | # src/DiscreteSE3Curve.cpp 58 | # src/SemiDiscreteSE3Curve.cpp 59 | # src/SE3CurveFactory.cpp 60 | ) 61 | 62 | target_link_libraries(${PROJECT_NAME} 63 | ${catkin_LIBRARIES} 64 | ${Boost_LIBRARIES} 65 | glog 66 | ) 67 | 68 | add_dependencies(${PROJECT_NAME} 69 | ${catkin_EXPORTED_TARGETS} 70 | ) 71 | 72 | catkin_add_gtest(${PROJECT_NAME}_tests 73 | test/test_main.cpp 74 | test/CubicHermiteSE3CurveTest.cpp 75 | test/PolynomialSplineContainerTest.cpp 76 | test/PolynomialSplineVectorSpaceCurveTest.cpp 77 | test/PolynomialSplineQuinticScalarCurveTest.cpp 78 | test/PolynomialSplinesTest.cpp 79 | # test/test_LocalSupport2CoefficientManager.cpp 80 | # test/test_Hermite.cpp 81 | # test/test_MITb_dataset.cpp 82 | # test/test_Pose2_Expressions.cpp 83 | # test/test_MITb_dataset_SE2.cpp 84 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/test 85 | ) 86 | 87 | target_link_libraries(${PROJECT_NAME}_tests 88 | ${PROJECT_NAME} 89 | ${catkin_LIBRARIES} 90 | glog 91 | ) 92 | 93 | install(TARGETS ${PROJECT_NAME} 94 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 95 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 96 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 97 | ) 98 | 99 | install(DIRECTORY include/${PROJECT_NAME}/ 100 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 101 | ) 102 | -------------------------------------------------------------------------------- /curves/doc/doxygen/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2013, Christian Gehring, Hannes Sommer, Paul Furgale, Remo Diethelm 2 | # All rights reserved. 3 | # 4 | # Redistribution and use in source and binary forms, with or without 5 | # modification, are permitted provided that the following conditions are met: 6 | # * Redistributions of source code must retain the above copyright 7 | # notice, this list of conditions and the following disclaimer. 8 | # * Redistributions in binary form must reproduce the above copyright 9 | # notice, this list of conditions and the following disclaimer in the 10 | # documentation and/or other materials provided with the distribution. 11 | # * Neither the name of the Autonomous Systems Lab, ETH Zurich nor the 12 | # names of its contributors may be used to endorse or promote products 13 | # derived from this software without specific prior written permission. 14 | # 15 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 16 | # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 17 | # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 18 | # DISCLAIMED. IN NO EVENT SHALL Christian Gehring, Hannes Sommer, Paul Furgale, 19 | # Remo Diethelm BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, 20 | # OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE 21 | # GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) 22 | # HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 23 | # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 24 | # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 25 | 26 | cmake_minimum_required (VERSION 2.8) 27 | 28 | #--------------------------# 29 | # Documentation 30 | 31 | 32 | 33 | find_package(Doxygen) 34 | if(DOXYGEN) 35 | set(DOCSOURCE_DIR ${PROJECT_SOURCE_DIR}/doc) 36 | set(DOXYGEN_SOURCE_DIRS "${DOXYGEN_SOURCE_DIRS} \"${CMAKE_CURRENT_SOURCE_DIR}\" ") 37 | set(DOXYGEN_SOURCE_DIRS "${DOXYGEN_SOURCE_DIRS} \"${CMAKE_CURRENT_SOURCE_DIR}/../../include/\" ") 38 | 39 | 40 | set(HTML_DIR ${PROJECT_SOURCE_DIR}/doc/html) 41 | set(DOXYGEN_QUIET YES) 42 | make_directory(${HTML_DIR}) 43 | set( HAVE_DOT YES ) 44 | 45 | configure_file(${CMAKE_CURRENT_SOURCE_DIR}/doxygen.config.in ${DOCSOURCE_DIR}/doxygen.config IMMEDIATE) 46 | 47 | add_custom_target(doc ${DOXYGEN} ${DOCSOURCE_DIR}/doxygen.config) 48 | else(DOXYGEN) 49 | message(STATUS "Doxygen not found") 50 | endif(DOXYGEN) 51 | 52 | #-------------------------# -------------------------------------------------------------------------------- /curves/doc/doxygen/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | 3 | \mainpage Curves for estimation 4 | 5 | This is the mainpage description for the "Curves for estimation" project as found in 6 | mainpage.dox. 7 | 8 | */ 9 | 10 | 11 | -------------------------------------------------------------------------------- /curves/etc/notes.md: -------------------------------------------------------------------------------- 1 | # Implementation Notes 2 | 3 | * Should the *extend* methods and the *fit* methods return keys? Coefficients? 4 | 5 | # Dealing with Values 6 | 7 | * The big question, How to make this non-intrusive? 8 | * [This interface](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/base/DerivedValue.h?at=develop) seems tricky 9 | , Specifically: 10 | * Supporting the boost::singleton_pool sounds like a tough job. 11 | * Figuring out a way to interface GTSAM without relying on GTSAM... 12 | * We have to make sure evaluators can be called functionally. 13 | * Making coefficients be Eigen::VectorXd would be great. 14 | 15 | ## What are the requirements 16 | * The Curve should 17 | * Have a unique key for each coefficient vector (Somebody has to explain how this works). This means it has a [Values](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/nonlinear/Values.h?at=develop) container for the whole spline 18 | * Return the vector of coefficients for each time 19 | * Return an evaluator for each time 20 | * **[Advanced]** Return evaluators that can move around in time (my gut tells me that if we get the Evaluator interface right, this can be added on without too much pain. 21 | * The Evaluator should 22 | * implement something like `virtual Vector evaluate(const Values& x, boost::optional&> H = boost::none) const;` to get the value and derivatives. This would be called from the Factor implementation. (still seems like this will be difficult). 23 | 24 | # Dealing with Factors and Evaluators 25 | 26 | Next: Look at the between factor to think about the implementation of the Evaluator. 27 | 28 | From `NoiseModelFactor` 29 | 30 | ```c++ 31 | /** 32 | * Error function *without* the NoiseModel, \f$ z-h(x) \f$. 33 | * Override this method to finish implementing an N-way factor. 34 | * If any of the optional Matrix reference arguments are specified, it should compute 35 | * both the function evaluation and its derivative(s) in X1 (and/or X2, X3...). 36 | */ 37 | virtual Vector unwhitenedError(const Values& x, boost::optional< std::vector< Matrix > &> H = boost::none) const = 0; 38 | ``` 39 | So, Values is an key/Value map. The Factor decides the ordering that the Jacobians are returned. 40 | # Curve 41 | * `Curve::grow()` Needs to return a list of coefficients that are new 42 | * `Curve::shrink()` needs to return a list of coefficients removed 43 | # Open Questions 44 | * Where do the keys live? 45 | * How do we make factors that change the keys they are hooked up to dynamically (per iteration, for example)? 46 | # Links 47 | * [Documentation](https://research.cc.gatech.edu/borg/sites/edu.borg/files/downloads/gtsam.pdf) 48 | ## Factors 49 | * [Factor](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/inference/Factor.h?at=develop) 50 | * [GaussianFactor](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/linear/GaussianFactor.h?at=develop) 51 | * [NonlinearFactor](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/nonlinear/NonlinearFactor.h?at=develop) 52 | * [NoiseModelFactor](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/nonlinear/NonlinearFactor.h?at=develop) 53 | ## Values 54 | * [Values](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/nonlinear/Values.h?at=develop) 55 | * [Value](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/base/Value.h?at=develop) -- This has good documentation for writing a class derived from Value without using DerivedValue. However, this documentation looks incomplete. 56 | * [Derived Value](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/base/DerivedValue.h?at=develop) 57 | * [LieVector](https://bitbucket.org/gtborg/gtsam/src/bcab483574f2bd636dcd8171cf1b62fdfe15b6d0/gtsam/base/LieVector.h?at=develop) 58 | # Scratch 59 | What about: 60 | 61 | Coefficient 62 | | 63 | -- MyCoefficientType 64 | | 65 | -- MyGtsamCoefficientType : public MyCoefficientType, public DerivedValue 66 | 67 | * Coefficient implements equals, dim, retract, local coordinates, print... 68 | * MyGtsamCoefficientType also implements these but forwards the implementation to the parent. 69 | 70 | Is it better if we make it rely on GTSAM directly? 71 | -- getCoefficients< CoefficientType* > 72 | -------------------------------------------------------------------------------- /curves/include/curves/CubicHermiteE3Curve.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * CubicHermiteE3Curve.hpp 3 | * 4 | * Created on: Aug, 2016 5 | * Author: Christian Gehring 6 | * Institute: ETH Zurich, Autonomous Systems Lab 7 | */ 8 | 9 | #pragma once 10 | 11 | #include 12 | 13 | #include "curves/LocalSupport2CoefficientManager.hpp" 14 | #include "curves/SE3Curve.hpp" 15 | 16 | struct HermiteE3Knot { 17 | typedef Eigen::Vector3d Position; 18 | typedef Eigen::Vector3d Velocity; 19 | typedef Eigen::Vector3d Acceleration; 20 | 21 | public: 22 | HermiteE3Knot(): HermiteE3Knot(Position::Zero(), Velocity::Zero()) {} 23 | HermiteE3Knot(const Position& position, 24 | const Velocity& velocity) : position_(position), velocity_(velocity){} 25 | virtual ~HermiteE3Knot(){} 26 | 27 | Position getPosition() const { 28 | return position_; 29 | } 30 | 31 | Velocity getVelocity() const { 32 | return velocity_; 33 | } 34 | 35 | void setPosition(const Position& position) { 36 | position_ = position; 37 | } 38 | 39 | void setVelocity(const Velocity& velocity) { 40 | velocity_ = velocity; 41 | } 42 | 43 | private: 44 | Position position_; 45 | Velocity velocity_; 46 | }; 47 | 48 | namespace curves { 49 | 50 | /// Implements the Cubic Hermite curve class. See KimKimShin paper. 51 | /// The Hermite interpolation function is defined, with the respective Jacobians regarding A and B: 52 | // 53 | /// Translations: 54 | /// Equations for the unit interval: 55 | // Let t_W_A, t_W_B denote the control point values (=translations) and W_v_W_A, W_v_W_B 56 | // the control derivatives (=velocities in R³) at the interval's boundaries. 57 | // Then (b == beta): 58 | // p0 = t_W_A, p1 = t_W_B, p2 = W_v_W_A, p3 = W_v_W_B 59 | // b0 = 2t³-3t²+1, b_1 = -2t³+3t², b_2 = t³-2t²+t, b_3 = t³-t² 60 | // Spline equation: 61 | // p(t) = p0 * b0 + p1 * b1 + p2 * b2 + p3 + b3 62 | 63 | class CubicHermiteE3Curve { 64 | public: 65 | typedef HermiteE3Knot Coefficient; 66 | typedef LocalSupport2CoefficientManager::CoefficientIter CoefficientIter; 67 | typedef HermiteE3Knot::Position ValueType; 68 | typedef HermiteE3Knot::Velocity DerivativeType; 69 | typedef HermiteE3Knot::Acceleration Acceleration; 70 | public: 71 | CubicHermiteE3Curve(); 72 | virtual ~CubicHermiteE3Curve(); 73 | 74 | /// Print the value of the coefficient, for debugging and unit tests 75 | virtual void print(const std::string& str = "") const; 76 | 77 | virtual bool writeEvalToFile(const std::string& filename, int nSamples) const; 78 | 79 | /// The first valid time for the curve. 80 | virtual Time getMinTime() const; 81 | 82 | /// The one past the last valid time for the curve. 83 | virtual Time getMaxTime() const; 84 | 85 | bool isEmpty() const; 86 | 87 | // return number of coefficients curve is composed of 88 | int size() const; 89 | 90 | /// \brief calculate the slope between 2 coefficients 91 | DerivativeType calculateSlope(const Time& timeA, 92 | const Time& timeB, 93 | const ValueType& coeffA, 94 | const ValueType& coeffB) const; 95 | 96 | /// Extend the curve so that it can be evaluated at these times. 97 | /// Try to make the curve fit to the values. 98 | /// Note: Assumes that extend times strictly increase the curve time 99 | virtual void extend(const std::vector