EasyNav Simple Stack
Loading...
Searching...
No Matches
SimpleController.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 GNU General Public License v3.0.
5// See <http://www.gnu.org/licenses/> for details.
6
7#ifndef EASYNAV_SIMPLE_CONTROLLER__SIMPLECONTROLLER_HPP_
8#define EASYNAV_SIMPLE_CONTROLLER__SIMPLECONTROLLER_HPP_
9
10#include <memory>
11#include <expected>
12#include <string>
13
14#include "geometry_msgs/msg/pose_stamped.hpp"
15#include "geometry_msgs/msg/point.hpp"
16#include "geometry_msgs/msg/twist_stamped.hpp"
17#include "nav_msgs/msg/path.hpp"
18
19#include "easynav_core/ControllerMethodBase.hpp"
20#include "easynav_common/types/NavState.hpp"
22
23namespace easynav
24{
25
28{
29public:
31
34
37 std::expected<void, std::string> on_initialize() override;
38
41 void update_rt(NavState & nav_state) override;
42
43protected:
44 std::shared_ptr<PIDController> linear_pid_;
45 std::shared_ptr<PIDController> angular_pid_;
46
47 double max_linear_speed_{1.0};
48 double max_angular_speed_{1.0};
49 double max_linear_acc_{0.3};
50 double max_angular_acc_{0.3};
51 double look_ahead_dist_{1.0};
52 double tolerance_dist_{0.05};
53 double k_rot_{0.5};
54
55 double last_vlin_{0.0};
56 double last_vrot_{0.0};
57
58 rclcpp::Time last_update_ts_;
59 geometry_msgs::msg::TwistStamped twist_stamped_;
60
65 geometry_msgs::msg::Pose get_ref_pose(
66 const nav_msgs::msg::Path & path,
67 double look_ahead);
68
73 double get_distance(const geometry_msgs::msg::Pose & a, const geometry_msgs::msg::Pose & b);
74
79 double get_angle(const geometry_msgs::msg::Point & from, const geometry_msgs::msg::Point & to);
80
85 double get_diff_angle(
86 const geometry_msgs::msg::Quaternion & a,
87 const geometry_msgs::msg::Quaternion & b);
88};
89
90} // namespace easynav
91
92#endif // EASYNAV_SIMPLE_CONTROLLER__SIMPLECONTROLLER_HPP_
Declaration of a simple PIDController class.
double max_linear_speed_
Maximum linear speed in m/s.
Definition SimpleController.hpp:47
double last_vlin_
Previous linear velocity for acceleration limiting.
Definition SimpleController.hpp:55
double max_angular_speed_
Maximum angular speed in rad/s.
Definition SimpleController.hpp:48
std::shared_ptr< PIDController > angular_pid_
PID controller for angular velocity.
Definition SimpleController.hpp:45
geometry_msgs::msg::Pose get_ref_pose(const nav_msgs::msg::Path &path, double look_ahead)
Gets the reference pose at look-ahead distance on the path.
Definition SimpleController.cpp:139
std::shared_ptr< PIDController > linear_pid_
PID controller for linear velocity.
Definition SimpleController.hpp:44
double get_angle(const geometry_msgs::msg::Point &from, const geometry_msgs::msg::Point &to)
Computes the angle between two points.
Definition SimpleController.cpp:166
double tolerance_dist_
Distance threshold to switch to orientation tracking.
Definition SimpleController.hpp:52
~SimpleController() override
Destructor.
double last_vrot_
Previous angular velocity for acceleration limiting.
Definition SimpleController.hpp:56
double max_angular_acc_
Maximum angular acceleration in rad/s².
Definition SimpleController.hpp:50
double k_rot_
Definition SimpleController.hpp:53
geometry_msgs::msg::TwistStamped twist_stamped_
Current velocity command.
Definition SimpleController.hpp:59
void update_rt(NavState &nav_state) override
Updates the controller using the given NavState.
Definition SimpleController.cpp:75
double get_distance(const geometry_msgs::msg::Pose &a, const geometry_msgs::msg::Pose &b)
Computes the Euclidean distance between two poses.
Definition SimpleController.cpp:156
std::expected< void, std::string > on_initialize() override
Initializes parameters and PID controllers.
Definition SimpleController.cpp:42
rclcpp::Time last_update_ts_
Timestamp of the last control update.
Definition SimpleController.hpp:58
double look_ahead_dist_
Distance ahead of the robot to track in meters.
Definition SimpleController.hpp:51
double get_diff_angle(const geometry_msgs::msg::Quaternion &a, const geometry_msgs::msg::Quaternion &b)
Computes the angular difference between two quaternions (yaw).
Definition SimpleController.cpp:174
SimpleController()
Definition SimpleController.cpp:35
double max_linear_acc_
Maximum linear acceleration in m/s².
Definition SimpleController.hpp:49
Definition SimpleMap.hpp:37