Skip to content

Commit c824d56

Browse files
committed
chore: run pre-commit to format files
Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
1 parent 64e5bf1 commit c824d56

File tree

272 files changed

+833
-1009
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

272 files changed

+833
-1009
lines changed

common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,8 @@
1010
<buildtool_depend>ament_cmake</buildtool_depend>
1111
<buildtool_depend>rosidl_default_generators</buildtool_depend>
1212

13-
<depend>autoware_vehicle_msgs</depend>
1413
<depend>autoware_perception_msgs</depend>
14+
<depend>autoware_vehicle_msgs</depend>
1515
<depend>std_msgs</depend>
1616
<depend>unique_identifier_msgs</depend>
1717
<exec_depend>rosidl_default_runtime</exec_depend>

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md

+6-6
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,13 @@ This plugin provides a visual and easy-to-understand display of vehicle speed, t
1515

1616
| Name | Type | Description |
1717
| ------------------------------------------------------- | ------------------------------------------------------- | ------------------------------------ |
18-
| `/vehicle/status/velocity_status` | `autoware_vehicle_msgs::msg::VelocityReport` | The topic is vehicle velocity |
19-
| `/vehicle/status/turn_indicators_status` | `autoware_vehicle_msgs::msg::TurnIndicatorsReport` | The topic is status of turn signal |
20-
| `/vehicle/status/hazard_status` | `autoware_vehicle_msgs::msg::HazardReport` | The topic is status of hazard |
21-
| `/vehicle/status/steering_status` | `autoware_vehicle_msgs::msg::SteeringReport` | The topic is status of steering |
22-
| `/vehicle/status/gear_status` | `autoware_vehicle_msgs::msg::GearReport` | The topic is status of gear |
18+
| `/vehicle/status/velocity_status` | `autoware_vehicle_msgs::msg::VelocityReport` | The topic is vehicle velocity |
19+
| `/vehicle/status/turn_indicators_status` | `autoware_vehicle_msgs::msg::TurnIndicatorsReport` | The topic is status of turn signal |
20+
| `/vehicle/status/hazard_status` | `autoware_vehicle_msgs::msg::HazardReport` | The topic is status of hazard |
21+
| `/vehicle/status/steering_status` | `autoware_vehicle_msgs::msg::SteeringReport` | The topic is status of steering |
22+
| `/vehicle/status/gear_status` | `autoware_vehicle_msgs::msg::GearReport` | The topic is status of gear |
2323
| `/planning/scenario_planning/current_max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | The topic is velocity limit |
24-
| `/perception/traffic_light_recognition/traffic_signals` | `autoware_perception_msgs::msg::TrafficLightGroupArray` | The topic is status of traffic light |
24+
| `/perception/traffic_light_recognition/traffic_signals` | `autoware_perception_msgs::msg::TrafficLightGroupArray` | The topic is status of traffic light |
2525

2626
## Parameter
2727

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -102,14 +102,14 @@ private Q_SLOTS:
102102
turn_signals_sub_;
103103
rclcpp::Subscription<autoware_vehicle_msgs::msg::HazardLightsReport>::SharedPtr
104104
hazard_lights_sub_;
105-
rclcpp::Subscription<autoware_perception_msgs::msg::TrafficLightGroupArray>::SharedPtr traffic_sub_;
105+
rclcpp::Subscription<autoware_perception_msgs::msg::TrafficLightGroupArray>::SharedPtr
106+
traffic_sub_;
106107
rclcpp::Subscription<tier4_planning_msgs::msg::VelocityLimit>::SharedPtr speed_limit_sub_;
107108

108109
std::mutex property_mutex_;
109110

110111
void updateGearData(const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr & msg);
111-
void updateSteeringData(
112-
const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & msg);
112+
void updateSteeringData(const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & msg);
113113
void updateSpeedData(const autoware_vehicle_msgs::msg::VelocityReport::ConstSharedPtr & msg);
114114
void updateTurnSignalsData(
115115
const autoware_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr & msg);

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/steering_wheel_display.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,7 @@ class SteeringWheelDisplay
3737
public:
3838
SteeringWheelDisplay();
3939
void drawSteeringWheel(QPainter & painter, const QRectF & backgroundRect);
40-
void updateSteeringData(
41-
const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & msg);
40+
void updateSteeringData(const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & msg);
4241

4342
private:
4443
float steering_angle_ = 0.0f;

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -23,9 +23,9 @@
2323
#include <rviz_common/properties/int_property.hpp>
2424
#include <rviz_common/ros_topic_display.hpp>
2525

26+
#include <autoware_perception_msgs/msg/traffic_light_element.hpp>
2627
#include <autoware_perception_msgs/msg/traffic_light_group.hpp>
2728
#include <autoware_perception_msgs/msg/traffic_light_group_array.hpp>
28-
#include <autoware_perception_msgs/msg/traffic_light_element.hpp>
2929

3030
#include <OgreColourValue.h>
3131
#include <OgreMaterial.h>

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -11,9 +11,9 @@
1111

1212
<license>BSD-3-Clause</license>
1313

14-
<depend>autoware_vehicle_msgs</depend>
1514
<depend>autoware_overlay_msgs</depend>
1615
<depend>autoware_perception_msgs</depend>
16+
<depend>autoware_vehicle_msgs</depend>
1717
<depend>boost</depend>
1818
<depend>rviz_common</depend>
1919
<depend>rviz_ogre_vendor</depend>

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,7 @@ GearDisplay::GearDisplay() : current_gear_(0)
4949
}
5050
}
5151

52-
void GearDisplay::updateGearData(
53-
const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr & msg)
52+
void GearDisplay::updateGearData(const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr & msg)
5453
{
5554
current_gear_ = msg->report; // Assuming msg->report contains the gear information
5655
}

common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp

+29-34
Original file line numberDiff line numberDiff line change
@@ -87,15 +87,13 @@ void SignalDisplay::onInitialize()
8787
turn_signals_topic_property_->initialize(rviz_ros_node);
8888

8989
speed_topic_property_ = std::make_unique<rviz_common::properties::RosTopicProperty>(
90-
"Speed Topic", "/vehicle/status/velocity_status",
91-
"autoware_vehicle_msgs/msg/VelocityReport", "Topic for Speed Data", this,
92-
SLOT(topic_updated_speed()));
90+
"Speed Topic", "/vehicle/status/velocity_status", "autoware_vehicle_msgs/msg/VelocityReport",
91+
"Topic for Speed Data", this, SLOT(topic_updated_speed()));
9392
speed_topic_property_->initialize(rviz_ros_node);
9493

9594
steering_topic_property_ = std::make_unique<rviz_common::properties::RosTopicProperty>(
96-
"Steering Topic", "/vehicle/status/steering_status",
97-
"autoware_vehicle_msgs/msg/SteeringReport", "Topic for Steering Data", this,
98-
SLOT(topic_updated_steering()));
95+
"Steering Topic", "/vehicle/status/steering_status", "autoware_vehicle_msgs/msg/SteeringReport",
96+
"Topic for Steering Data", this, SLOT(topic_updated_steering()));
9997
steering_topic_property_->initialize(rviz_ros_node);
10098

10199
hazard_lights_topic_property_ = std::make_unique<rviz_common::properties::RosTopicProperty>(
@@ -112,8 +110,8 @@ void SignalDisplay::onInitialize()
112110

113111
traffic_topic_property_ = std::make_unique<rviz_common::properties::RosTopicProperty>(
114112
"Traffic Topic", "/perception/traffic_light_recognition/traffic_signals",
115-
"autoware_perception_msgs/msgs/msg/TrafficLightGroupArray", "Topic for Traffic Light Data", this,
116-
SLOT(topic_updated_traffic()));
113+
"autoware_perception_msgs/msgs/msg/TrafficLightGroupArray", "Topic for Traffic Light Data",
114+
this, SLOT(topic_updated_traffic()));
117115
traffic_topic_property_->initialize(rviz_ros_node);
118116
}
119117

@@ -125,9 +123,7 @@ void SignalDisplay::setupRosSubscriptions()
125123
gear_sub_ = rviz_node_->create_subscription<autoware_vehicle_msgs::msg::GearReport>(
126124
gear_topic_property_->getTopicStd(),
127125
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
128-
[this](const autoware_vehicle_msgs::msg::GearReport::SharedPtr msg) {
129-
updateGearData(msg);
130-
});
126+
[this](const autoware_vehicle_msgs::msg::GearReport::SharedPtr msg) { updateGearData(msg); });
131127

132128
steering_sub_ = rviz_node_->create_subscription<autoware_vehicle_msgs::msg::SteeringReport>(
133129
steering_topic_property_->getTopicStd(),
@@ -159,12 +155,13 @@ void SignalDisplay::setupRosSubscriptions()
159155
updateHazardLightsData(msg);
160156
});
161157

162-
traffic_sub_ = rviz_node_->create_subscription<autoware_perception_msgs::msg::TrafficLightGroupArray>(
163-
traffic_topic_property_->getTopicStd(),
164-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
165-
[this](const autoware_perception_msgs::msg::TrafficLightGroupArray::SharedPtr msg) {
166-
updateTrafficLightData(msg);
167-
});
158+
traffic_sub_ =
159+
rviz_node_->create_subscription<autoware_perception_msgs::msg::TrafficLightGroupArray>(
160+
traffic_topic_property_->getTopicStd(),
161+
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
162+
[this](const autoware_perception_msgs::msg::TrafficLightGroupArray::SharedPtr msg) {
163+
updateTrafficLightData(msg);
164+
});
168165

169166
speed_limit_sub_ = rviz_node_->create_subscription<tier4_planning_msgs::msg::VelocityLimit>(
170167
speed_limit_topic_property_->getTopicStd(),
@@ -422,37 +419,35 @@ void SignalDisplay::topic_updated_gear()
422419
rviz_ros_node->get_raw_node()->create_subscription<autoware_vehicle_msgs::msg::GearReport>(
423420
gear_topic_property_->getTopicStd(),
424421
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
425-
[this](const autoware_vehicle_msgs::msg::GearReport::SharedPtr msg) {
426-
updateGearData(msg);
427-
});
422+
[this](const autoware_vehicle_msgs::msg::GearReport::SharedPtr msg) { updateGearData(msg); });
428423
}
429424

430425
void SignalDisplay::topic_updated_steering()
431426
{
432427
// resubscribe to the topic
433428
steering_sub_.reset();
434429
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
435-
steering_sub_ = rviz_ros_node->get_raw_node()
436-
->create_subscription<autoware_vehicle_msgs::msg::SteeringReport>(
437-
steering_topic_property_->getTopicStd(),
438-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
439-
[this](const autoware_vehicle_msgs::msg::SteeringReport::SharedPtr msg) {
440-
updateSteeringData(msg);
441-
});
430+
steering_sub_ =
431+
rviz_ros_node->get_raw_node()->create_subscription<autoware_vehicle_msgs::msg::SteeringReport>(
432+
steering_topic_property_->getTopicStd(),
433+
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
434+
[this](const autoware_vehicle_msgs::msg::SteeringReport::SharedPtr msg) {
435+
updateSteeringData(msg);
436+
});
442437
}
443438

444439
void SignalDisplay::topic_updated_speed()
445440
{
446441
// resubscribe to the topic
447442
speed_sub_.reset();
448443
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
449-
speed_sub_ = rviz_ros_node->get_raw_node()
450-
->create_subscription<autoware_vehicle_msgs::msg::VelocityReport>(
451-
speed_topic_property_->getTopicStd(),
452-
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
453-
[this](const autoware_vehicle_msgs::msg::VelocityReport::SharedPtr msg) {
454-
updateSpeedData(msg);
455-
});
444+
speed_sub_ =
445+
rviz_ros_node->get_raw_node()->create_subscription<autoware_vehicle_msgs::msg::VelocityReport>(
446+
speed_topic_property_->getTopicStd(),
447+
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
448+
[this](const autoware_vehicle_msgs::msg::VelocityReport::SharedPtr msg) {
449+
updateSpeedData(msg);
450+
});
456451
}
457452

458453
void SignalDisplay::topic_updated_speed_limit()

common/autoware_perception_rviz_plugin/README.md

+4-4
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,8 @@ Example:
1919

2020
#### Input Types
2121

22-
| Name | Type | Description |
23-
| ---- | ----------------------------------------------------- | ---------------------- |
22+
| Name | Type | Description |
23+
| ---- | ------------------------------------------------ | ---------------------- |
2424
| | `autoware_perception_msgs::msg::DetectedObjects` | detection result array |
2525

2626
#### Visualization Result
@@ -31,8 +31,8 @@ Example:
3131

3232
#### Input Types
3333

34-
| Name | Type | Description |
35-
| ---- | ---------------------------------------------------- | --------------------- |
34+
| Name | Type | Description |
35+
| ---- | ----------------------------------------------- | --------------------- |
3636
| | `autoware_perception_msgs::msg::TrackedObjects` | tracking result array |
3737

3838
#### Visualization Result

common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -62,17 +62,15 @@ const std::map<
6262
autoware_perception_msgs::msg::ObjectClassification::_label_type, ObjectPropertyValues>
6363
// Color map is based on cityscapes color
6464
kDefaultObjectPropertyValues = {
65-
{autoware_perception_msgs::msg::ObjectClassification::UNKNOWN,
66-
{"UNKNOWN", {255, 255, 255}}},
65+
{autoware_perception_msgs::msg::ObjectClassification::UNKNOWN, {"UNKNOWN", {255, 255, 255}}},
6766
{autoware_perception_msgs::msg::ObjectClassification::CAR, {"CAR", {30, 144, 255}}},
6867
{autoware_perception_msgs::msg::ObjectClassification::BUS, {"BUS", {30, 144, 255}}},
6968
{autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN,
7069
{"PEDESTRIAN", {255, 192, 203}}},
7170
{autoware_perception_msgs::msg::ObjectClassification::BICYCLE, {"CYCLIST", {119, 11, 32}}},
7271
{autoware_perception_msgs::msg::ObjectClassification::MOTORCYCLE,
7372
{"MOTORCYCLE", {119, 11, 32}}},
74-
{autoware_perception_msgs::msg::ObjectClassification::TRAILER,
75-
{"TRAILER", {30, 144, 255}}},
73+
{autoware_perception_msgs::msg::ObjectClassification::TRAILER, {"TRAILER", {30, 144, 255}}},
7674
{autoware_perception_msgs::msg::ObjectClassification::TRUCK, {"TRUCK", {30, 144, 255}}}};
7775

7876
/// \brief Convert the given polygon into a marker representing the shape in 3d

common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -666,7 +666,7 @@ void calc_2d_bounding_box_bottom_line_list(
666666
const double width_half = shape.dimensions.y * 0.5;
667667
const double height_half = shape.dimensions.z * 0.5;
668668
geometry_msgs::msg::Point point;
669-
669+
670670
// bounding box corner points
671671
// top surface, clockwise
672672
const double point_list[4][3] = {

common/component_interface_specs/include/component_interface_specs/planning.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,8 @@
1717

1818
#include <rclcpp/qos.hpp>
1919

20-
#include <autoware_planning_msgs/msg/trajectory.hpp>
2120
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
21+
#include <autoware_planning_msgs/msg/trajectory.hpp>
2222
#include <tier4_planning_msgs/msg/route_state.hpp>
2323
#include <tier4_planning_msgs/srv/clear_route.hpp>
2424
#include <tier4_planning_msgs/srv/set_lanelet_route.hpp>

common/component_interface_specs/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,9 @@
1212
<buildtool_depend>autoware_cmake</buildtool_depend>
1313

1414
<depend>autoware_adapi_v1_msgs</depend>
15-
<depend>autoware_vehicle_msgs</depend>
1615
<depend>autoware_perception_msgs</depend>
1716
<depend>autoware_planning_msgs</depend>
17+
<depend>autoware_vehicle_msgs</depend>
1818
<depend>nav_msgs</depend>
1919
<depend>rcl</depend>
2020
<depend>rclcpp</depend>

common/motion_utils/include/motion_utils/resample/resample.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,8 @@
1616
#define MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_
1717

1818
#include "autoware_planning_msgs/msg/path.hpp"
19-
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"
2019
#include "autoware_planning_msgs/msg/trajectory.hpp"
20+
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"
2121

2222
#include <vector>
2323

common/motion_utils/include/motion_utils/trajectory/conversion.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -16,10 +16,10 @@
1616
#define MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_
1717

1818
#include "autoware_planning_msgs/msg/detail/path__struct.hpp"
19-
#include "tier4_planning_msgs/msg/detail/path_with_lane_id__struct.hpp"
2019
#include "autoware_planning_msgs/msg/detail/trajectory__struct.hpp"
2120
#include "autoware_planning_msgs/msg/detail/trajectory_point__struct.hpp"
2221
#include "std_msgs/msg/header.hpp"
22+
#include "tier4_planning_msgs/msg/detail/path_with_lane_id__struct.hpp"
2323

2424
#include <vector>
2525

@@ -95,8 +95,7 @@ inline TrajectoryPoints convertToTrajectoryPoints(
9595
}
9696

9797
template <class T>
98-
tier4_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId(
99-
[[maybe_unused]] const T & input)
98+
tier4_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId([[maybe_unused]] const T & input)
10099
{
101100
static_assert(sizeof(T) == 0, "Only specializations of convertToPathWithLaneId can be used.");
102101
throw std::logic_error("Only specializations of convertToPathWithLaneId can be used.");

common/motion_utils/include/motion_utils/trajectory/interpolation.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,8 @@
1717

1818
#include "tier4_autoware_utils/geometry/geometry.hpp"
1919

20-
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"
2120
#include "autoware_planning_msgs/msg/trajectory.hpp"
21+
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"
2222

2323
#include <boost/optional.hpp>
2424

0 commit comments

Comments
 (0)