| Namespaces | |
| uuid | |
| Classes | |
| class | AsyncMotionModel | 
| A motion model base class that provides node handles and a private callback queue.  More... | |
| class | AsyncPublisher | 
| A publisher base class that provides node handles attached to an internal callback queue serviced by a local thread (or threads) using a spinner.  More... | |
| class | AsyncSensorModel | 
| A sensor model base class that provides node handles and a private callback queue.  More... | |
| class | AutoDiffLocalParameterization | 
| Create a local parameterization with the Jacobians computed via automatic differentiation.  More... | |
| class | CallbackWrapper | 
| Object that wraps a generic function call so that it may be inserted into a ROS callback queue.  More... | |
| class | Constraint | 
| The Constraint interface definition.  More... | |
| class | DelayedThrottleFilter | 
| ROS console filter that prints messages with ROS_*_DELAYED_THROTTLE and allows to reset the last time the message was print, so the delayed and throttle conditions are computed from the initial state again.  More... | |
| class | Graph | 
| This is an interface definition describing the collection of constraints and variables that form the factor graph, a graphical model of a nonlinear least-squares problem.  More... | |
| class | GraphDeserializer | 
| Deserialize a graph.  More... | |
| class | LocalParameterization | 
| The LocalParameterization interface definition.  More... | |
| class | Loss | 
| The Loss function interface definition.  More... | |
| class | LossLoader | 
| Load a loss function using pluginlib::ClassLoader.  More... | |
| class | MessageBuffer | 
| A utility class that maintains a history of received messages, and allows a range of messages to be easily queried by timestamp.  More... | |
| class | MessageBufferStreamSink | 
| A Boost IOStreams sink device designed to write bytes directly from a ROS message byte array ('uint8[]')  More... | |
| class | MessageBufferStreamSource | 
| A Boost IOStreams source device designed to read bytes directly from a ROS message byte array ('uint8[]')  More... | |
| class | MotionModel | 
| The interface definition for motion model plugins in the fuse ecosystem.  More... | |
| class | Publisher | 
| The interface class for publisher plugins in the fuse ecosystem.  More... | |
| class | SensorModel | 
| The interface definition for sensor model plugins in the fuse ecosystem.  More... | |
| class | ThrottledCallback | 
| A throttled callback that encapsulates the logic to throttle a callback so it is only called after a given period in seconds (or more). The dropped calls can optionally be received in a dropped callback, that could be used to count the number of calls dropped.  More... | |
| class | TimestampManager | 
| A utility class that manages the set of timestamps that have been used to generate motion model constraints.  More... | |
| class | Transaction | 
| A transaction is a group of variable and constraint additions and subtractions that should all be processed at the same time.  More... | |
| class | TransactionDeserializer | 
| Deserialize a Transaction.  More... | |
| class | Variable | 
| The Variable interface definition.  More... | |
| Typedefs | |
| using | BinaryInputArchive = boost::archive::binary_iarchive | 
| using | BinaryOutputArchive = boost::archive::binary_oarchive | 
| template<typename Scalar , int RowsAtCompileTime, int ColsAtCompileTime> | |
| using | Matrix = Eigen::Matrix< Scalar, RowsAtCompileTime, ColsAtCompileTime, Eigen::RowMajor > | 
| using | Matrix1d = Eigen::Matrix< double, 1, 1, Eigen::RowMajor > | 
| using | Matrix2d = Eigen::Matrix< double, 2, 2, Eigen::RowMajor > | 
| using | Matrix3d = Eigen::Matrix< double, 3, 3, Eigen::RowMajor > | 
| using | Matrix4d = Eigen::Matrix< double, 4, 4, Eigen::RowMajor > | 
| using | Matrix5d = Eigen::Matrix< double, 5, 5, Eigen::RowMajor > | 
| using | Matrix6d = Eigen::Matrix< double, 6, 6, Eigen::RowMajor > | 
| using | Matrix7d = Eigen::Matrix< double, 7, 7, Eigen::RowMajor > | 
| using | Matrix8d = Eigen::Matrix< double, 8, 8, Eigen::RowMajor > | 
| using | Matrix9d = Eigen::Matrix< double, 9, 9, Eigen::RowMajor > | 
| using | MatrixXd = Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > | 
| using | TextInputArchive = boost::archive::text_iarchive | 
| using | TextOutputArchive = boost::archive::text_oarchive | 
| template<class M > | |
| using | ThrottledMessageCallback = ThrottledCallback< std::function< void(const typename M::ConstPtr &)> > | 
| Throttled callback for ROS messages.  More... | |
| using | TransactionCallback = std::function< void(Transaction::SharedPtr transaction)> | 
| The signature of the callback function that will be executed for every generated transaction object.  More... | |
| using | UUID = boost::uuids::uuid | 
| using | Vector1d = Eigen::Matrix< double, 1, 1 > | 
| using | Vector2d = Eigen::Matrix< double, 2, 1 > | 
| using | Vector3d = Eigen::Matrix< double, 3, 1 > | 
| using | Vector4d = Eigen::Matrix< double, 4, 1 > | 
| using | Vector5d = Eigen::Matrix< double, 5, 1 > | 
| using | Vector6d = Eigen::Matrix< double, 6, 1 > | 
| using | Vector7d = Eigen::Matrix< double, 7, 1 > | 
| using | Vector8d = Eigen::Matrix< double, 8, 1 > | 
| using | Vector9d = Eigen::Matrix< double, 9, 1 > | 
| using | VectorXd = Eigen::Matrix< double, Eigen::Dynamic, 1 > | 
| Functions | |
| pluginlib::UniquePtr< fuse_core::Loss > | createUniqueLoss (const std::string &lookup_name) | 
| Create an unique instance of a loss function loaded with the singleton Loss loader.  More... | |
| template<int Size, typename Scalar = double> | |
| fuse_core::Matrix< Scalar, Size, Size > | getCovarianceDiagonalParam (const ros::NodeHandle &node_handle, const std::string ¶meter_name, Scalar default_value) | 
| Helper function that loads a covariance matrix diagonal vector from the parameter server and checks the size and the values are invalid, i.e. they are positive.  More... | |
| template<class T > | |
| T | getParam (const ros::NodeHandle &node_handle, const std::string ¶meter_name, const T &default_value) | 
| Helper function that loads a Ceres Option (e.g. ceres::LinearSolverType) value from the parameter server.  More... | |
| template<typename T > | |
| void | getParamRequired (const ros::NodeHandle &nh, const std::string &key, T &value) | 
| Utility method for handling required ROS params.  More... | |
| template<typename T > | |
| static T | getPitch (const T w, const T x, const T y, const T z) | 
| Returns the Euler pitch angle from a quaternion.  More... | |
| void | getPositiveParam (const ros::NodeHandle &node_handle, const std::string ¶meter_name, ros::Duration &default_value, const bool strict=true) | 
| Helper function that loads positive duration values from the parameter server.  More... | |
| template<typename T , typename = std::enable_if_t<std::is_integral<T>::value || std::is_floating_point<T>::value>> | |
| void | getPositiveParam (const ros::NodeHandle &node_handle, const std::string ¶meter_name, T &default_value, const bool strict=true) | 
| Helper function that loads positive integral or floating point values from the parameter server.  More... | |
| template<typename T > | |
| static T | getRoll (const T w, const T x, const T y, const T z) | 
| Returns the Euler roll angle from a quaternion.  More... | |
| template<typename T > | |
| static T | getYaw (const T w, const T x, const T y, const T z) | 
| Returns the Euler yaw angle from a quaternion.  More... | |
| template<typename Derived > | |
| bool | isPositiveDefinite (const Eigen::DenseBase< Derived > &m) | 
| Check if a matrix is Positive Definite (PD), i.e. all eigenvalues are > 0.0.  More... | |
| template<typename Derived > | |
| bool | isSymmetric (const Eigen::DenseBase< Derived > &m, const typename Eigen::DenseBase< Derived >::RealScalar precision=Eigen::NumTraits< typename Eigen::DenseBase< Derived >::Scalar >::dummy_precision()) | 
| Check if a matrix is symmetric.  More... | |
| void | loadCovarianceOptionsFromROS (const ros::NodeHandle &nh, ceres::Covariance::Options &covariance_options) | 
| Populate a ceres::Covariance::Options object with information from the parameter server.  More... | |
| fuse_core::Loss::SharedPtr | loadLossConfig (const ros::NodeHandle &nh, const std::string &name) | 
| Utility method to load a loss configuration.  More... | |
| void | loadProblemOptionsFromROS (const ros::NodeHandle &nh, ceres::Problem::Options &problem_options) | 
| Populate a ceres::Problem::Options object with information from the parameter server.  More... | |
| void | loadSolverOptionsFromROS (const ros::NodeHandle &nh, ceres::Solver::Options &solver_options) | 
| Populate a ceres::Solver::Options object with information from the parameter server.  More... | |
| std::ostream & | operator<< (std::ostream &stream, const Constraint &constraint) | 
| std::ostream & | operator<< (std::ostream &stream, const Graph &graph) | 
| std::ostream & | operator<< (std::ostream &stream, const Loss &loss) | 
| std::ostream & | operator<< (std::ostream &stream, const Transaction &transaction) | 
| std::ostream & | operator<< (std::ostream &stream, const Variable &variable) | 
| template<typename T > | |
| Eigen::Matrix< T, 2, 2, Eigen::RowMajor > | rotationMatrix2D (const T angle) | 
| Create an 2x2 rotation matrix from an angle.  More... | |
| void | serializeGraph (const fuse_core::Graph &graph, fuse_msgs::SerializedGraph &msg) | 
| Serialize a graph into a message.  More... | |
| void | serializeTransaction (const fuse_core::Transaction &transaction, fuse_msgs::SerializedTransaction &msg) | 
| Serialize a transaction into a message.  More... | |
| template<typename Derived > | |
| std::string | to_string (const Eigen::DenseBase< Derived > &m, const int precision=4) | 
| Serialize a matrix into an std::string using this format:  More... | |
| template<typename T > | |
| T | wrapAngle2D (const T &angle) | 
| Wrap a 2D angle to the standard (-Pi, +Pi] range.  More... | |
| template<typename T > | |
| void | wrapAngle2D (T &angle) | 
| Wrap a 2D angle to the standard [-Pi, +Pi) range.  More... | |
| using fuse_core::BinaryInputArchive = typedef boost::archive::binary_iarchive | 
Definition at line 60 of file serialization.h.
| using fuse_core::BinaryOutputArchive = typedef boost::archive::binary_oarchive | 
Definition at line 61 of file serialization.h.
| using fuse_core::Matrix = typedef Eigen::Matrix<Scalar, RowsAtCompileTime, ColsAtCompileTime, Eigen::RowMajor> | 
| using fuse_core::Matrix1d = typedef Eigen::Matrix<double, 1, 1, Eigen::RowMajor> | 
| using fuse_core::Matrix2d = typedef Eigen::Matrix<double, 2, 2, Eigen::RowMajor> | 
| using fuse_core::Matrix3d = typedef Eigen::Matrix<double, 3, 3, Eigen::RowMajor> | 
| using fuse_core::Matrix4d = typedef Eigen::Matrix<double, 4, 4, Eigen::RowMajor> | 
| using fuse_core::Matrix5d = typedef Eigen::Matrix<double, 5, 5, Eigen::RowMajor> | 
| using fuse_core::Matrix6d = typedef Eigen::Matrix<double, 6, 6, Eigen::RowMajor> | 
| using fuse_core::Matrix7d = typedef Eigen::Matrix<double, 7, 7, Eigen::RowMajor> | 
| using fuse_core::Matrix8d = typedef Eigen::Matrix<double, 8, 8, Eigen::RowMajor> | 
| using fuse_core::Matrix9d = typedef Eigen::Matrix<double, 9, 9, Eigen::RowMajor> | 
| using fuse_core::MatrixXd = typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> | 
| using fuse_core::TextInputArchive = typedef boost::archive::text_iarchive | 
Definition at line 62 of file serialization.h.
| using fuse_core::TextOutputArchive = typedef boost::archive::text_oarchive | 
Definition at line 63 of file serialization.h.
| using fuse_core::ThrottledMessageCallback = typedef ThrottledCallback<std::function<void(const typename M::ConstPtr&)> > | 
Throttled callback for ROS messages.
| M | The ROS message type, which should have the M::ConstPtr nested type | 
Definition at line 208 of file throttled_callback.h.
| using fuse_core::TransactionCallback = typedef std::function<void(Transaction::SharedPtr transaction)> | 
The signature of the callback function that will be executed for every generated transaction object.
Definition at line 51 of file sensor_model.h.
| using fuse_core::UUID = typedef boost::uuids::uuid | 
| using fuse_core::Vector1d = typedef Eigen::Matrix<double, 1, 1> | 
| using fuse_core::Vector2d = typedef Eigen::Matrix<double, 2, 1> | 
| using fuse_core::Vector3d = typedef Eigen::Matrix<double, 3, 1> | 
| using fuse_core::Vector4d = typedef Eigen::Matrix<double, 4, 1> | 
| using fuse_core::Vector5d = typedef Eigen::Matrix<double, 5, 1> | 
| using fuse_core::Vector6d = typedef Eigen::Matrix<double, 6, 1> | 
| using fuse_core::Vector7d = typedef Eigen::Matrix<double, 7, 1> | 
| using fuse_core::Vector8d = typedef Eigen::Matrix<double, 8, 1> | 
| using fuse_core::Vector9d = typedef Eigen::Matrix<double, 9, 1> | 
| using fuse_core::VectorXd = typedef Eigen::Matrix<double, Eigen::Dynamic, 1> | 
| 
 | inline | 
