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
knzo25 authored Jun 7, 2024
2 parents 4ab9207 + 565589c commit f1d57e2
Show file tree
Hide file tree
Showing 325 changed files with 2,213 additions and 1,385 deletions.
5 changes: 3 additions & 2 deletions .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,7 @@ planning/autoware_behavior_velocity_run_out_module/** [email protected] m
planning/autoware_behavior_velocity_template_module/** [email protected]
planning/autoware_behavior_velocity_virtual_traffic_light_module/** [email protected] [email protected] [email protected]
planning/autoware_behavior_velocity_walkway_module/** [email protected] [email protected] [email protected] [email protected]
planning/autoware_costmap_generator/** [email protected] [email protected] [email protected]
planning/autoware_external_velocity_limit_selector/** [email protected] [email protected] [email protected] [email protected] [email protected]
planning/autoware_path_optimizer/** [email protected] [email protected] [email protected]
planning/autoware_planning_test_manager/** [email protected] [email protected]
Expand All @@ -178,11 +179,11 @@ planning/behavior_velocity_no_drivable_lane_module/** [email protected]
planning/behavior_velocity_no_stopping_area_module/** [email protected] [email protected] [email protected]
planning/behavior_velocity_occlusion_spot_module/** [email protected] [email protected] [email protected]
planning/behavior_velocity_out_of_lane_module/** [email protected] [email protected] [email protected] [email protected]
planning/behavior_velocity_planner_common/** [email protected] [email protected] [email protected] [email protected] [email protected]
planning/autoware_behavior_velocity_planner_common/** [email protected] [email protected] [email protected] [email protected] [email protected]
planning/autoware_behavior_velocity_run_out_module/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/behavior_velocity_speed_bump_module/** [email protected] [email protected] [email protected]
planning/behavior_velocity_stop_line_module/** [email protected] [email protected] [email protected] [email protected]
planning/behavior_velocity_traffic_light_module/** [email protected] [email protected] [email protected] [email protected]
planning/costmap_generator/** [email protected] [email protected] [email protected]
planning/freespace_planner/** [email protected] [email protected] [email protected]
planning/freespace_planning_algorithms/** [email protected] [email protected] [email protected]
planning/mission_planner/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
Expand Down
37 changes: 0 additions & 37 deletions .github/workflows/build-and-test-differential.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -74,40 +74,3 @@ jobs:

- name: Show disk space after the tasks
run: df -h

clang-tidy-differential:
runs-on: ubuntu-latest
container: ghcr.io/autowarefoundation/autoware:latest-prebuilt-cuda
steps:
- name: Check out repository
uses: actions/checkout@v4
with:
fetch-depth: 0

- name: Show disk space before the tasks
run: df -h

- name: Remove exec_depend
uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1

- name: Get modified packages
id: get-modified-packages
uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1

- name: Get modified files
id: get-modified-files
uses: tj-actions/changed-files@v35
with:
files: |
**/*.cpp
**/*.hpp
- name: Run clang-tidy
if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }}
uses: autowarefoundation/autoware-github-actions/clang-tidy@v1
with:
rosdistro: humble
target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
target-files: ${{ steps.get-modified-files.outputs.all_changed_files }}
clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy
build-depends-repos: build_depends.repos
51 changes: 51 additions & 0 deletions .github/workflows/clang-tidy-differential.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
name: clang-tidy-differential

on:
pull_request:
types:
- opened
- synchronize
- labeled

jobs:
prevent-no-label-execution:
uses: autowarefoundation/autoware-github-actions/.github/workflows/prevent-no-label-execution.yaml@v1
with:
label: tag:run-clang-tidy-differential

clang-tidy-differential:
runs-on: ubuntu-latest
container: ghcr.io/autowarefoundation/autoware:latest-prebuilt-cuda
steps:
- name: Check out repository
uses: actions/checkout@v4
with:
fetch-depth: 0

- name: Show disk space before the tasks
run: df -h

- name: Remove exec_depend
uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1

- name: Get modified packages
id: get-modified-packages
uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1

- name: Get modified files
id: get-modified-files
uses: tj-actions/changed-files@v35
with:
files: |
**/*.cpp
**/*.hpp
- name: Run clang-tidy
if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }}
uses: autowarefoundation/autoware-github-actions/clang-tidy@v1
with:
rosdistro: humble
target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
target-files: ${{ steps.get-modified-files.outputs.all_changed_files }}
clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy
build-depends-repos: build_depends.repos
2 changes: 1 addition & 1 deletion launch/tier4_planning_launch/launch/planning.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@

<!-- planning validator -->
<group>
<include file="$(find-pkg-share planning_validator)/launch/planning_validator.launch.xml">
<include file="$(find-pkg-share autoware_planning_validator)/launch/planning_validator.launch.xml">
<arg name="input_trajectory" value="/planning/scenario_planning/velocity_smoother/trajectory"/>
<arg name="output_trajectory" value="/planning/scenario_planning/trajectory"/>
<arg name="planning_validator_param_path" value="$(var planning_validator_param_path)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@
<arg name="behavior_velocity_planner_launch_modules" default="["/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::CrosswalkModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::CrosswalkModulePlugin, '&quot;)"
if="$(var launch_crosswalk_module)"
/>
<let
Expand All @@ -111,27 +111,27 @@
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::TrafficLightModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::TrafficLightModulePlugin, '&quot;)"
if="$(var launch_traffic_light_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::IntersectionModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::IntersectionModulePlugin, '&quot;)"
if="$(var launch_intersection_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::MergeFromPrivateModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::MergeFromPrivateModulePlugin, '&quot;)"
if="$(var launch_merge_from_private_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::BlindSpotModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::BlindSpotModulePlugin, '&quot;)"
if="$(var launch_blind_spot_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::DetectionAreaModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::DetectionAreaModulePlugin, '&quot;)"
if="$(var launch_detection_area_module)"
/>
<let
Expand All @@ -141,17 +141,17 @@
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::NoStoppingAreaModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::NoStoppingAreaModulePlugin, '&quot;)"
if="$(var launch_no_stopping_area_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::StopLineModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::StopLineModulePlugin, '&quot;)"
if="$(var launch_stop_line_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::OcclusionSpotModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::OcclusionSpotModulePlugin, '&quot;)"
if="$(var launch_occlusion_spot_module)"
/>
<let
Expand All @@ -161,22 +161,22 @@
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::SpeedBumpModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::SpeedBumpModulePlugin, '&quot;)"
if="$(var launch_speed_bump_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::OutOfLaneModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::OutOfLaneModulePlugin, '&quot;)"
if="$(var launch_out_of_lane_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::NoDrivableLaneModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::NoDrivableLaneModulePlugin, '&quot;)"
if="$(var launch_no_drivable_lane_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::DynamicObstacleStopModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::DynamicObstacleStopModulePlugin, '&quot;)"
if="$(var launch_dynamic_obstacle_stop_module)"
/>
<let name="behavior_velocity_planner_launch_modules" value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + '$(var launch_module_list_end)'&quot;)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@
<group>
<group if="$(eval &quot;'$(var motion_path_planner_type)' == 'path_optimizer'&quot;)">
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
<composable_node pkg="autoware_path_optimizer" plugin="autoware_path_optimizer::PathOptimizer" name="path_optimizer" namespace="">
<composable_node pkg="autoware_path_optimizer" plugin="autoware::path_optimizer::PathOptimizer" name="path_optimizer" namespace="">
<!-- topic remap -->
<remap from="~/input/path" to="path_smoother/path"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<push-ros-namespace namespace="parking"/>

<node_container pkg="rclcpp_components" exec="$(var container_type)" name="parking_container" namespace="" output="screen">
<composable_node pkg="costmap_generator" plugin="CostmapGenerator" name="costmap_generator" namespace="">
<composable_node pkg="autoware_costmap_generator" plugin="autoware::costmap_generator::CostmapGenerator" name="costmap_generator" namespace="">
<!-- topic remap -->
<remap from="~/input/objects" to="/perception/object_recognition/objects"/>
<remap from="~/input/points_no_ground" to="/perception/obstacle_segmentation/pointcloud"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
<!-- motion velocity smoother -->
<group>
<node_container pkg="rclcpp_components" exec="component_container" name="velocity_smoother_container" namespace="">
<composable_node pkg="autoware_velocity_smoother" plugin="autoware_velocity_smoother::VelocitySmootherNode" name="velocity_smoother" namespace="">
<composable_node pkg="autoware_velocity_smoother" plugin="autoware::velocity_smoother::VelocitySmootherNode" name="velocity_smoother" namespace="">
<param name="algorithm_type" value="$(var velocity_smoother_type)"/>
<param from="$(var common_param_path)"/>
<param from="$(var nearest_search_param_path)"/>
Expand Down
4 changes: 2 additions & 2 deletions launch/tier4_planning_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -58,22 +58,22 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>autoware_behavior_velocity_planner</exec_depend>
<exec_depend>autoware_costmap_generator</exec_depend>
<exec_depend>autoware_external_velocity_limit_selector</exec_depend>
<exec_depend>autoware_path_optimizer</exec_depend>
<exec_depend>autoware_planning_topic_converter</exec_depend>
<exec_depend>autoware_planning_validator</exec_depend>
<exec_depend>autoware_remaining_distance_time_calculator</exec_depend>
<exec_depend>autoware_surround_obstacle_checker</exec_depend>
<exec_depend>autoware_velocity_smoother</exec_depend>
<exec_depend>behavior_path_planner</exec_depend>
<exec_depend>costmap_generator</exec_depend>
<exec_depend>external_cmd_selector</exec_depend>
<exec_depend>freespace_planner</exec_depend>
<exec_depend>glog_component</exec_depend>
<exec_depend>mission_planner</exec_depend>
<exec_depend>obstacle_cruise_planner</exec_depend>
<exec_depend>obstacle_stop_planner</exec_depend>
<exec_depend>planning_evaluator</exec_depend>
<exec_depend>planning_validator</exec_depend>
<exec_depend>scenario_selector</exec_depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,14 +30,14 @@ class DiagnosticsModule
public:
DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name);
void clear();
void addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg);
void add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg);
template <typename T>
void addKeyValue(const std::string & key, const T & value);
void updateLevelAndMessage(const int8_t level, const std::string & message);
void add_key_value(const std::string & key, const T & value);
void update_level_and_message(const int8_t level, const std::string & message);
void publish(const rclcpp::Time & publish_time_stamp);

private:
diagnostic_msgs::msg::DiagnosticArray createDiagnosticsArray(
[[nodiscard]] diagnostic_msgs::msg::DiagnosticArray create_diagnostics_array(
const rclcpp::Time & publish_time_stamp) const;

rclcpp::Clock::SharedPtr clock_;
Expand All @@ -47,18 +47,18 @@ class DiagnosticsModule
};

template <typename T>
void DiagnosticsModule::addKeyValue(const std::string & key, const T & value)
void DiagnosticsModule::add_key_value(const std::string & key, const T & value)
{
diagnostic_msgs::msg::KeyValue key_value;
key_value.key = key;
key_value.value = std::to_string(value);
addKeyValue(key_value);
add_key_value(key_value);
}

template <>
void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value);
void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value);
template <>
void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value);
void DiagnosticsModule::add_key_value(const std::string & key, const bool & value);

} // namespace autoware::gyro_odometer

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,13 @@ class GyroOdometerNode : public rclcpp::Node

public:
explicit GyroOdometerNode(const rclcpp::NodeOptions & node_options);
~GyroOdometerNode();

private:
void callbackVehicleTwist(
void callback_vehicle_twist(
const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr vehicle_twist_msg_ptr);
void callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr);
void concatGyroAndOdometer();
void publishData(const geometry_msgs::msg::TwistWithCovarianceStamped & twist_with_cov_raw);
void callback_imu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr);
void concat_gyro_and_odometer();
void publish_data(const geometry_msgs::msg::TwistWithCovarianceStamped & twist_with_cov_raw);

rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr
vehicle_twist_sub_;
Expand Down
16 changes: 8 additions & 8 deletions localization/gyro_odometer/src/diagnostics_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ void DiagnosticsModule::clear()
diagnostics_status_msg_.message = "";
}

void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg)
void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg)
{
auto it = std::find_if(
std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values),
Expand All @@ -58,24 +58,24 @@ void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_v
}

template <>
void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value)
void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value)
{
diagnostic_msgs::msg::KeyValue key_value;
key_value.key = key;
key_value.value = value;
addKeyValue(key_value);
add_key_value(key_value);
}

template <>
void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value)
void DiagnosticsModule::add_key_value(const std::string & key, const bool & value)
{
diagnostic_msgs::msg::KeyValue key_value;
key_value.key = key;
key_value.value = value ? "True" : "False";
addKeyValue(key_value);
add_key_value(key_value);
}

void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::string & message)
void DiagnosticsModule::update_level_and_message(const int8_t level, const std::string & message)
{
if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) {
if (!diagnostics_status_msg_.message.empty()) {
Expand All @@ -90,10 +90,10 @@ void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::str

void DiagnosticsModule::publish(const rclcpp::Time & publish_time_stamp)
{
diagnostics_pub_->publish(createDiagnosticsArray(publish_time_stamp));
diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp));
}

diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::createDiagnosticsArray(
diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::create_diagnostics_array(
const rclcpp::Time & publish_time_stamp) const
{
diagnostic_msgs::msg::DiagnosticArray diagnostics_msg;
Expand Down
Loading

0 comments on commit f1d57e2

Please sign in to comment.