Skip to content

Commit

Permalink
feat(trajectory_follower): publsih control horzion
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 committed Sep 27, 2024
1 parent 070e4ee commit 4728922
Show file tree
Hide file tree
Showing 11 changed files with 243 additions and 22 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "autoware/mpc_lateral_controller/qp_solver/qp_solver_interface.hpp"
#include "autoware/mpc_lateral_controller/steering_predictor.hpp"
#include "autoware/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp"
#include "autoware/trajectory_follower_base/control_horizon.hpp"
#include "rclcpp/rclcpp.hpp"

#include "autoware_control_msgs/msg/lateral.hpp"
Expand All @@ -38,6 +39,7 @@
namespace autoware::motion::control::mpc_lateral_controller
{

using autoware::motion::control::trajectory_follower::LateralHorizon;
using autoware_control_msgs::msg::Lateral;
using autoware_planning_msgs::msg::Trajectory;
using autoware_vehicle_msgs::msg::SteeringReport;
Expand Down Expand Up @@ -450,7 +452,8 @@ class MPC
*/
bool calculateMPC(
const SteeringReport & current_steer, const Odometry & current_kinematics, Lateral & ctrl_cmd,
Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic);
Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic,
LateralHorizon & ctrl_cmd_horizon);

/**
* @brief Set the reference trajectory to be followed.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "autoware/trajectory_follower_base/lateral_controller_base.hpp"
#include "rclcpp/rclcpp.hpp"

#include <autoware/trajectory_follower_base/control_horizon.hpp>
#include <diagnostic_updater/diagnostic_updater.hpp>

#include "autoware_control_msgs/msg/lateral.hpp"
Expand Down Expand Up @@ -49,6 +50,7 @@ using autoware_vehicle_msgs::msg::SteeringReport;
using nav_msgs::msg::Odometry;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using tier4_debug_msgs::msg::Float32Stamped;
using trajectory_follower::LateralHorizon;

class MpcLateralController : public trajectory_follower::LateralControllerBase
{
Expand Down Expand Up @@ -214,6 +216,13 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
*/
Lateral createCtrlCmdMsg(const Lateral & ctrl_cmd);

/**
* @brief Create the control command horizon message.
* @param ctrl_cmd_horizion Control command horizon to be created.

Check warning on line 221 in control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (horizion)
* @return Created control command horizon.
*/
LateralHorizon createCtrlCmdHorizonMsg(const LateralHorizon & ctrl_cmd_horizion) const;

Check warning on line 224 in control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (horizion)

