Program Listing for File unicycle_2d.hpp

Return to documentation for file (/tmp/ws/src/fuse/fuse_models/include/fuse_models/unicycle_2d.hpp)

/*
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2018, Locus Robotics
 *  All rights reserved.
 *
 *  Redistribution and use in source and binary forms, with or without
 *  modification, are permitted provided that the following conditions
 *  are met:
 *
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   * Neither the name of the copyright holder nor the names of its
 *     contributors may be used to endorse or promote products derived
 *     from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *  POSSIBILITY OF SUCH DAMAGE.
 */
#ifndef FUSE_MODELS__UNICYCLE_2D_HPP_
#define FUSE_MODELS__UNICYCLE_2D_HPP_

#include <map>
#include <string>
#include <utility>
#include <vector>

#include <fuse_core/async_motion_model.hpp>
#include <fuse_core/constraint.hpp>
#include <fuse_core/eigen.hpp>
#include <fuse_core/graph.hpp>
#include <fuse_core/fuse_macros.hpp>
#include <fuse_core/timestamp_manager.hpp>
#include <fuse_core/transaction.hpp>
#include <fuse_core/variable.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2_2d/tf2_2d.hpp>


namespace fuse_models
{

class Unicycle2D : public fuse_core::AsyncMotionModel
{
public:
  FUSE_SMART_PTR_DEFINITIONS_WITH_EIGEN(Unicycle2D)


  Unicycle2D();

  ~Unicycle2D() = default;

  void initialize(
    fuse_core::node_interfaces::NodeInterfaces<ALL_FUSE_CORE_NODE_INTERFACES> interfaces,
    const std::string & name) override;

  void print(std::ostream & stream = std::cout) const;

protected:
  struct StateHistoryElement
  {
    fuse_core::UUID position_uuid;
    fuse_core::UUID yaw_uuid;
    fuse_core::UUID vel_linear_uuid;
    fuse_core::UUID vel_yaw_uuid;
    fuse_core::UUID acc_linear_uuid;

    tf2_2d::Transform pose;
    tf2_2d::Vector2 velocity_linear;
    double velocity_yaw{0.0};
    tf2_2d::Vector2 acceleration_linear;

    void print(std::ostream & stream = std::cout) const;

    void validate() const;
  };
  using StateHistory = std::map<rclcpp::Time, StateHistoryElement>;

  bool applyCallback(fuse_core::Transaction & transaction) override;

  void generateMotionModel(
    const rclcpp::Time & beginning_stamp,
    const rclcpp::Time & ending_stamp,
    std::vector<fuse_core::Constraint::SharedPtr> & constraints,
    std::vector<fuse_core::Variable::SharedPtr> & variables);

  void onGraphUpdate(fuse_core::Graph::ConstSharedPtr graph) override;

  void onInit() override;

  void onStart() override;

  static void updateStateHistoryEstimates(
    const fuse_core::Graph & graph,
    StateHistory & state_history,
    const rclcpp::Duration & buffer_length);

  static void validateMotionModel(
    const StateHistoryElement & state1, const StateHistoryElement & state2,
    const fuse_core::Matrix8d & process_noise_covariance);

  fuse_core::node_interfaces::NodeInterfaces<
    fuse_core::node_interfaces::Base,
    fuse_core::node_interfaces::Clock,
    fuse_core::node_interfaces::Logging,
    fuse_core::node_interfaces::Parameters,
    fuse_core::node_interfaces::Topics,
    fuse_core::node_interfaces::Waitables
  > interfaces_;

  rclcpp::Clock::SharedPtr clock_;
  rclcpp::Logger logger_;

  rclcpp::Duration buffer_length_;
  fuse_core::UUID device_id_;
  fuse_core::TimestampManager timestamp_manager_;
  fuse_core::Matrix8d process_noise_covariance_;
  bool scale_process_noise_{false};
  double velocity_norm_min_{1e-3};
  bool disable_checks_{false};
  StateHistory state_history_;
};

std::ostream & operator<<(std::ostream & stream, const Unicycle2D & unicycle_2d);

}  // namespace fuse_models

#endif  // FUSE_MODELS__UNICYCLE_2D_HPP_