Program Listing for File batch_optimizer.hpp

Return to documentation for file (/tmp/ws/src/fuse/fuse_optimizers/include/fuse_optimizers/batch_optimizer.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_OPTIMIZERS__BATCH_OPTIMIZER_HPP_
#define FUSE_OPTIMIZERS__BATCH_OPTIMIZER_HPP_

#include <atomic>
#include <condition_variable>
#include <map>
#include <mutex>
#include <set>
#include <string>
#include <thread>
#include <utility>
#include <vector>

#include <fuse_core/graph.hpp>
#include <fuse_core/fuse_macros.hpp>
#include <fuse_core/transaction.hpp>
#include <fuse_optimizers/batch_optimizer_params.hpp>
#include <fuse_optimizers/optimizer.hpp>
#include <fuse_graphs/hash_graph.hpp>


namespace fuse_optimizers
{

class BatchOptimizer : public Optimizer
{
public:
  FUSE_SMART_PTR_DEFINITIONS(BatchOptimizer)
  using ParameterType = BatchOptimizerParams;

  BatchOptimizer(
    fuse_core::node_interfaces::NodeInterfaces<ALL_FUSE_CORE_NODE_INTERFACES> interfaces,
    fuse_core::Graph::UniquePtr graph = nullptr
  );

  virtual ~BatchOptimizer();

protected:
  struct TransactionQueueElement
  {
    std::string sensor_name;
    fuse_core::Transaction::SharedPtr transaction;

    TransactionQueueElement(
      const std::string & sensor_name,
      fuse_core::Transaction::SharedPtr transaction)
    : sensor_name(sensor_name),
      transaction(std::move(transaction)) {}
  };

  using TransactionQueue = std::multimap<rclcpp::Time, TransactionQueueElement>;

  fuse_core::Transaction::SharedPtr combined_transaction_;
  std::mutex combined_transaction_mutex_;
  ParameterType params_;
  std::atomic<bool> optimization_request_;
  std::condition_variable optimization_requested_;
  std::mutex optimization_requested_mutex_;
  std::thread optimization_thread_;
  rclcpp::TimerBase::SharedPtr optimize_timer_;
  TransactionQueue pending_transactions_;
  std::mutex pending_transactions_mutex_;
  rclcpp::Time start_time_;
  bool started_;

  void applyMotionModelsToQueue();

  void optimizationLoop();

  void optimizerTimerCallback();

  void transactionCallback(
    const std::string & sensor_name,
    fuse_core::Transaction::SharedPtr transaction) override;

  void setDiagnostics(diagnostic_updater::DiagnosticStatusWrapper & status) override;
};

}  // namespace fuse_optimizers

#endif  // FUSE_OPTIMIZERS__BATCH_OPTIMIZER_HPP_