Skip to content

Commit

Permalink
fix: apply pre-commit fix
Browse files Browse the repository at this point in the history
Signed-off-by: mitsudome-r <[email protected]>
  • Loading branch information
mitsudome-r committed Feb 27, 2025
1 parent c09d6be commit df5688b
Show file tree
Hide file tree
Showing 7 changed files with 15 additions and 17 deletions.
2 changes: 1 addition & 1 deletion common/autoware_test_utils/src/autoware_test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,13 @@
// limitations under the License.

#include <ament_index_cpp/get_package_share_directory.hpp>
#include <autoware_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_test_utils/autoware_test_utils.hpp>
#include <autoware_test_utils/mock_data_parser.hpp>
#include <autoware_utils/geometry/geometry.hpp>
#include <rclcpp/node.hpp>

#include <lanelet2_core/geometry/LineString.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,8 +107,8 @@ class CostmapGenerator : public rclcpp::Node
this, "~/input/points_no_ground", autoware_utils::single_depth_sensor_qos()};
autoware_utils::InterProcessPollingSubscriber<PredictedObjects> sub_objects_{
this, "~/input/objects"};
autoware_utils::InterProcessPollingSubscriber<tier4_planning_msgs::msg::Scenario>
sub_scenario_{this, "~/input/scenario"};
autoware_utils::InterProcessPollingSubscriber<tier4_planning_msgs::msg::Scenario> sub_scenario_{
this, "~/input/scenario"};

rclcpp::TimerBase::SharedPtr timer_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_
#define AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_
#include <autoware/route_handler/route_handler.hpp>
#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_test_utils/autoware_test_utils.hpp>
#include <autoware_utils/geometry/geometry.hpp>

#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <geometry_msgs/msg/pose.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,6 @@
#include "autoware/motion_utils/trajectory/path_with_lane_id.hpp"

#include <autoware/motion_utils/resample/resample.hpp>
#include <autoware_utils/geometry/boost_geometry.hpp>
#include <autoware_utils/geometry/boost_polygon_utils.hpp>
#include <autoware_utils/math/unit_conversion.hpp>
#include <autoware_lanelet2_extension/utility/message_conversion.hpp>
#include <autoware_lanelet2_extension/utility/query.hpp>
#include <autoware_lanelet2_extension/utility/utilities.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,8 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
get_or_declare_parameter<bool>(node, ns + ".enable_pass_judge");
planner_param_.yellow_lamp_period =
get_or_declare_parameter<double>(node, ns + ".yellow_lamp_period");
planner_param_.v2i_use_rest_time = get_or_declare_parameter<bool>(node, ns + ".v2i.use_rest_time");
planner_param_.v2i_use_rest_time =
get_or_declare_parameter<bool>(node, ns + ".v2i.use_rest_time");
planner_param_.v2i_last_time_allowed_to_pass =
get_or_declare_parameter<double>(node, ns + ".v2i.last_time_allowed_to_pass");
planner_param_.v2i_velocity_threshold =
Expand All @@ -58,9 +59,9 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)

if (planner_param_.v2i_use_rest_time) {
RCLCPP_INFO(logger_, "V2I is enabled");
v2i_subscriber_ = autoware_utils::InterProcessPollingSubscriber<
jpn_signal_v2i_msgs::msg::TrafficLightInfo>::
create_subscription(&node, "/v2i/external/v2i_traffic_light_info", 1);
v2i_subscriber_ =
autoware_utils::InterProcessPollingSubscriber<jpn_signal_v2i_msgs::msg::TrafficLightInfo>::
create_subscription(&node, "/v2i/external/v2i_traffic_light_info", 1);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,10 +69,10 @@ struct ObstacleFilteringParam
{
object_types =
utils::get_target_object_type(node, "obstacle_slow_down.obstacle_filtering.object_type.");
min_lat_margin =
get_or_declare_parameter<double>(node, "obstacle_slow_down.obstacle_filtering.min_lat_margin");
max_lat_margin =
get_or_declare_parameter<double>(node, "obstacle_slow_down.obstacle_filtering.max_lat_margin");
min_lat_margin = get_or_declare_parameter<double>(
node, "obstacle_slow_down.obstacle_filtering.min_lat_margin");
max_lat_margin = get_or_declare_parameter<double>(
node, "obstacle_slow_down.obstacle_filtering.max_lat_margin");
lat_hysteresis_margin = get_or_declare_parameter<double>(
node, "obstacle_slow_down.obstacle_filtering.lat_hysteresis_margin");
successive_num_to_entry_slow_down_condition = get_or_declare_parameter<int>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,8 +93,8 @@ struct ObstacleFilteringParam
utils::get_target_object_type(node, "obstacle_stop.obstacle_filtering.object_type.inside.");
outside_stop_object_types =
utils::get_target_object_type(node, "obstacle_stop.obstacle_filtering.object_type.outside.");
use_pointcloud =
get_or_declare_parameter<bool>(node, "obstacle_stop.obstacle_filtering.object_type.pointcloud");
use_pointcloud = get_or_declare_parameter<bool>(
node, "obstacle_stop.obstacle_filtering.object_type.pointcloud");

obstacle_velocity_threshold_to_stop = get_or_declare_parameter<double>(
node, "obstacle_stop.obstacle_filtering.obstacle_velocity_threshold_to_stop");
Expand Down

0 comments on commit df5688b

Please sign in to comment.