Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Oct 16, 2024
1 parent 0e9c316 commit ff0ed49
Show file tree
Hide file tree
Showing 38 changed files with 166 additions and 111 deletions.
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 COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
#define COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_

#include <rclcpp/qos.hpp>

Expand Down Expand Up @@ -67,4 +67,4 @@ struct IsStopped

} // namespace autoware::component_interface_specs::control_interface

#endif // COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_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 COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#define COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_

#include <rclcpp/qos.hpp>

Expand Down Expand Up @@ -60,4 +60,4 @@ struct Acceleration

} // namespace autoware::component_interface_specs::localization_interface

#endif // COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_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 COMPONENT_INTERFACE_SPECS__MAP_HPP_
#define COMPONENT_INTERFACE_SPECS__MAP_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_

#include <rclcpp/qos.hpp>

Expand All @@ -33,4 +33,4 @@ struct MapProjectorInfo

} // namespace autoware::component_interface_specs::map_interface

#endif // COMPONENT_INTERFACE_SPECS__MAP_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_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 COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#define COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_

#include <rclcpp/qos.hpp>

Expand All @@ -33,4 +33,4 @@ struct ObjectRecognition

} // namespace autoware::component_interface_specs::perception_interface

#endif // COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_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 COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#define COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_

#include <rclcpp/qos.hpp>

Expand Down Expand Up @@ -75,4 +75,4 @@ struct Trajectory

} // namespace autoware::component_interface_specs::planning_interface

#endif // COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_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 COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_
#define COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_

#include <rclcpp/qos.hpp>

Expand Down Expand Up @@ -57,4 +57,4 @@ struct OperationModeState

} // namespace autoware::component_interface_specs::system_interface

#endif // COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_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 COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#define COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_

#include <rclcpp/qos.hpp>

Expand Down Expand Up @@ -97,4 +97,4 @@ struct DoorStatus

} // namespace autoware::component_interface_specs::vehicle_interface

#endif // COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@
#ifndef AUTOWARE_TEST_UTILS__AUTOWARE_TEST_UTILS_HPP_
#define AUTOWARE_TEST_UTILS__AUTOWARE_TEST_UTILS_HPP_

#include <autoware/component_interface_specs/planning.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware_lanelet2_extension/io/autoware_osm_parser.hpp>
#include <autoware_lanelet2_extension/projection/mgrs_projector.hpp>
#include <autoware_lanelet2_extension/utility/message_conversion.hpp>
#include <autoware_lanelet2_extension/utility/utilities.hpp>
#include <autoware/component_interface_specs/planning.hpp>

#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_test_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,14 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>ament_index_cpp</depend>
<depend>autoware_component_interface_specs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>lanelet2_io</depend>
<depend>nav_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<build_depend>rosidl_default_generators</build_depend>

<depend>autoware_component_interface_specs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
Expand Down
11 changes: 7 additions & 4 deletions control/autoware_operation_mode_transition_manager/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
#include "compatibility.hpp"
#include "state.hpp"

#include <autoware/universe_utils/ros/polling_subscriber.hpp>
#include <autoware/component_interface_specs/system.hpp>
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
#include <component_interface_utils/rclcpp.hpp>
#include <rclcpp/rclcpp.hpp>

Expand All @@ -35,9 +35,12 @@ class OperationModeTransitionManager : public rclcpp::Node
explicit OperationModeTransitionManager(const rclcpp::NodeOptions & options);

private:
using ChangeAutowareControlAPI = autoware::component_interface_specs::system_interface::ChangeAutowareControl;
using ChangeOperationModeAPI = autoware::component_interface_specs::system_interface::ChangeOperationMode;
using OperationModeStateAPI = autoware::component_interface_specs::system_interface::OperationModeState;
using ChangeAutowareControlAPI =
autoware::component_interface_specs::system_interface::ChangeAutowareControl;
using ChangeOperationModeAPI =
autoware::component_interface_specs::system_interface::ChangeOperationMode;
using OperationModeStateAPI =
autoware::component_interface_specs::system_interface::OperationModeState;
component_interface_utils::Service<ChangeAutowareControlAPI>::SharedPtr srv_autoware_control_;
component_interface_utils::Service<ChangeOperationModeAPI>::SharedPtr srv_operation_mode_;
component_interface_utils::Publisher<OperationModeStateAPI>::SharedPtr pub_operation_mode_;
Expand Down
2 changes: 1 addition & 1 deletion control/autoware_vehicle_cmd_gate/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,12 @@
<build_depend>rosidl_default_generators</build_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>diagnostic_updater</depend>
<depend>geometry_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,13 @@
#ifndef PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_
#define PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_

#include <autoware/component_interface_specs/control.hpp>
#include <autoware/motion_utils/trajectory/conversion.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/ros/self_pose_listener.hpp>
#include <autoware_vehicle_info_utils/vehicle_info.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <autoware/component_interface_specs/control.hpp>
#include <component_interface_utils/rclcpp.hpp>
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <predicted_path_checker/collision_checker.hpp>
Expand Down Expand Up @@ -96,10 +96,12 @@ class PredictedPathCheckerNode : public rclcpp::Node
sub_predicted_trajectory_;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
rclcpp::Subscription<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr sub_accel_;
component_interface_utils::Subscription<autoware::component_interface_specs::control_interface::IsStopped>::SharedPtr sub_stop_state_;
component_interface_utils::Subscription<
autoware::component_interface_specs::control_interface::IsStopped>::SharedPtr sub_stop_state_;

