Skip to content

Commit d916d1e

Browse files
Support for ackermann robots and propose a solution of zero linear velocity problem
1 parent 3508aae commit d916d1e

File tree

11 files changed

+237
-30
lines changed

11 files changed

+237
-30
lines changed

ilqr_trajectory_tracker/CMakeLists.txt

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,10 @@ endif()
1616

1717
find_package(ament_cmake REQUIRED)
1818

19-
add_library(ilqr_trajectory_tracker_lib SHARED src/models/diff_robot_model.cpp)
19+
add_library(
20+
ilqr_trajectory_tracker_lib SHARED
21+
src/models/diff_robot_model.cpp
22+
src/models/ackermann_robot_model.cpp)
2023

2124
target_include_directories(
2225
ilqr_trajectory_tracker_lib

ilqr_trajectory_tracker/include/ilqr_trajectory_tracker/ilqr_optimizer.hpp

Lines changed: 30 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,10 @@
1919

2020
#include <Eigen/Dense>
2121
#include <cmath>
22+
#include <memory>
2223
#include <tuple>
2324
#include <algorithm>
25+
#include <limits>
2426

2527
using namespace Eigen;
2628

@@ -40,15 +42,19 @@ template<typename RobotModel>
4042
class NewtonOptimizer : public Optimizer
4143
{
4244
public:
43-
NewtonOptimizer();
45+
template<typename ... RobotModelParams>
46+
NewtonOptimizer(const RobotModelParams ... model_params);
47+
4448
std::vector<MatrixXd> backwardPass(
4549
const std::vector<typename RobotModel::StateT> & x_feasible,
4650
const std::vector<typename RobotModel::InputT> & u_feasible,
4751
const MatrixXd & Q, const MatrixXd & R, const double dt);
52+
4853
std::tuple<MatrixXd, MatrixXd> solveDiscreteLQRProblem(
4954
const MatrixXd & A, const MatrixXd & B,
5055
const MatrixXd & Q, const MatrixXd & R,
5156
const MatrixXd & P);
57+
5258
std::tuple<std::vector<typename RobotModel::StateT>,
5359
std::vector<typename RobotModel::InputT>> forwardPass(
5460
const std::vector<typename RobotModel::StateT> & x_feasible,
@@ -58,23 +64,31 @@ class NewtonOptimizer : public Optimizer
5864
std::vector<typename RobotModel::InputT> optimize(
5965
const std::vector<typename RobotModel::StateT> & x_feasible, const Matrix3d & Q,
6066
const Matrix2d & R, const double dt);
67+
6168
double cost(
6269
const std::vector<typename RobotModel::StateT> & x_tracked,
6370
const std::vector<typename RobotModel::StateT> & x_trajectory);
6471

6572
void setIterationNumber(const size_t iteration_number);
73+
6674
void setAlpha(const double alpha);
6775

76+
void setInputConstraints(
77+
typename RobotModel::InputT input_limits_min,
78+
typename RobotModel::InputT input_limits_max);
79+
6880
private:
69-
RobotModel robot_model_;
81+
std::unique_ptr<RobotModel> robot_model_;
7082
double alpha_;
7183
size_t iteration_number_;
7284
};
7385

7486
template<typename RobotModel>
75-
NewtonOptimizer<RobotModel>::NewtonOptimizer()
87+
template<typename ... RobotModelParams>
88+
NewtonOptimizer<RobotModel>::NewtonOptimizer(const RobotModelParams ... model_params)
7689
: Optimizer()
7790
{
91+
robot_model_ = std::make_unique<RobotModel>(model_params...);
7892
}
7993

8094
template<typename RobotModel>
@@ -95,15 +109,15 @@ std::vector<MatrixXd> NewtonOptimizer<RobotModel>::backwardPass(
95109

96110
for (auto i = std::distance(x_feasible.begin(), std::prev(x_feasible.end(), 2)); i >= 0; i--) {
97111
auto x_offset =
98-
robot_model_.applySystemDynamics(x_feasible.at(i), u_feasible[i], dt) - x_feasible[i + 1];
112+
robot_model_->applySystemDynamics(x_feasible.at(i), u_feasible[i], dt) - x_feasible[i + 1];
99113

100114
MatrixXd A_tilda = MatrixXd::Identity(state_dimension + 1, state_dimension + 1);
101-
auto A = robot_model_.getStateMatrix(x_feasible[i], u_feasible[i], dt);
115+
auto A = robot_model_->getStateMatrix(x_feasible[i], u_feasible[i], dt);
102116
A_tilda.topLeftCorner(state_dimension, state_dimension) = A;
103117
A_tilda.topRightCorner(state_dimension, 1) = x_offset;
104118

105119
MatrixXd B_tilda = MatrixXd::Zero(state_dimension + 1, input_dimension);
106-
auto B = robot_model_.getControlMatrix(x_feasible[i], u_feasible[i], dt);
120+
auto B = robot_model_->getControlMatrix(x_feasible[i], u_feasible[i], dt);
107121
B_tilda.topLeftCorner(state_dimension, input_dimension) = B;
108122

109123
MatrixXd Q_tilda = MatrixXd::Identity(state_dimension + 1, state_dimension + 1);
@@ -143,7 +157,8 @@ std::tuple<std::vector<typename RobotModel::StateT>,
143157
z_error << x_error, alpha;
144158

145159
u_applied[i] = u_feasible[i] + K_gains[i] * z_error;
146-
x_tracked[i + 1] = robot_model_.applySystemDynamics(x_tracked[i], u_applied[i], dt);
160+
u_applied[i] = robot_model_->applyLimits(u_applied[i]);
161+
x_tracked[i + 1] = robot_model_->applySystemDynamics(x_tracked[i], u_applied[i], dt);
147162
}
148163

149164
return {x_tracked, u_applied};
@@ -235,4 +250,12 @@ void NewtonOptimizer<RobotModel>::setAlpha(const double alpha)
235250
alpha_ = alpha;
236251
}
237252

253+
template<typename RobotModel>
254+
void NewtonOptimizer<RobotModel>::setInputConstraints(
255+
typename RobotModel::InputT input_limits_min,
256+
typename RobotModel::InputT input_limits_max)
257+
{
258+
robot_model_->setLimits(input_limits_min, input_limits_max);
259+
}
260+
238261
}
Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
// Copyright (C) 2024 Cihat Kurtuluş Altıparmak
2+
// Copyright (C) 2024 Prof. Tufan Kumbasar, Istanbul Technical University Artificial Intelligence and Intelligent Systems (AI2S) Laboratory
3+
// Copyright (C) 2024 Prof. Behçet Uğur Töreyin
4+
//
5+
// This program is free software: you can redistribute it and/or modify
6+
// it under the terms of the GNU General Public License as published by
7+
// the Free Software Foundation, either version 3 of the License, or
8+
// (at your option) any later version.
9+
//
10+
// This program is distributed in the hope that it will be useful,
11+
// but WITHOUT ANY WARRANTY; without even the implied warranty of
12+
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13+
// GNU General Public License for more details.
14+
//
15+
// You should have received a copy of the GNU General Public License
16+
// along with this program. If not, see <https://www.gnu.org/licenses/>.
17+
18+
#pragma once
19+
20+
#include <ilqr_trajectory_tracker/models/base_model.hpp>
21+
22+
#include <Eigen/Dense>
23+
#include <cmath>
24+
25+
using namespace Eigen;
26+
27+
namespace ilqr_trajectory_tracker
28+
{
29+
30+
using AckermannRobotModelState = Vector3d;
31+
using AckermannRobotModelInput = Vector2d;
32+
33+
class AckermannRobotModel : public Model<AckermannRobotModelState, AckermannRobotModelInput>
34+
{
35+
public:
36+
using StateT = AckermannRobotModelState;
37+
using InputT = AckermannRobotModelInput;
38+
AckermannRobotModel(const double wheelbase);
39+
StateT applySystemDynamics(const StateT & x, const InputT & u, const double dt) override;
40+
InputT applyLimits(const InputT & u) override;
41+
MatrixXd getStateMatrix(const StateT & x_eq, const InputT & u_eq, const double dt);
42+
MatrixXd getControlMatrix(const StateT & x_eq, const InputT & u_eq, const double dt);
43+
private:
44+
double wheelbase_;
45+
};
46+
47+
}

ilqr_trajectory_tracker/include/ilqr_trajectory_tracker/models/base_model.hpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,15 +31,28 @@ class Model
3131
public:
3232
Model();
3333
virtual StateT applySystemDynamics(const StateT & x, const InputT & u, const double dt) = 0;
34+
virtual InputT applyLimits(const InputT & u) = 0;
35+
void setLimits(const Vector2d & input_limits_min, const Vector2d & input_limits_max);
3436
virtual MatrixXd getStateMatrix(const StateT & x_eq, const InputT & u_eq, const double dt) = 0;
3537
virtual MatrixXd getControlMatrix(
3638
const StateT & x_eq, const InputT & u_eq,
3739
const double dt) = 0;
40+
protected:
41+
InputT input_limits_min_;
42+
InputT input_limits_max_;
3843
};
3944

