Program Listing for File optimizer.hpp
↰ Return to documentation for file (include/nav2_mppi_controller/optimizer.hpp
)
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_MPPI_CONTROLLER__OPTIMIZER_HPP_
#define NAV2_MPPI_CONTROLLER__OPTIMIZER_HPP_
#include <string>
#include <memory>
// xtensor creates warnings that needs to be ignored as we are building with -Werror
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Warray-bounds"
#pragma GCC diagnostic ignored "-Wstringop-overflow"
#include <xtensor/xtensor.hpp>
#include <xtensor/xview.hpp>
#pragma GCC diagnostic pop
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
#include "nav2_core/goal_checker.hpp"
#include "nav2_core/controller_exceptions.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/path.hpp"
#include "nav2_mppi_controller/models/optimizer_settings.hpp"
#include "nav2_mppi_controller/motion_models.hpp"
#include "nav2_mppi_controller/critic_manager.hpp"
#include "nav2_mppi_controller/models/state.hpp"
#include "nav2_mppi_controller/models/trajectories.hpp"
#include "nav2_mppi_controller/models/path.hpp"
#include "nav2_mppi_controller/tools/noise_generator.hpp"
#include "nav2_mppi_controller/tools/parameters_handler.hpp"
#include "nav2_mppi_controller/tools/utils.hpp"
namespace mppi
{
class Optimizer
{
public:
Optimizer() = default;
~Optimizer() {shutdown();}
void initialize(
rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
ParametersHandler * dynamic_parameters_handler);
void shutdown();
geometry_msgs::msg::TwistStamped evalControl(
const geometry_msgs::msg::PoseStamped & robot_pose,
const geometry_msgs::msg::Twist & robot_speed, const nav_msgs::msg::Path & plan,
nav2_core::GoalChecker * goal_checker);
models::Trajectories & getGeneratedTrajectories();
xt::xtensor<float, 2> getOptimizedTrajectory();
void setSpeedLimit(double speed_limit, bool percentage);
void reset();
protected:
void optimize();
void prepare(
const geometry_msgs::msg::PoseStamped & robot_pose,
const geometry_msgs::msg::Twist & robot_speed,
const nav_msgs::msg::Path & plan, nav2_core::GoalChecker * goal_checker);
void getParams();
void setMotionModel(const std::string & model);
void shiftControlSequence();
void generateNoisedTrajectories();
void applyControlSequenceConstraints();
void updateStateVelocities(models::State & state) const;
void updateInitialStateVelocities(models::State & state) const;
void propagateStateVelocitiesFromInitials(models::State & state) const;
void integrateStateVelocities(
models::Trajectories & trajectories,
const models::State & state) const;
void integrateStateVelocities(
xt::xtensor<float, 2> & trajectories,
const xt::xtensor<float, 2> & state) const;
void updateControlSequence();
geometry_msgs::msg::TwistStamped
getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time & stamp);
bool isHolonomic() const;
void setOffset(double controller_frequency);
bool fallback(bool fail);
protected:
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
nav2_costmap_2d::Costmap2D * costmap_;
std::string name_;
std::shared_ptr<MotionModel> motion_model_;
ParametersHandler * parameters_handler_;
CriticManager critic_manager_;
NoiseGenerator noise_generator_;
models::OptimizerSettings settings_;
models::State state_;
models::ControlSequence control_sequence_;
std::array<mppi::models::Control, 4> control_history_;
models::Trajectories generated_trajectories_;
models::Path path_;
xt::xtensor<float, 1> costs_;
CriticData critics_data_ =
{state_, generated_trajectories_, path_, costs_, settings_.model_dt, false, nullptr, nullptr,
std::nullopt, std::nullopt};
rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
};
} // namespace mppi
#endif // NAV2_MPPI_CONTROLLER__OPTIMIZER_HPP_