Create an unique instance of a loss function loaded with the singleton Loss loader.
| [in] | lookup_name | Loss function lookup name | 
Definition at line 103 of file loss_loader.h.
| fuse_core::Matrix<Scalar, Size, Size> fuse_core::getCovarianceDiagonalParam | ( | const ros::NodeHandle & | node_handle, | 
| const std::string & | parameter_name, | ||
| Scalar | default_value | ||
| ) | 
Helper function that loads a covariance matrix diagonal vector from the parameter server and checks the size and the values are invalid, i.e. they are positive.
| Scalar | - A scalar type, defaults to double | 
| Size | - An int size that specifies the expected size of the covariance matrix (rows and columns) | 
| [in] | node_handle | - The node handle used to load the parameter | 
| [in] | parameter_name | - The parameter name to load | 
| [in] | default_value | - A default value to use for all the diagonal elements if the provided parameter name does not exist | 
Definition at line 126 of file parameter.h.
| T fuse_core::getParam | ( | const ros::NodeHandle & | node_handle, | 
| const std::string & | parameter_name, | ||
| const T & | default_value | ||
| ) | 
Helper function that loads a Ceres Option (e.g. ceres::LinearSolverType) value from the parameter server.
String definitions for all Ceres options.
| [in] | node_handle | - The node handle used to load the parameter | 
| [in] | parameter_name | - The parameter name to load | 
| [in] | default_value | - A default value to use if the provided parameter name does not exist | 
Definition at line 194 of file ceres_options.h.
| void fuse_core::getParamRequired | ( | const ros::NodeHandle & | nh, | 
| const std::string & | key, | ||
| T & | value | ||
| ) | 
Utility method for handling required ROS params.
| [in] | nh | - The ROS node handle with which to load parameters | 
| [in] | key | - The ROS parameter key for the required parameter | 
| [out] | value | - The ROS parameter value for the key | 
| std::runtime_error | if the parameter does not exist | 
Definition at line 58 of file parameter.h.
| 
 | inlinestatic | 
