Skip to content

Commit

Permalink
Merge branch 'main' into feat/lidar_transfusion
Browse files Browse the repository at this point in the history
  • Loading branch information
amadeuszsz authored Jun 7, 2024
2 parents 61d4fc1 + ce0fcf5 commit 7044c30
Show file tree
Hide file tree
Showing 42 changed files with 96 additions and 94 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(mpc_lateral_controller)
project(autoware_mpc_lateral_controller)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_
#define MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_

#include <algorithm>
#include <cmath>
Expand Down Expand Up @@ -102,4 +102,4 @@ namespace MoveAverageFilter
bool filt_vector(const int num, std::vector<double> & u);
} // namespace MoveAverageFilter
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__MPC_HPP_
#define MPC_LATERAL_CONTROLLER__MPC_HPP_

#include "mpc_lateral_controller/lowpass_filter.hpp"
#include "mpc_lateral_controller/mpc_trajectory.hpp"
#include "mpc_lateral_controller/qp_solver/qp_solver_interface.hpp"
#include "mpc_lateral_controller/steering_predictor.hpp"
#include "mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp"
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_HPP_

#include "autoware_mpc_lateral_controller/lowpass_filter.hpp"
#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp"
#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 "rclcpp/rclcpp.hpp"

#include "autoware_control_msgs/msg/lateral.hpp"
Expand Down Expand Up @@ -525,4 +525,4 @@ class MPC
}; // class MPC
} // namespace autoware::motion::control::mpc_lateral_controller

#endif // MPC_LATERAL_CONTROLLER__MPC_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_
#define MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_

#include "mpc_lateral_controller/mpc.hpp"
#include "mpc_lateral_controller/mpc_trajectory.hpp"
#include "mpc_lateral_controller/mpc_utils.hpp"
#include "mpc_lateral_controller/steering_offset/steering_offset.hpp"
#include "autoware_mpc_lateral_controller/mpc.hpp"
#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp"
#include "autoware_mpc_lateral_controller/mpc_utils.hpp"
#include "autoware_mpc_lateral_controller/steering_offset/steering_offset.hpp"
#include "rclcpp/rclcpp.hpp"
#include "trajectory_follower_base/lateral_controller_base.hpp"

Expand Down Expand Up @@ -281,4 +281,4 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
};
} // namespace autoware::motion::control::mpc_lateral_controller

#endif // MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_
#define MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_

#include "tier4_autoware_utils/geometry/geometry.hpp"

Expand Down Expand Up @@ -125,4 +125,4 @@ class MPCTrajectory
}
};
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_
#define MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_

#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"
Expand All @@ -26,7 +26,7 @@
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#endif

#include "mpc_lateral_controller/mpc_trajectory.hpp"
#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp"

#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
Expand Down Expand Up @@ -230,4 +230,4 @@ void update_param(

} // namespace MPCUtils
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_
#define MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_

#include <Eigen/Core>

Expand Down Expand Up @@ -51,4 +51,4 @@ class QPSolverInterface
virtual double getObjVal() const { return 0.0; }
};
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_
#define MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_

#include "mpc_lateral_controller/qp_solver/qp_solver_interface.hpp"
#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_interface.hpp"
#include "osqp_interface/osqp_interface.hpp"
#include "rclcpp/rclcpp.hpp"

Expand Down Expand Up @@ -62,4 +62,4 @@ class QPSolverOSQP : public QPSolverInterface
rclcpp::Logger logger_;
};
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_
#define MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_

#include "mpc_lateral_controller/qp_solver/qp_solver_interface.hpp"
#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_interface.hpp"

namespace autoware::motion::control::mpc_lateral_controller
{
Expand Down Expand Up @@ -62,4 +62,4 @@ class QPSolverEigenLeastSquareLLT : public QPSolverInterface
private:
};
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_
#define MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_

#include <geometry_msgs/msg/twist.hpp>

Expand Down Expand Up @@ -45,4 +45,4 @@ class SteeringOffsetEstimator
double steering_offset_ = 0.0;
};

#endif // MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_
#define MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_

#include "rclcpp/rclcpp.hpp"

Expand Down Expand Up @@ -81,4 +81,4 @@ class SteeringPredictor

} // namespace autoware::motion::control::mpc_lateral_controller

#endif // MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,10 @@
* Tracking", Robotics Institute, Carnegie Mellon University, February 2009.
*/

#ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_
#define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_

#include "mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp"
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp"

#include <Eigen/Core>
#include <Eigen/LU>
Expand Down Expand Up @@ -122,4 +122,4 @@ class DynamicsBicycleModel : public VehicleModelInterface
double m_cr; //!< @brief rear cornering power [N/rad]
};
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@
*
*/

#ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_
#define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_

#include "mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp"
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp"

#include <Eigen/Core>
#include <Eigen/LU>
Expand Down Expand Up @@ -106,4 +106,4 @@ class KinematicsBicycleModel : public VehicleModelInterface
double m_steer_tau; //!< @brief steering time constant for 1d-model [s]
};
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@
*
*/

#ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_
#define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_ // NOLINT
#define AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_ // NOLINT

#include "mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp"
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp"

#include <Eigen/Core>
#include <Eigen/LU>
Expand Down Expand Up @@ -101,4 +101,6 @@ class KinematicsBicycleModelNoDelay : public VehicleModelInterface
double m_steer_lim; //!< @brief steering angle limit [rad]
};
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_
// clang-format off
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_ // NOLINT
// clang-format on
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_
#define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_
#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_
#define AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_

#include "mpc_lateral_controller/mpc_trajectory.hpp"
#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp"

#include <Eigen/Core>

Expand Down Expand Up @@ -149,4 +149,4 @@ class VehicleModelInterface
const MPCTrajectory & reference_trajectory, const double dt) const = 0;
};
} // namespace autoware::motion::control::mpc_lateral_controller
#endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_
#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>mpc_lateral_controller</name>
<name>autoware_mpc_lateral_controller</name>
<version>1.0.0</version>
<description>MPC-based lateral controller</description>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mpc_lateral_controller/lowpass_filter.hpp"
#include "autoware_mpc_lateral_controller/lowpass_filter.hpp"

#include <vector>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mpc_lateral_controller/mpc.hpp"
#include "autoware_mpc_lateral_controller/mpc.hpp"

#include "autoware_mpc_lateral_controller/mpc_utils.hpp"
#include "interpolation/linear_interpolation.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "mpc_lateral_controller/mpc_utils.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tier4_autoware_utils/math/unit_conversion.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mpc_lateral_controller/mpc_lateral_controller.hpp"
#include "autoware_mpc_lateral_controller/mpc_lateral_controller.hpp"

#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp"
#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp"
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp"
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp"
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp"
#include "mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp"
#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp"
#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp"
#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp"
#include "tf2/utils.h"
#include "tf2_ros/create_timer_ros.h"
#include "vehicle_info_util/vehicle_info_util.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mpc_lateral_controller/mpc_trajectory.hpp"
#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp"

namespace autoware::motion::control::mpc_lateral_controller
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mpc_lateral_controller/mpc_utils.hpp"
#include "autoware_mpc_lateral_controller/mpc_utils.hpp"

#include "interpolation/linear_interpolation.hpp"
#include "interpolation/spline_interpolation.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp"
#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp"

#include <string>
#include <vector>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp"
#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp"

#include <Eigen/Dense>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mpc_lateral_controller/steering_offset/steering_offset.hpp"
#include "autoware_mpc_lateral_controller/steering_offset/steering_offset.hpp"

#include <algorithm>
#include <iostream>
Expand Down
Loading

0 comments on commit 7044c30

Please sign in to comment.