Program Listing for File fixed_lag_smoother.hpp
↰ Return to documentation for file (/tmp/ws/src/fuse/fuse_optimizers/include/fuse_optimizers/fixed_lag_smoother.hpp
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2019, 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__FIXED_LAG_SMOOTHER_HPP_
#define FUSE_OPTIMIZERS__FIXED_LAG_SMOOTHER_HPP_
#include <atomic>
#include <condition_variable>
#include <functional>
#include <memory>
#include <mutex>
#include <string>
#include <thread>
#include <vector>
#include <fuse_core/graph.hpp>
#include <fuse_core/transaction.hpp>
#include <fuse_optimizers/fixed_lag_smoother_params.hpp>
#include <fuse_optimizers/optimizer.hpp>
#include <fuse_optimizers/variable_stamp_index.hpp>
#include <fuse_graphs/hash_graph.hpp>
#include <fuse_constraints/marginalize_variables.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_srvs/srv/empty.hpp>
namespace fuse_optimizers
{
class FixedLagSmoother : public Optimizer
{
public:
FUSE_SMART_PTR_DEFINITIONS(FixedLagSmoother)
using ParameterType = FixedLagSmootherParams;
FixedLagSmoother(
fuse_core::node_interfaces::NodeInterfaces<ALL_FUSE_CORE_NODE_INTERFACES> interfaces,
fuse_core::Graph::UniquePtr graph = nullptr
);
virtual ~FixedLagSmoother();
protected:
struct TransactionQueueElement
{
std::string sensor_name;
fuse_core::Transaction::SharedPtr transaction;
const rclcpp::Time & stamp() const {return transaction->stamp();}
const rclcpp::Time & minStamp() const {return transaction->minStamp();}
const rclcpp::Time & maxStamp() const {return transaction->maxStamp();}
};
using TransactionQueue = std::vector<TransactionQueueElement>;
// Read-only after construction
std::thread optimization_thread_;
ParameterType params_;
// Inherently thread-safe
std::atomic<bool> ignited_;
std::atomic<bool> optimization_running_;
std::atomic<bool> started_;
// Guarded by pending_transactions_mutex_
std::mutex pending_transactions_mutex_;
TransactionQueue pending_transactions_;
// Guarded by optimization_mutex_
std::mutex optimization_mutex_;
// fuse_core::Graph* graph_ member from the base class
rclcpp::Time lag_expiration_;
fuse_core::Transaction marginal_transaction_;
VariableStampIndex timestamp_tracking_;
ceres::Solver::Summary summary_;
// Guarded by optimization_requested_mutex_
std::mutex optimization_requested_mutex_;
rclcpp::Time optimization_deadline_;
bool optimization_request_;
std::condition_variable optimization_requested_;
// Guarded by start_time_mutex_
mutable std::mutex start_time_mutex_;
rclcpp::Time start_time_ {0, 0, RCL_ROS_TIME};
// Ordering ROS objects with callbacks last
rclcpp::TimerBase::SharedPtr optimize_timer_;
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_service_server_;
void autostart();
void preprocessMarginalization(const fuse_core::Transaction & new_transaction);
rclcpp::Time computeLagExpirationTime() const;
std::vector<fuse_core::UUID> computeVariablesToMarginalize(const rclcpp::Time & lag_expiration);
void postprocessMarginalization(const fuse_core::Transaction & marginal_transaction);
void optimizationLoop();
void optimizerTimerCallback();
void processQueue(fuse_core::Transaction & transaction, const rclcpp::Time & lag_expiration);
bool resetServiceCallback(
const std::shared_ptr<std_srvs::srv::Empty::Request>,
std::shared_ptr<std_srvs::srv::Empty::Response>
);
rclcpp::Time getStartTime() const
{
std::lock_guard<std::mutex> lock(start_time_mutex_);
return start_time_;
}
void setStartTime(const rclcpp::Time & start_time)
{
std::lock_guard<std::mutex> lock(start_time_mutex_);
start_time_ = start_time;
}
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__FIXED_LAG_SMOOTHER_HPP_