Returns the Euler pitch angle from a quaternion.
| [in] | w | The quaternion real-valued component | 
| [in] | x | The quaternion x-axis component | 
| [in] | y | The quaternion x-axis component | 
| [in] | z | The quaternion x-axis component | 
| 
 | inline | 
Helper function that loads positive duration values from the parameter server.
| [in] | node_handle | - The node handle used to load the parameter | 
| [in] | parameter_name | - The parameter name to load | 
| [in,out] | default_value | - A default value to use if the provided parameter name does not exist. As output it has the loaded (or default) value | 
| [in] | strict | - Whether to check the loaded value is strictly positive or not, i.e. whether 0 is accepted or not | 
Definition at line 104 of file parameter.h.
| void fuse_core::getPositiveParam | ( | const ros::NodeHandle & | node_handle, | 
| const std::string & | parameter_name, | ||
| T & | default_value, | ||
| const bool | strict = true | ||
| ) | 
Helper function that loads positive integral or floating point values from the parameter server.
| [in] | node_handle | - The node handle used to load the parameter | 
| [in] | parameter_name | - The parameter name to load | 
| [in,out] | default_value | - A default value to use if the provided parameter name does not exist. As output it has the loaded (or default) value | 
| [in] | strict | - Whether to check the loaded value is strictly positive or not, i.e. whether 0 is accepted or not | 
Definition at line 79 of file parameter.h.
| 
 | inlinestatic | 
