Program Listing for File fixed_lag_smoother_params.hpp

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

#include <ceres/solver.h>

#include <algorithm>
#include <string>
#include <vector>

#include <fuse_core/ceres_options.hpp>
#include <fuse_core/parameter.hpp>
#include <rclcpp/rclcpp.hpp>


namespace fuse_optimizers
{

struct FixedLagSmootherParams
{
public:
  rclcpp::Duration lag_duration {5, 0};

  rclcpp::Duration optimization_period {0, static_cast<uint32_t>(RCUTILS_S_TO_NS(0.1))};

  std::string reset_service {"~/reset"};

  rclcpp::Duration transaction_timeout {0, static_cast<uint32_t>(RCUTILS_S_TO_NS(0.1))};

  ceres::Solver::Options solver_options;

  void loadFromROS(
    fuse_core::node_interfaces::NodeInterfaces<
      fuse_core::node_interfaces::Base,
      fuse_core::node_interfaces::Logging,
      fuse_core::node_interfaces::Parameters
    > interfaces)
  {
    // Read settings from the parameter server
    fuse_core::getPositiveParam(interfaces, "lag_duration", lag_duration);

    double optimization_frequency{-1.0};
    optimization_frequency = fuse_core::getParam(
      interfaces, "optimization_frequency",
      optimization_frequency);
    fuse_core::getPositiveParam(interfaces, "optimization_period", optimization_period);

    if (optimization_frequency != -1.0) {
      if (optimization_frequency < 0) {
        RCLCPP_WARN_STREAM(
          interfaces.get_node_logging_interface()->get_logger(),
          "The requested optimization_frequency parameter is < 0. Using the optimization_period"
          "parameter instead!");
      }
      optimization_period =
        rclcpp::Duration::from_seconds(1.0 / optimization_frequency);
    }

    fuse_core::getParam(interfaces, "reset_service", reset_service);

    fuse_core::getPositiveParam(interfaces, "transaction_timeout", transaction_timeout);

    fuse_core::loadSolverOptionsFromROS(interfaces, solver_options, "solver_options");
  }
};

}  // namespace fuse_optimizers

#endif  // FUSE_OPTIMIZERS__FIXED_LAG_SMOOTHER_PARAMS_HPP_