-
Notifications
You must be signed in to change notification settings - Fork 11
Expand file tree
/
Copy pathMPPIController.hpp
More file actions
86 lines (68 loc) · 3.32 KB
/
MPPIController.hpp
File metadata and controls
86 lines (68 loc) · 3.32 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
// Copyright 2025 Intelligent Robotics Lab
//
// This file is part of the project Easy Navigation (EasyNav in short)
// 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 EASYNAV_MPPI_CONTROLLER__MPPICONTROLLER_HPP_
#define EASYNAV_MPPI_CONTROLLER__MPPICONTROLLER_HPP_
#include <memory>
#include <expected>
#include <string>
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/path.hpp"
#include "easynav_core/ControllerMethodBase.hpp"
#include "easynav_common/types/NavState.hpp"
#include "easynav_mppi_controller/MPPIOptimizer.hpp"
#include "visualization_msgs/msg/marker.hpp"
#include "visualization_msgs/msg/marker_array.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
namespace easynav
{
/// \brief A MPPI Controller.
class MPPIController : public ControllerMethodBase
{
public:
MPPIController();
/// \brief Destructor.
~MPPIController() override;
/// \brief Initializes parameters and MPPI controller.
/// \return std::expected<void, std::string> success or error message.
std::expected<void, std::string> on_initialize() override;
/// \brief Updates the controller using the given NavState.
/// \param nav_state Current navigation state, including odometry and planned path.
void update_rt(NavState & nav_state) override;
protected:
int num_samples_{100}; ///< Number of samples for MPPI.
int horizon_steps_{10}; ///< Prediction horizon for MPPI.
double dt_{0.1}; ///< Time step for MPPI.
double lambda_{0.1}; ///< Temperature parameter for MPPI.
double max_lin_vel_{1.0}; ///< Maximum linear velocity for MPPI.
double max_ang_vel_{1.0}; ///< Maximum angular velocity for MPPI.
double max_lin_acc_{0.5}; ///< Maximum linear acceleration for MPPI.
double max_ang_acc_{1.0}; ///< Maximum angular acceleration for MPPI.
double fov_{M_PI / 2.0}; ///< Field of view for MPPI.
double safety_radius_{0.6}; ///< Safety radius for obstacle avoidance.
geometry_msgs::msg::TwistStamped twist_stamped_; ///< Current velocity command.
std::unique_ptr<MPPIOptimizer> optimizer_; ///< MPPI optimizer
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr mppi_candidates_pub_; ///< Publisher for MPPI candidates markers.
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr mppi_optimal_pub_; ///< Publisher for MPPI optimal path markers.
/// \brief Publishes MPPI markers for visualization.
/// \param all_trajs All trajectories generated by MPPI.
/// \param best_traj Optimal trajectory generated by MPPI.
void publish_mppi_markers(
const std::vector<std::vector<std::pair<double, double>>> & all_trajs,
const std::vector<std::pair<double, double>> & best_traj);
};
} // namespace easynav
#endif // EASYNAV_MPPI_CONTROLLER__MPPICONTROLLER_HPP_