Returns the Euler roll angle from a quaternion.
| [in] | w | The quaternion real-valued component | 
| [in] | x | The quaternion x-axis component | 
| [in] | y | The quaternion x-axis component | 
| [in] | z | The quaternion x-axis component | 
| 
 | inlinestatic | 
Returns the Euler yaw angle from a quaternion.
Returned angle is in the range [-Pi, +Pi]
| [in] | w | The quaternion real-valued component | 
| [in] | x | The quaternion x-axis component | 
| [in] | y | The quaternion y-axis component | 
| [in] | z | The quaternion z-axis component | 
| bool fuse_core::isPositiveDefinite | ( | const Eigen::DenseBase< Derived > & | m | ) | 
| bool fuse_core::isSymmetric | ( | const Eigen::DenseBase< Derived > & | m, | 
| const typename Eigen::DenseBase< Derived >::RealScalar | precision = Eigen::NumTraits<typename Eigen::DenseBase<Derived>::Scalar>::dummy_precision() | ||
| ) | 
Check if a matrix is symmetric.
| [in] | m | - Square matrix to check symmetry on | 
| [in] | precision | - Precision used to compared the matrix m with its transpose, which is the property used to check for symmetry. | 
| void fuse_core::loadCovarianceOptionsFromROS | ( | const ros::NodeHandle & | nh, | 
| ceres::Covariance::Options & | covariance_options | ||
| ) | 
Populate a ceres::Covariance::Options object with information from the parameter server.
| [in] | nh | - A node handle in a namespace containing ceres::Covariance::Options settings | 
| [out] | covariance_options | - The ceres::Covariance::Options object to update | 
Definition at line 49 of file ceres_options.cpp.
| 
 | inline | 