/**
* @brief Publish the predicted future trajectory.
* @param predicted_traj Predicted future trajectory to be published.
Expand Down
16 changes: 15 additions & 1 deletion control/autoware_mpc_lateral_controller/src/mpc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ MPC::MPC(rclcpp::Node & node)

bool MPC::calculateMPC(
const SteeringReport & current_steer, const Odometry & current_kinematics, Lateral & ctrl_cmd,
Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic)
Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic,
LateralHorizon & ctrl_cmd_horizon)
{
// since the reference trajectory does not take into account the current velocity of the ego
// vehicle, it needs to calculate the trajectory velocity considering the longitudinal dynamics.
Expand Down Expand Up @@ -124,6 +125,19 @@ bool MPC::calculateMPC(
diagnostic =
generateDiagData(reference_trajectory, mpc_data, mpc_matrix, ctrl_cmd, Uex, current_kinematics);

// create LateralHorizon command
ctrl_cmd_horizon.time_step_ms = prediction_dt * 1000.0;
ctrl_cmd_horizon.controls.push_back(ctrl_cmd);
for (auto it = std::next(Uex.begin()); it != Uex.end(); ++it) {
Lateral lateral{};
lateral.steering_tire_angle = static_cast<float>(std::clamp(*it, -m_steer_lim, m_steer_lim));
lateral.steering_tire_rotation_rate =
(lateral.steering_tire_angle - ctrl_cmd_horizon.controls.back().steering_tire_angle) /
m_ctrl_period;

ctrl_cmd_horizon.controls.push_back(lateral);
}

Check notice on line 140 in control/autoware_mpc_lateral_controller/src/mpc.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Excess Number of Function Arguments

MPC::calculateMPC increases from 5 to 6 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.
return true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -276,8 +276,10 @@ trajectory_follower::LateralOutput MpcLateralController::run(
m_is_ctrl_cmd_prev_initialized = true;
}

trajectory_follower::LateralHorizon ctrl_cmd_horizon{};
const bool is_mpc_solved = m_mpc->calculateMPC(
m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values);
m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values,
ctrl_cmd_horizon);

m_is_mpc_solved = is_mpc_solved; // for diagnostic updater

Expand All @@ -304,9 +306,13 @@ trajectory_follower::LateralOutput MpcLateralController::run(
publishPredictedTraj(predicted_traj);
publishDebugValues(debug_values);

const auto createLateralOutput = [this](const auto & cmd, const bool is_mpc_solved) {
const auto createLateralOutput =
[this](
const auto & cmd, const bool is_mpc_solved,
const auto & cmd_horion) -> trajectory_follower::LateralOutput {

Check warning on line 312 in control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (horion)
trajectory_follower::LateralOutput output;
output.control_cmd = createCtrlCmdMsg(cmd);
output.control_cmd_horizon = createCtrlCmdHorizonMsg(cmd_horion);

Check warning on line 315 in control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (horion)
// To be sure current steering of the vehicle is desired steering angle, we need to check
// following conditions.
// 1. At the last loop, mpc should be solved because command should be optimized output.
Expand All @@ -325,7 +331,7 @@ trajectory_follower::LateralOutput MpcLateralController::run(
}
// Use previous command value as previous raw steer command
m_mpc->m_raw_steer_cmd_prev = m_ctrl_cmd_prev.steering_tire_angle;
return createLateralOutput(m_ctrl_cmd_prev, false);
return createLateralOutput(m_ctrl_cmd_prev, false, ctrl_cmd_horizon);
}

if (!is_mpc_solved) {
Expand All @@ -334,7 +340,7 @@ trajectory_follower::LateralOutput MpcLateralController::run(
}

m_ctrl_cmd_prev = ctrl_cmd;
return createLateralOutput(ctrl_cmd, is_mpc_solved);
return createLateralOutput(ctrl_cmd, is_mpc_solved, ctrl_cmd_horizon);
}

bool MpcLateralController::isSteerConverged(const Lateral & cmd) const
Expand Down Expand Up @@ -465,6 +471,17 @@ Lateral MpcLateralController::createCtrlCmdMsg(const Lateral & ctrl_cmd)
return out;
}

LateralHorizon MpcLateralController::createCtrlCmdHorizonMsg(
const LateralHorizon & ctrl_cmd_horizion) const

Check warning on line 475 in control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (horizion)
{
auto out = ctrl_cmd_horizion;

Check warning on line 477 in control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (horizion)
const auto now = clock_->now();
for (auto & cmd : out.controls) {
cmd.stamp = now;
}
return out;
}

void MpcLateralController::publishPredictedTraj(Trajectory & predicted_traj) const
{
predicted_traj.header.stamp = clock_->now();
Expand Down
39 changes: 26 additions & 13 deletions control/autoware_mpc_lateral_controller/test/test_mpc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include "gtest/gtest.h"
#include "rclcpp/rclcpp.hpp"

#include <autoware/trajectory_follower_base/control_horizon.hpp>

#include "autoware_control_msgs/msg/lateral.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
Expand All @@ -41,6 +43,7 @@
namespace autoware::motion::control::mpc_lateral_controller
{

using autoware::motion::control::trajectory_follower::LateralHorizon;
using autoware_control_msgs::msg::Lateral;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
Expand Down Expand Up @@ -209,8 +212,9 @@ TEST_F(MPCTest, InitializeAndCalculate)
Lateral ctrl_cmd;
Trajectory pred_traj;
Float32MultiArrayStamped diag;
LateralHorizon ctrl_cmd_horizon;
const auto odom = makeOdometry(pose_zero, default_velocity);
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
}
Expand Down Expand Up @@ -241,8 +245,9 @@ TEST_F(MPCTest, InitializeAndCalculateRightTurn)
Lateral ctrl_cmd;
Trajectory pred_traj;
Float32MultiArrayStamped diag;
LateralHorizon ctrl_cmd_horizon;
const auto odom = makeOdometry(pose_zero, default_velocity);
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
}
Expand All @@ -268,8 +273,9 @@ TEST_F(MPCTest, OsqpCalculate)
Lateral ctrl_cmd;
Trajectory pred_traj;
Float32MultiArrayStamped diag;
LateralHorizon ctrl_cmd_horizon;
const auto odom = makeOdometry(pose_zero, default_velocity);
EXPECT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
EXPECT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
}
Expand All @@ -296,8 +302,9 @@ TEST_F(MPCTest, OsqpCalculateRightTurn)
Lateral ctrl_cmd;
Trajectory pred_traj;
Float32MultiArrayStamped diag;
LateralHorizon ctrl_cmd_horizon;
const auto odom = makeOdometry(pose_zero, default_velocity);
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
}
Expand Down Expand Up @@ -326,8 +333,9 @@ TEST_F(MPCTest, KinematicsNoDelayCalculate)
Lateral ctrl_cmd;
Trajectory pred_traj;
Float32MultiArrayStamped diag;
LateralHorizon ctrl_cmd_horizon;
const auto odom = makeOdometry(pose_zero, default_velocity);
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
}
Expand Down Expand Up @@ -357,8 +365,9 @@ TEST_F(MPCTest, KinematicsNoDelayCalculateRightTurn)
Lateral ctrl_cmd;
Trajectory pred_traj;
Float32MultiArrayStamped diag;
LateralHorizon ctrl_cmd_horizon;
const auto odom = makeOdometry(pose_zero, default_velocity);
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
}
Expand All @@ -382,8 +391,9 @@ TEST_F(MPCTest, DynamicCalculate)
Lateral ctrl_cmd;
Trajectory pred_traj;
Float32MultiArrayStamped diag;
LateralHorizon ctrl_cmd_horizon;
const auto odom = makeOdometry(pose_zero, default_velocity);
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
}
Expand All @@ -406,21 +416,22 @@ TEST_F(MPCTest, MultiSolveWithBuffer)
Lateral ctrl_cmd;
Trajectory pred_traj;
Float32MultiArrayStamped diag;
LateralHorizon ctrl_cmd_horizon;
const auto odom = makeOdometry(pose_zero, default_velocity);

ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));
EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f);
EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f);
EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3));
Expand All @@ -446,11 +457,13 @@ TEST_F(MPCTest, FailureCases)
Lateral ctrl_cmd;
Trajectory pred_traj;
Float32MultiArrayStamped diag;
LateralHorizon ctrl_cmd_horizon;
const auto odom = makeOdometry(pose_far, default_velocity);
EXPECT_FALSE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag));
EXPECT_FALSE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon));

// Calculate MPC with a fast velocity to make the prediction go further than the reference path
EXPECT_FALSE(mpc->calculateMPC(
neutral_steer, makeOdometry(pose_far, default_velocity + 10.0), ctrl_cmd, pred_traj, diag));
neutral_steer, makeOdometry(pose_far, default_velocity + 10.0), ctrl_cmd, pred_traj, diag,
ctrl_cmd_horizon));
}
} // namespace autoware::motion::control::mpc_lateral_controller
Original file line number Diff line number Diff line change
Expand Up @@ -433,6 +433,8 @@ trajectory_follower::LongitudinalOutput PidLongitudinalController::run(
publishDebugData(raw_ctrl_cmd, control_data); // publish debug data
trajectory_follower::LongitudinalOutput output;
output.control_cmd = cmd_msg;
output.control_cmd_horizon.controls.push_back(cmd_msg);
output.control_cmd_horizon.time_step_ms = 0.0;
return output;
}

Expand All @@ -442,11 +444,15 @@ trajectory_follower::LongitudinalOutput PidLongitudinalController::run(
// calculate control command
const Motion ctrl_cmd = calcCtrlCmd(control_data);

// publish control command
// create control command
const auto cmd_msg = createCtrlCmdMsg(ctrl_cmd, control_data.current_motion.vel);
trajectory_follower::LongitudinalOutput output;
output.control_cmd = cmd_msg;

// create control command horizon
output.control_cmd_horizon.controls.push_back(cmd_msg);
output.control_cmd_horizon.time_step_ms = 0.0;

// publish debug data
publishDebugData(ctrl_cmd, control_data);

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright 2024 The Autoware Foundation
//
// 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 AUTOWARE__TRAJECTORY_FOLLOWER_BASE__CONTROL_HORIZON_HPP_
#define AUTOWARE__TRAJECTORY_FOLLOWER_BASE__CONTROL_HORIZON_HPP_

#include "autoware_control_msgs/msg/lateral.hpp"
#include "autoware_control_msgs/msg/longitudinal.hpp"

#include <vector>

namespace autoware::motion::control::trajectory_follower
{

using autoware_control_msgs::msg::Lateral;
using autoware_control_msgs::msg::Longitudinal;

struct LateralHorizon
{
double time_step_ms;
std::vector<Lateral> controls;
};

struct LongitudinalHorizon
{
double time_step_ms;
std::vector<Longitudinal> controls;
};

} // namespace autoware::motion::control::trajectory_follower
#endif // AUTOWARE__TRAJECTORY_FOLLOWER_BASE__CONTROL_HORIZON_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef AUTOWARE__TRAJECTORY_FOLLOWER_BASE__LATERAL_CONTROLLER_BASE_HPP_
#define AUTOWARE__TRAJECTORY_FOLLOWER_BASE__LATERAL_CONTROLLER_BASE_HPP_

#include "autoware/trajectory_follower_base/control_horizon.hpp"
#include "autoware/trajectory_follower_base/input_data.hpp"
#include "autoware/trajectory_follower_base/sync_data.hpp"
#include "rclcpp/rclcpp.hpp"
Expand All @@ -24,9 +25,11 @@
#include <boost/optional.hpp>
namespace autoware::motion::control::trajectory_follower
{
using autoware_control_msgs::msg::Lateral;
struct LateralOutput
{
autoware_control_msgs::msg::Lateral control_cmd;
Lateral control_cmd;
LateralHorizon control_cmd_horizon;
LateralSyncData sync_data;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef AUTOWARE__TRAJECTORY_FOLLOWER_BASE__LONGITUDINAL_CONTROLLER_BASE_HPP_
#define AUTOWARE__TRAJECTORY_FOLLOWER_BASE__LONGITUDINAL_CONTROLLER_BASE_HPP_

#include "autoware/trajectory_follower_base/control_horizon.hpp"
#include "autoware/trajectory_follower_base/input_data.hpp"
#include "autoware/trajectory_follower_base/sync_data.hpp"
#include "rclcpp/rclcpp.hpp"
Expand All @@ -25,9 +26,11 @@

namespace autoware::motion::control::trajectory_follower
{
using autoware_control_msgs::msg::Longitudinal;
struct LongitudinalOutput
{
autoware_control_msgs::msg::Longitudinal control_cmd;
Longitudinal control_cmd;
LongitudinalHorizon control_cmd_horizon;
LongitudinalSyncData sync_data;
};
class LongitudinalControllerBase
Expand Down
Loading

0 comments on commit 4728922

Please sign in to comment.