Skip to content

Commit 3d30ff8

Browse files
Merge branch 'main' into feature/fix/mix/support_for_ackermann_robots
2 parents d916d1e + 063190e commit 3d30ff8

File tree

4 files changed

+17
-8
lines changed

4 files changed

+17
-8
lines changed

ilqr_trajectory_tracker/demos/ilqr_optimizer_demo.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,9 @@ int main(int argc, char ** argv)
5656
newton_optimizer.setAlpha(alpha);
5757

5858
const auto start{std::chrono::steady_clock::now()};
59-
auto u_optimal = newton_optimizer.optimize(x_feasible, Q, R, dt);
59+
// TODO: Fix demo later, we should pass the actual robot pose instead of
60+
// the beginning pose of the feasible trajectory
61+
auto u_optimal = newton_optimizer.optimize(x_feasible[0], x_feasible, Q, R, dt);
6062
const auto end{std::chrono::steady_clock::now()};
6163

6264
const std::chrono::duration<double> elapsed_seconds{end - start};

ilqr_trajectory_tracker/include/ilqr_trajectory_tracker/ilqr_optimizer.hpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -57,11 +57,13 @@ class NewtonOptimizer : public Optimizer
5757

5858
std::tuple<std::vector<typename RobotModel::StateT>,
5959
std::vector<typename RobotModel::InputT>> forwardPass(
60+
const typename RobotModel::StateT & x0,
6061
const std::vector<typename RobotModel::StateT> & x_feasible,
6162
const std::vector<typename RobotModel::InputT> & u_feasible,
6263
const std::vector<MatrixXd> & K_gains, const double dt, const double alpha);
6364

6465
std::vector<typename RobotModel::InputT> optimize(
66+
const typename RobotModel::StateT & x0,
6567
const std::vector<typename RobotModel::StateT> & x_feasible, const Matrix3d & Q,
6668
const Matrix2d & R, const double dt);
6769

@@ -136,6 +138,7 @@ std::vector<MatrixXd> NewtonOptimizer<RobotModel>::backwardPass(
136138
template<typename RobotModel>
137139
std::tuple<std::vector<typename RobotModel::StateT>,
138140
std::vector<typename RobotModel::InputT>> NewtonOptimizer<RobotModel>::forwardPass(
141+
const typename RobotModel::StateT & x0,
139142
const std::vector<typename RobotModel::StateT> & x_feasible,
140143
const std::vector<typename RobotModel::InputT> & u_feasible,
141144
const std::vector<MatrixXd> & K_gains, const double dt, const double alpha)
@@ -147,7 +150,7 @@ std::tuple<std::vector<typename RobotModel::StateT>,
147150
std::vector<typename RobotModel::InputT> u_applied(input_size);
148151

149152
// assert trajectory_size > 0
150-
x_tracked[0] = x_feasible[0];
153+
x_tracked[0] = x0;
151154
for (typename std::vector<typename RobotModel::StateT>::difference_type i = 0,
152155
max_difference = std::distance(x_feasible.begin(), std::prev(x_feasible.end(), 1));
153156
i < max_difference; ++i)
@@ -180,6 +183,7 @@ std::tuple<MatrixXd, MatrixXd> NewtonOptimizer<RobotModel>::solveDiscreteLQRProb
180183

181184
template<typename RobotModel>
182185
std::vector<typename RobotModel::InputT> NewtonOptimizer<RobotModel>::optimize(
186+
const typename RobotModel::StateT & x0,
183187
const std::vector<typename RobotModel::StateT> & x_trajectory, const Matrix3d & Q,
184188
const Matrix2d & R, const double dt)
185189
{
@@ -198,7 +202,7 @@ std::vector<typename RobotModel::InputT> NewtonOptimizer<RobotModel>::optimize(
198202
double previous_best_trajectory_cost = best_trajectory_cost;
199203
for (size_t i = 0; i < iteration_number_; ++i) {
200204
auto K_gain_list = this->backwardPass(x_trajectory, u_optimized, Q, R, dt);
201-
auto [x_tracked, u_tracked] = this->forwardPass(
205+
auto [x_tracked, u_tracked] = this->forwardPass(x0,
202206
x_trajectory, u_optimized, K_gain_list, dt,
203207
alpha);
204208
u_optimized = u_tracked;

nav2_frenet_ilqr_controller/include/nav2_frenet_ilqr_controller/frenet_ilqr_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ class FrenetILQRController : public nav2_core::Controller
110110
nav2_core::GoalChecker * /*goal_checker*/) override;
111111

112112
Vector2d findOptimalInputForTrajectory(
113-
const geometry_msgs::msg::PoseStamped & robot_pose,
113+
const Vector3d & c_state_robot,
114114
const frenet_trajectory_planner::CartesianTrajectory & robot_cartesian_trajectory);
115115

116116
bool cancel() override;

nav2_frenet_ilqr_controller/src/frenet_ilqr_controller.cpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,7 @@ nav_msgs::msg::Path FrenetILQRController::truncateGlobalPlanWithLookAheadDist(
206206
}
207207

208208
Vector2d FrenetILQRController::findOptimalInputForTrajectory(
209-
const geometry_msgs::msg::PoseStamped & /*robot_pose*/,
209+
const Vector3d & c_state_robot,
210210
const frenet_trajectory_planner::CartesianTrajectory & robot_cartesian_trajectory)
211211
{
212212

@@ -242,7 +242,7 @@ Vector2d FrenetILQRController::findOptimalInputForTrajectory(
242242

243243
newton_optimizer.setIterationNumber(20);
244244
newton_optimizer.setAlpha(alpha);
245-
auto U_optimal = newton_optimizer.optimize(X_feasible, Q, R, dt);
245+
auto U_optimal = newton_optimizer.optimize(c_state_robot, X_feasible, Q, R, dt);
246246

247247
if (U_optimal.empty()) {
248248
throw nav2_core::NoValidControl("Iterative LQR couldn't find any solution!");
@@ -319,13 +319,16 @@ geometry_msgs::msg::TwistStamped FrenetILQRController::computeVelocityCommands(
319319
transformed_plan.header.frame_id,
320320
planned_cartesian_trajectory);
321321
frenet_plan = path_handler_->transformPath(costmap_ros_->getBaseFrameID(), frenet_plan);
322-
323322
planned_cartesian_trajectory = convertToCartesianTrajectory(frenet_plan);
324323

325324
truncated_path_pub_->publish(frenet_plan);
326325
robot_pose_pub_->publish(robot_pose);
327326

328-
auto u_opt = findOptimalInputForTrajectory(robot_pose, planned_cartesian_trajectory);
327+
path_handler_->transformPose(costmap_ros_->getBaseFrameID(), robot_pose, robot_pose);
328+
Vector3d c_state_robot;
329+
c_state_robot << robot_pose.pose.position.x, robot_pose.pose.position.y,
330+
tf2::getYaw(robot_pose.pose.orientation);
331+
auto u_opt = findOptimalInputForTrajectory(c_state_robot, planned_cartesian_trajectory);
329332

330333
// populate and return message
331334
geometry_msgs::msg::TwistStamped cmd_vel;

0 commit comments

Comments
 (0)