EasyNav Plugins
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 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_SIMPLE_CONTROLLER__SIMPLECONTROLLER_HPP_
17#define EASYNAV_SIMPLE_CONTROLLER__SIMPLECONTROLLER_HPP_
18
19#include <memory>
20#include <string>
21
22#include "geometry_msgs/msg/point.hpp"
23#include "geometry_msgs/msg/twist_stamped.hpp"
24#include "nav_msgs/msg/path.hpp"
25
26#include "easynav_core/ControllerMethodBase.hpp"
27#include "easynav_common/types/NavState.hpp"
29
30namespace easynav
31{
32
34class SimpleController : public ControllerMethodBase
35{
36public:
38
41
44 void on_initialize() override;
45
48 void update_rt(NavState & nav_state) override;
49
50protected:
51 std::shared_ptr<PIDController> linear_pid_;
52 std::shared_ptr<PIDController> angular_pid_;
53
54 double max_linear_speed_{1.0};
55 double max_angular_speed_{1.0};
56 double max_linear_acc_{0.3};
57 double max_angular_acc_{0.3};
58 double look_ahead_dist_{1.0};
59 double tolerance_dist_{0.05};
60 double k_rot_{0.5};
62 double linear_kp_{0.95};
63 double linear_ki_{0.03};
64 double linear_kd_{0.08};
65 double angular_kp_{1.5};
66 double angular_ki_{0.03};
67 double angular_kd_{0.08};
68
69 double last_vlin_{0.0};
70 double last_vrot_{0.0};
71
72 rclcpp::Time last_update_ts_;
73 geometry_msgs::msg::TwistStamped twist_stamped_;
74
79 geometry_msgs::msg::Pose get_ref_pose(
80 const nav_msgs::msg::Path & path,
81 double look_ahead);
82
87 double get_distance(const geometry_msgs::msg::Pose & a, const geometry_msgs::msg::Pose & b);
88
93 double get_angle(const geometry_msgs::msg::Point & from, const geometry_msgs::msg::Point & to);
94
99 double get_diff_angle(
100 const geometry_msgs::msg::Quaternion & a,
101 const geometry_msgs::msg::Quaternion & b);
102};
103
104} // namespace easynav
105
106#endif // EASYNAV_SIMPLE_CONTROLLER__SIMPLECONTROLLER_HPP_
Declaration of a simple PIDController class.
double linear_kd_
Derivative gain for linear PID.
Definition SimpleController.hpp:64
double final_goal_angle_tolerance_
Angular tolerance at the final goal in radians.
Definition SimpleController.hpp:61
double max_linear_speed_
Maximum linear speed in m/s.
Definition SimpleController.hpp:54
double linear_ki_
Integral gain for linear PID.
Definition SimpleController.hpp:63
double angular_kd_
Derivative gain for angular PID.
Definition SimpleController.hpp:67
double last_vlin_
Previous linear velocity for acceleration limiting.
Definition SimpleController.hpp:69
double max_angular_speed_
Maximum angular speed in rad/s.
Definition SimpleController.hpp:55
std::shared_ptr< PIDController > angular_pid_
PID controller for angular velocity.
Definition SimpleController.hpp:52
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:187
std::shared_ptr< PIDController > linear_pid_
PID controller for linear velocity.
Definition SimpleController.hpp:51
double get_angle(const geometry_msgs::msg::Point &from, const geometry_msgs::msg::Point &to)
Computes the angle between two points.
Definition SimpleController.cpp:214
double tolerance_dist_
Distance threshold to switch to orientation tracking.
Definition SimpleController.hpp:59
~SimpleController() override
Destructor.
double last_vrot_
Previous angular velocity for acceleration limiting.
Definition SimpleController.hpp:70
double max_angular_acc_
Maximum angular acceleration in rad/s².
Definition SimpleController.hpp:57
double k_rot_
Gain to reduce linear speed based on angular velocity.
Definition SimpleController.hpp:60
geometry_msgs::msg::TwistStamped twist_stamped_
Current velocity command.
Definition SimpleController.hpp:73
void update_rt(NavState &nav_state) override
Updates the controller using the given NavState.
Definition SimpleController.cpp:88
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:204
double angular_ki_
Integral gain for angular PID.
Definition SimpleController.hpp:66
double angular_kp_
Proportional gain for angular PID.
Definition SimpleController.hpp:65
rclcpp::Time last_update_ts_
Timestamp of the last control update.
Definition SimpleController.hpp:72
double look_ahead_dist_
Distance ahead of the robot to track in meters.
Definition SimpleController.hpp:58
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:222
void on_initialize() override
Initializes parameters and PID controllers.
Definition SimpleController.cpp:37
SimpleController()
Definition SimpleController.cpp:30
double linear_kp_
Proportional gain for linear PID.
Definition SimpleController.hpp:62
double max_linear_acc_
Maximum linear acceleration in m/s².
Definition SimpleController.hpp:56
Provides a mapping for often used cost values.
Definition cost_values.hpp:41