EasyNav Plugins
Loading...
Searching...
No Matches
MPPIController.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
2//
3// This file is part of the project Easy Navigation (EasyNav in short)
4// Licensed under the Apache License, Version 2.0 (the "License");
5// you may not use this file except in compliance with the License.
6// You may obtain a copy of the License at
7//
8// http://www.apache.org/licenses/LICENSE-2.0
9//
10// Unless required by applicable law or agreed to in writing, software
11// distributed under the License is distributed on an "AS IS" BASIS,
12// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13// See the License for the specific language governing permissions and
14// limitations under the License.
15
16#ifndef EASYNAV_MPPI_CONTROLLER__MPPICONTROLLER_HPP_
17#define EASYNAV_MPPI_CONTROLLER__MPPICONTROLLER_HPP_
18
19#include <memory>
20#include <string>
21
22#include "geometry_msgs/msg/twist_stamped.hpp"
23
24#include "easynav_core/ControllerMethodBase.hpp"
25#include "easynav_common/types/NavState.hpp"
26
28
29#include "visualization_msgs/msg/marker_array.hpp"
30
31namespace easynav
32{
33
35class MPPIController : public ControllerMethodBase
36{
37public:
39
41 ~MPPIController() override;
42
45 void on_initialize() override;
46
49 void update_rt(NavState & nav_state) override;
50
51protected:
52 int num_samples_{100};
54 double dt_{0.1};
55 double lambda_{0.1};
56 double max_lin_vel_{1.0};
57 double max_ang_vel_{1.0};
58 double max_lin_acc_{0.5};
59 double max_ang_acc_{1.0};
60 double fov_{M_PI / 2.0};
61 double safety_radius_{0.6};
62
63 geometry_msgs::msg::TwistStamped twist_stamped_;
64
65 std::unique_ptr<MPPIOptimizer> optimizer_;
66 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr mppi_candidates_pub_;
67 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr mppi_optimal_pub_;
68
73 const std::vector<std::vector<std::pair<double, double>>> & all_trajs,
74 const std::vector<std::pair<double, double>> & best_traj);
75
76};
77
78} // namespace easynav
79
80#endif // EASYNAV_MPPI_CONTROLLER__MPPICONTROLLER_HPP_
std::unique_ptr< MPPIOptimizer > optimizer_
MPPI optimizer.
Definition MPPIController.hpp:65
void publish_mppi_markers(const std::vector< std::vector< std::pair< double, double > > > &all_trajs, const std::vector< std::pair< double, double > > &best_traj)
Publishes MPPI markers for visualization.
Definition MPPIController.cpp:71
double max_lin_vel_
Maximum linear velocity for MPPI.
Definition MPPIController.hpp:56
double safety_radius_
Safety radius for obstacle avoidance.
Definition MPPIController.hpp:61
double dt_
Time step for MPPI.
Definition MPPIController.hpp:54
double max_ang_acc_
Maximum angular acceleration for MPPI.
Definition MPPIController.hpp:59
double lambda_
Temperature parameter for MPPI.
Definition MPPIController.hpp:55
geometry_msgs::msg::TwistStamped twist_stamped_
Current velocity command.
Definition MPPIController.hpp:63
void update_rt(NavState &nav_state) override
Updates the controller using the given NavState.
Definition MPPIController.cpp:137
int num_samples_
Number of samples for MPPI.
Definition MPPIController.hpp:52
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr mppi_candidates_pub_
Publisher for MPPI candidates markers.
Definition MPPIController.hpp:66
~MPPIController() override
Destructor.
double max_ang_vel_
Maximum angular velocity for MPPI.
Definition MPPIController.hpp:57
void on_initialize() override
Initializes parameters and MPPI controller.
Definition MPPIController.cpp:35
double fov_
Field of view for MPPI.
Definition MPPIController.hpp:60
int horizon_steps_
Prediction horizon for MPPI.
Definition MPPIController.hpp:53
MPPIController()
Definition MPPIController.cpp:30
double max_lin_acc_
Maximum linear acceleration for MPPI.
Definition MPPIController.hpp:58
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr mppi_optimal_pub_
Publisher for MPPI optimal path markers.
Definition MPPIController.hpp:67
Provides a mapping for often used cost values.
Definition cost_values.hpp:41