4045
template<typename StateT, typename InputT>
4146
Model<StateT, InputT>::Model()
4247
{
4348
}
4449

50+
template<typename StateT, typename InputT>
51+
void Model<StateT, InputT>::setLimits(
52+
const Vector2d & input_limits_min,
53+
const Vector2d & input_limits_max) {
54+
55+
input_limits_min_ = input_limits_min;
56+
input_limits_max_ = input_limits_max;
57+
}
4558
}

ilqr_trajectory_tracker/include/ilqr_trajectory_tracker/models/diff_robot_model.hpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,9 +36,10 @@ class DiffDriveRobotModel : public Model<DiffDriveRobotModelState, DiffDriveRobo
3636
using StateT = DiffDriveRobotModelState;
3737
using InputT = DiffDriveRobotModelInput;
3838
DiffDriveRobotModel();
39-
Vector3d applySystemDynamics(const Vector3d & x, const Vector2d & u, const double dt) override;
40-
MatrixXd getStateMatrix(const Vector3d & x_eq, const Vector2d & u_eq, const double dt);
41-
MatrixXd getControlMatrix(const Vector3d & x_eq, const Vector2d & u_eq, const double dt);
39+
DiffDriveRobotModelState applySystemDynamics(const StateT & x, const InputT & u, const double dt) override;
40+
InputT applyLimits(const InputT & u) override;
41+
MatrixXd getStateMatrix(const StateT & x_eq, const InputT & u_eq, const double dt);
42+
MatrixXd getControlMatrix(const StateT & x_eq, const InputT & u_eq, const double dt);
4243
};
4344