Utility method to load a loss configuration.
| [in] | nh | - The ROS node handle with which to load parameters | 
| [in] | name | - The ROS parameter name for the loss configuration parameter | 
Definition at line 158 of file parameter.h.
| void fuse_core::loadProblemOptionsFromROS | ( | const ros::NodeHandle & | nh, | 
| ceres::Problem::Options & | problem_options | ||
| ) | 
Populate a ceres::Problem::Options object with information from the parameter server.
| [in] | nh | - A node handle in a namespace containing ceres::Problem::Options settings | 
| [out] | problem_options | - The ceres::Problem::Options object to update | 
Definition at line 65 of file ceres_options.cpp.
| void fuse_core::loadSolverOptionsFromROS | ( | const ros::NodeHandle & | nh, | 
| ceres::Solver::Options & | solver_options | ||
| ) | 
Populate a ceres::Solver::Options object with information from the parameter server.
| [in] | nh | - A node handle in a namespace containing ceres::Solver::Options settings | 
| [out] | solver_options | - The ceres::Solver::Options object to update | 
Definition at line 72 of file ceres_options.cpp.
| std::ostream & fuse_core::operator<< | ( | std::ostream & | stream, | 
| const Constraint & | constraint | ||
| ) | 
Stream operator implementation used for all derived Constraint classes.
Definition at line 53 of file constraint.cpp.
| std::ostream & fuse_core::operator<< | ( | std::ostream & | stream, | 
| const Graph & | graph | ||
| ) | 
| std::ostream & fuse_core::operator<< | ( | std::ostream & | stream, | 
| const Loss & | loss | ||
| ) | 
| std::ostream & fuse_core::operator<< | ( | std::ostream & | stream, | 
| const Transaction & | transaction | ||
| ) | 
Stream operator for printing Transaction objects.
Definition at line 292 of file transaction.cpp.
| std::ostream & fuse_core::operator<< | ( | std::ostream & | stream, | 
| const Variable & | variable | ||
| ) | 
Stream operator implementation used for all derived Variable classes.
Definition at line 47 of file variable.cpp.
| Eigen::Matrix<T, 2, 2, Eigen::RowMajor> fuse_core::rotationMatrix2D | ( | const T | angle | ) | 
| void fuse_core::serializeGraph | ( | const fuse_core::Graph & | graph, | 
| fuse_msgs::SerializedGraph & | msg | ||
| ) | 
Serialize a graph into a message.
Definition at line 45 of file graph_deserializer.cpp.
| void fuse_core::serializeTransaction | ( | const fuse_core::Transaction & | transaction, | 
| fuse_msgs::SerializedTransaction & | msg | ||
| ) | 
Serialize a transaction into a message.
Definition at line 45 of file transaction_deserializer.cpp.
| std::string fuse_core::to_string | ( | const Eigen::DenseBase< Derived > & | m, | 
| const int | precision = 4 | ||
| ) | 
Serialize a matrix into an std::string using this format:
[1, 2, 3] [4, 5, 6] [7, 8, 9]
| [in] | m | - The matrix to serialize into an std::string. | 
| [in] | precision | - The precision to print the matrix elements with. | 
| T fuse_core::wrapAngle2D | ( | const T & | angle | ) |