// Client
component_interface_utils::Client<autoware::component_interface_specs::control_interface::SetStop>::SharedPtr cli_set_stop_;
component_interface_utils::Client<
autoware::component_interface_specs::control_interface::SetStop>::SharedPtr cli_set_stop_;

// Data Buffer
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_;
Expand All @@ -108,7 +110,8 @@ class PredictedPathCheckerNode : public rclcpp::Node
PredictedObjects::ConstSharedPtr object_ptr_{nullptr};
autoware_planning_msgs::msg::Trajectory::ConstSharedPtr reference_trajectory_;
autoware_planning_msgs::msg::Trajectory::ConstSharedPtr predicted_trajectory_;
autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr is_stopped_ptr_{nullptr};
autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr
is_stopped_ptr_{nullptr};

// Core
std::unique_ptr<CollisionChecker> collision_checker_;
Expand All @@ -126,7 +129,9 @@ class PredictedPathCheckerNode : public rclcpp::Node
void onPredictedTrajectory(const autoware_planning_msgs::msg::Trajectory::SharedPtr msg);
void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg);
void onAccel(const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg);
void onIsStopped(const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr msg);
void onIsStopped(
const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr
msg);

// Timer
rclcpp::TimerBase::SharedPtr timer_;
Expand Down
2 changes: 1 addition & 1 deletion control/predicted_path_checker/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_component_interface_specs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>boost</depend>
<depend>autoware_component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>diagnostic_updater</depend>
<depend>eigen</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,8 @@ void PredictedPathCheckerNode::onAccel(
}

void PredictedPathCheckerNode::onIsStopped(
const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr msg)
const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr
msg)
{
is_stopped_ptr_ = msg;

Expand Down Expand Up @@ -415,7 +416,8 @@ void PredictedPathCheckerNode::checkVehicleState(diagnostic_updater::DiagnosticS
void PredictedPathCheckerNode::sendRequest(bool make_stop_vehicle)
{
if (!is_calling_set_stop_ && cli_set_stop_->service_is_ready()) {
const auto req = std::make_shared<autoware::component_interface_specs::control_interface::SetStop::Service::Request>();
const auto req = std::make_shared<
autoware::component_interface_specs::control_interface::SetStop::Service::Request>();
req->stop = make_stop_vehicle;
req->request_source = "predicted_path_checker";
is_calling_set_stop_ = true;
Expand Down
2 changes: 1 addition & 1 deletion localization/autoware_geo_pose_projector/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_geography_utils</depend>
<depend>autoware_component_interface_specs</depend>
<depend>autoware_geography_utils</depend>
<depend>component_interface_utils</depend>
<depend>geographic_msgs</depend>
<depend>geometry_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion localization/autoware_pose_initializer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,11 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_component_interface_specs</depend>
<depend>autoware_localization_util</depend>
<depend>autoware_map_height_fitter</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@

#include "autoware/localization_util/diagnostics_module.hpp"

#include <autoware/universe_utils/ros/logger_level_configure.hpp>
#include <autoware/component_interface_specs/localization.hpp>
#include <autoware/universe_utils/ros/logger_level_configure.hpp>
#include <component_interface_utils/rclcpp.hpp>
#include <rclcpp/rclcpp.hpp>

Expand Down
2 changes: 1 addition & 1 deletion map/autoware_map_projection_loader/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_lanelet2_extension</depend>
<depend>autoware_component_interface_specs</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>component_interface_utils</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
#define MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_

#include <autoware_lanelet2_extension/version.hpp>
#include <autoware/component_interface_specs/map.hpp>
#include <autoware_lanelet2_extension/version.hpp>
#include <component_interface_utils/rclcpp.hpp>
#include <rclcpp/rclcpp.hpp>

Expand Down
2 changes: 1 addition & 1 deletion map/map_loader/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,10 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_component_interface_specs</depend>
<depend>autoware_geography_utils</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>fmt</depend>
<depend>geometry_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_planning_test_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_component_interface_specs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_map_msgs</depend>
Expand All @@ -23,7 +24,6 @@
<depend>autoware_test_utils</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>lanelet2_io</depend>
<depend>nav_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion sensing/autoware_gnss_poser/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@

<build_depend>libboost-dev</build_depend>

<depend>autoware_component_interface_specs</depend>
<depend>autoware_geography_utils</depend>
<depend>autoware_sensing_msgs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>geographic_msgs</depend>
<depend>geographiclib</depend>
Expand Down
2 changes: 1 addition & 1 deletion system/autoware_default_adapi/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,13 @@
<depend>autoware_ad_api_specs</depend>
<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_adapi_version_msgs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>autoware_geography_utils</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_system_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>autoware_component_interface_specs</depend>
<depend>component_interface_utils</depend>
<depend>diagnostic_graph_utils</depend>
<depend>geographic_msgs</depend>
Expand Down
Loading

0 comments on commit ff0ed49

Please sign in to comment.