4445
}
Lines changed: 74 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,74 @@
1+
// Copyright (C) 2024 Cihat Kurtuluş Altıparmak
2+
// Copyright (C) 2024 Prof. Tufan Kumbasar, Istanbul Technical University Artificial Intelligence and Intelligent Systems (AI2S) Laboratory
3+
// Copyright (C) 2024 Prof. Behçet Uğur Töreyin
4+
//
5+
// This program is free software: you can redistribute it and/or modify
6+
// it under the terms of the GNU General Public License as published by
7+
// the Free Software Foundation, either version 3 of the License, or
8+
// (at your option) any later version.
9+
//
10+
// This program is distributed in the hope that it will be useful,
11+
// but WITHOUT ANY WARRANTY; without even the implied warranty of
12+
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13+
// GNU General Public License for more details.
14+
//
15+
// You should have received a copy of the GNU General Public License
16+
// along with this program. If not, see <https://www.gnu.org/licenses/>.
17+
18+
#include <ilqr_trajectory_tracker/models/ackermann_robot_model.hpp>
19+
#include <Eigen/Dense>
20+
#include <cmath>
21+
22+
using namespace Eigen;
23+
24+
namespace ilqr_trajectory_tracker
25+
{
26+
27+
AckermannRobotModel::AckermannRobotModel(const double wheelbase)
28+
: Model<AckermannRobotModelState, AckermannRobotModelInput>(), wheelbase_(wheelbase)
29+
{
30+
31+
}
32+
33+
AckermannRobotModelState AckermannRobotModel::applySystemDynamics(
34+
const AckermannRobotModelState & x, const AckermannRobotModelInput & u,
35+
const double dt)
36+
{
37+
AckermannRobotModelState x_final;
38+
x_final <<
39+
x[0] + u[0] * std::cos(x[2]) * dt,
40+
x[1] + u[0] * std::sin(x[2]) * dt,
41+
x[2] + (u[0] / wheelbase_) * std::tan(u[1]) * dt;
42+
43+
return x_final;
44+
}
45+
46+
AckermannRobotModelInput AckermannRobotModel::applyLimits(const AckermannRobotModelInput & u) {
47+
return u.cwiseMin(input_limits_max_).cwiseMax(input_limits_min_);
48+
}
49+
50+
MatrixXd AckermannRobotModel::getStateMatrix(
51+
const AckermannRobotModelState & x_eq, const AckermannRobotModelInput & u_eq,
52+
const double dt)
53+
{
54+
Matrix3d state_matrix;
55+
state_matrix << 1, 0, -u_eq[0] * std::sin(x_eq[2]) * dt,
56+
0, 1, u_eq[0] * std::cos(x_eq[2]) * dt,
57+
0, 0, 1;
58+
59+
return state_matrix;
60+
}
61+
62+
MatrixXd AckermannRobotModel::getControlMatrix(
63+
const AckermannRobotModelState & x_eq, const AckermannRobotModelInput & u_eq,
64+
const double dt)
65+
{
66+
Matrix<double, 3, 2> control_matrix;
67+
control_matrix << std::cos(x_eq[2]) * dt, 0,
68+
std::sin(x_eq[2]) * dt, 0,
69+
std::tan(u_eq[1]) / wheelbase_ * dt, (u_eq[0] / wheelbase_) * (1 / (std::cos(u_eq[1]) * std::cos(u_eq[1]))) * dt;
70+
71+
return control_matrix;
72+
}
73+
74+
}

