Skip to content

Commit df61189

Browse files
committed
pre-commit
Signed-off-by: Zhe Shen <lucidshenzhe@gmail.com>
1 parent e84dc8c commit df61189

File tree

4 files changed

+16
-13
lines changed

4 files changed

+16
-13
lines changed

control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp

+6-3
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,8 @@
2222
#include "autoware/trajectory_follower_base/lateral_controller_base.hpp"
2323
#include "rclcpp/rclcpp.hpp"
2424

25+
#include <diagnostic_updater/diagnostic_updater.hpp>
26+
2527
#include "autoware_control_msgs/msg/lateral.hpp"
2628
#include "autoware_planning_msgs/msg/trajectory.hpp"
2729
#include "autoware_vehicle_msgs/msg/steering_report.hpp"
@@ -31,7 +33,6 @@
3133
#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
3234
#include "tier4_debug_msgs/msg/float32_stamped.hpp"
3335

34-
#include <diagnostic_updater/diagnostic_updater.hpp>
3536
#include <deque>
3637
#include <memory>
3738
#include <string>
@@ -53,7 +54,8 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
5354
{
5455
public:
5556
/// \param node Reference to the node used only for the component and parameter initialization.
56-
explicit MpcLateralController(rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater);
57+
explicit MpcLateralController(
58+
rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater);
5759
virtual ~MpcLateralController();
5860

5961
private:
@@ -64,7 +66,8 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
6466
rclcpp::Publisher<Float32MultiArrayStamped>::SharedPtr m_pub_debug_values;
6567
rclcpp::Publisher<Float32Stamped>::SharedPtr m_pub_steer_offset;
6668

67-
std::shared_ptr<diagnostic_updater::Updater> diag_updater_{}; // Diagnostic updater for publishing diagnostic data.
69+
std::shared_ptr<diagnostic_updater::Updater>
70+
diag_updater_{}; // Diagnostic updater for publishing diagnostic data.
6871

6972
//!< @brief parameters for path smoothing
7073
TrajectoryFilteringParam m_trajectory_filtering_param;

control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

+5-8
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,8 @@
3535
namespace autoware::motion::control::mpc_lateral_controller
3636
{
3737

38-
MpcLateralController::MpcLateralController(rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater)
38+
MpcLateralController::MpcLateralController(
39+
rclcpp::Node & node, std::shared_ptr<diagnostic_updater::Updater> diag_updater)
3940
: clock_(node.get_clock()), logger_(node.get_logger().get_child("lateral_controller"))
4041
{
4142
const auto dp_int = [&](const std::string & s) { return node.declare_parameter<int>(s); };
@@ -231,8 +232,7 @@ std::shared_ptr<SteeringOffsetEstimator> MpcLateralController::createSteerOffset
231232
return steering_offset_;
232233
}
233234

234-
void MpcLateralController::setStatus(
235-
diagnostic_updater::DiagnosticStatusWrapper & stat)
235+
void MpcLateralController::setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat)
236236
{
237237
if (m_is_mpc_solved) {
238238
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "MPC succeeded.");
@@ -247,10 +247,7 @@ void MpcLateralController::setupDiag()
247247
auto & d = diag_updater_;
248248
d->setHardwareID("mpc_lateral_controller");
249249

250-
d->add("MPC_solve_checker", [&](auto & stat) {
251-
setStatus(
252-
stat);
253-
});
250+
d->add("MPC_solve_checker", [&](auto & stat) { setStatus(stat); });
254251
}
255252

256253
trajectory_follower::LateralOutput MpcLateralController::run(
@@ -281,7 +278,7 @@ trajectory_follower::LateralOutput MpcLateralController::run(
281278
const bool is_mpc_solved = m_mpc->calculateMPC(
282279
m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values);
283280

284-
m_is_mpc_solved = is_mpc_solved; // for diagnostic updater
281+
m_is_mpc_solved = is_mpc_solved; // for diagnostic updater
285282

286283
diag_updater_->force_update();
287284

control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,9 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node
7474
double timeout_thr_sec_;
7575
boost::optional<LongitudinalOutput> longitudinal_output_{boost::none};
7676

77-
std::shared_ptr<diagnostic_updater::Updater> diag_updater_ = std::make_shared<diagnostic_updater::Updater>(this); // Diagnostic updater for publishing diagnostic data.
77+
std::shared_ptr<diagnostic_updater::Updater> diag_updater_ =
78+
std::make_shared<diagnostic_updater::Updater>(
79+
this); // Diagnostic updater for publishing diagnostic data.
7880

7981
std::shared_ptr<trajectory_follower::LongitudinalControllerBase> longitudinal_controller_;
8082
std::shared_ptr<trajectory_follower::LateralControllerBase> lateral_controller_;

control/autoware_trajectory_follower_node/src/controller_node.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,8 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control
3939
getLateralControllerMode(declare_parameter<std::string>("lateral_controller_mode"));
4040
switch (lateral_controller_mode) {
4141
case LateralControllerMode::MPC: {
42-
lateral_controller_ = std::make_shared<mpc_lateral_controller::MpcLateralController>(*this, diag_updater_);
42+
lateral_controller_ =
43+
std::make_shared<mpc_lateral_controller::MpcLateralController>(*this, diag_updater_);
4344
break;
4445
}
4546
case LateralControllerMode::PURE_PURSUIT: {

0 commit comments

Comments
 (0)