ilqr_trajectory_tracker/src/models/diff_robot_model.cpp

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -30,11 +30,11 @@ DiffDriveRobotModel::DiffDriveRobotModel()
3030

3131
}
3232

33-
Vector3d DiffDriveRobotModel::applySystemDynamics(
34-
const Vector3d & x, const Vector2d & u,
33+
DiffDriveRobotModelState DiffDriveRobotModel::applySystemDynamics(
34+
const DiffDriveRobotModelState & x, const DiffDriveRobotModelInput & u,
3535
const double dt)
3636
{
37-
Vector3d x_final;
37+
DiffDriveRobotModelState x_final;
3838
x_final <<
3939
x[0] + u[0] * std::cos(x[2] + u[1] * dt) * dt,
4040
x[1] + u[0] * std::sin(x[2] + u[1] * dt) * dt,
@@ -43,8 +43,12 @@ Vector3d DiffDriveRobotModel::applySystemDynamics(
4343
return x_final;
4444
}
4545

46+
DiffDriveRobotModelInput DiffDriveRobotModel::applyLimits(const DiffDriveRobotModelInput & u) {
47+
return u.cwiseMin(input_limits_max_).cwiseMax(input_limits_min_);
48+
}
49+
4650
MatrixXd DiffDriveRobotModel::getStateMatrix(
47-
const Vector3d & x_eq, const Vector2d & u_eq,
51+
const DiffDriveRobotModelState & x_eq, const DiffDriveRobotModelInput & u_eq,
4852
const double dt)
4953
{
5054
Matrix3d state_matrix;
@@ -56,7 +60,7 @@ MatrixXd DiffDriveRobotModel::getStateMatrix(
5660
}
5761

5862
MatrixXd DiffDriveRobotModel::getControlMatrix(
59-
const Vector3d & x_eq, const Vector2d & /*u_eq*/,
63+
const DiffDriveRobotModelState & x_eq, const DiffDriveRobotModelInput & u_eq,
6064
const double dt)
6165
{
6266
Matrix<double, 3, 2> control_matrix;

nav2_frenet_ilqr_controller/include/nav2_frenet_ilqr_controller/frenet_ilqr_controller.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737
#include "frenet_trajectory_planner/type_definitions.hpp"
3838
#include "frenet_trajectory_planner/frenet_trajectory_planner.hpp"
3939
#include "ilqr_trajectory_tracker/models/diff_robot_model.hpp"
40+
#include "ilqr_trajectory_tracker/models/ackermann_robot_model.hpp"
4041
#include "ilqr_trajectory_tracker/ilqr_optimizer.hpp"
4142

4243
namespace nav2_frenet_ilqr_controller

nav2_frenet_ilqr_controller/include/nav2_frenet_ilqr_controller/policies/rclcpp_node_policy.hpp

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ namespace policies
3333
class RclcppNodePolicy : public Policy
3434
{
3535
public:
36-
RclcppNodePolicy();
36+
RclcppNodePolicy() : Policy() {}
3737
virtual void initialize(
3838
const std::string & policy_plugin_name,
3939
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
@@ -55,11 +55,6 @@ class RclcppNodePolicy : public Policy
5555
nav2_costmap_2d::Costmap2D * costmap_{nullptr};
5656
};
5757

58-
RclcppNodePolicy::RclcppNodePolicy()
59-
: Policy()
60-
{
61-
}
62-
6358
}
6459
}
6560

0 commit comments

Comments
 (0)