Skip to content

Commit

Permalink
Merge branch 'main' into mau/refactor/localization/localization_error…
Browse files Browse the repository at this point in the history
…_monitor
  • Loading branch information
SakodaShintaro committed Jun 10, 2024
2 parents 4af048f + 420c6bd commit 50ea679
Show file tree
Hide file tree
Showing 1,015 changed files with 9,153 additions and 6,976 deletions.
68 changes: 37 additions & 31 deletions .github/CODEOWNERS

Large diffs are not rendered by default.

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://github.com/autowarefoundation/autoware/main/.clang-tidy
build-depends-repos: build_depends.repos
53 changes: 53 additions & 0 deletions .github/workflows/clang-tidy-differential.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
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:
needs: prevent-no-label-execution
if: ${{ needs.prevent-no-label-execution.outputs.run == 'true' }}
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://github.com/autowarefoundation/autoware/main/.clang-tidy
build-depends-repos: build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ def launch_setup(context, *args, **kwargs):

load_vehicle_info = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[FindPackageShare("vehicle_info_util"), "/launch/vehicle_info.launch.py"]
[FindPackageShare("autoware_vehicle_info_utils"), "/launch/vehicle_info.launch.py"]
),
launch_arguments={
"vehicle_info_param_file": [vehicle_description_pkg, "/config/vehicle_info.param.yaml"]
Expand Down
2 changes: 1 addition & 1 deletion common/global_parameter_loader/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>vehicle_info_util</exec_depend>
<exec_depend>autoware_vehicle_info_utils</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,14 @@ namespace tier4_autoware_utils
template <typename T>
class InterProcessPollingSubscriber
{
public:
using SharedPtr = std::shared_ptr<InterProcessPollingSubscriber<T>>;
static SharedPtr create_subscription(
rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos = rclcpp::QoS{1})
{
return std::make_shared<InterProcessPollingSubscriber<T>>(node, topic_name, qos);
}

private:
typename rclcpp::Subscription<T>::SharedPtr subscriber_;
typename T::SharedPtr data_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,9 @@ class TransformListener
try {
tf = tf_buffer_->lookupTransform(from, to, tf2::TimePointZero);
} catch (tf2::TransformException & ex) {
RCLCPP_WARN(
logger_, "failed to get transform from %s to %s: %s", from.c_str(), to.c_str(), ex.what());
RCLCPP_WARN_THROTTLE(
logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(),
to.c_str(), ex.what());
return {};
}

Expand All @@ -64,8 +65,9 @@ class TransformListener
try {
tf = tf_buffer_->lookupTransform(from, to, time, duration);
} catch (tf2::TransformException & ex) {
RCLCPP_WARN(
logger_, "failed to get transform from %s to %s: %s", from.c_str(), to.c_str(), ex.what());
RCLCPP_WARN_THROTTLE(
logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(),
to.c_str(), ex.what());
return {};
}

Expand Down
2 changes: 1 addition & 1 deletion common/tier4_localization_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_vehicle_info_utils</depend>
<depend>geometry_msgs</depend>
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
Expand All @@ -20,7 +21,6 @@
<depend>rviz_common</depend>
<depend>rviz_default_plugins</depend>
<depend>tf2_ros</depend>
<depend>vehicle_info_util</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ void PoseHistoryFootprint::updateFootprint()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_THROTTLE(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_
#define POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_

#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rviz_common/message_filter_display.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <geometry_msgs/msg/pose_stamped.hpp>

Expand All @@ -39,8 +39,8 @@ class BoolProperty;
namespace rviz_plugins
{

using vehicle_info_util::VehicleInfo;
using vehicle_info_util::VehicleInfoUtil;
using autoware::vehicle_info_utils::VehicleInfo;
using autoware::vehicle_info_utils::VehicleInfoUtils;

class PoseHistoryFootprint
: public rviz_common::MessageFilterDisplay<geometry_msgs::msg::PoseStamped>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_
#define TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_

#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rviz_common/display_context.hpp>
#include <rviz_common/frame_manager_iface.hpp>
Expand All @@ -25,7 +26,6 @@
#include <rviz_common/properties/parse_color.hpp>
#include <rviz_common/validate_floats.hpp>
#include <rviz_rendering/objects/movable_text.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_planning_msgs/msg/path.hpp>

Expand Down Expand Up @@ -97,8 +97,8 @@ bool validateFloats(const typename T::ConstSharedPtr & msg_ptr)

namespace rviz_plugins
{
using vehicle_info_util::VehicleInfo;
using vehicle_info_util::VehicleInfoUtil;
using autoware::vehicle_info_utils::VehicleInfo;
using autoware::vehicle_info_utils::VehicleInfoUtils;
template <typename T>
class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay<T>
{
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_planning_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
<depend>libqt5-widgets</depend>
Expand All @@ -25,7 +26,6 @@
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_planning_msgs</depend>
<depend>vehicle_info_util</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
6 changes: 3 additions & 3 deletions common/tier4_planning_rviz_plugin/src/path/display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ void AutowarePathWithLaneIdDisplay::preProcessMessageDetail()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_ONCE(
Expand Down Expand Up @@ -107,7 +107,7 @@ void AutowarePathDisplay::preProcessMessageDetail()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_ONCE(
Expand All @@ -124,7 +124,7 @@ void AutowareTrajectoryDisplay::preProcessMessageDetail()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_ONCE(
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(autonomous_emergency_braking)
project(autoware_autonomous_emergency_braking)

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

#ifndef AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
#define AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
#ifndef AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
#define AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_

#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <motion_utils/trajectory/trajectory.hpp>
#include <pcl_ros/transforms.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/polling_subscriber.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <autoware_system_msgs/msg/autoware_state.hpp>
Expand Down Expand Up @@ -59,11 +59,11 @@ using nav_msgs::msg::Odometry;
using sensor_msgs::msg::Imu;
using sensor_msgs::msg::PointCloud2;
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
using autoware::vehicle_info_utils::VehicleInfo;
using diagnostic_updater::DiagnosticStatusWrapper;
using diagnostic_updater::Updater;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
using vehicle_info_util::VehicleInfo;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
using Path = std::vector<geometry_msgs::msg::Pose>;
Expand Down Expand Up @@ -340,4 +340,4 @@ class AEB : public rclcpp::Node
};
} // namespace autoware::motion::control::autonomous_emergency_braking

#endif // AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
#endif // AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
<launch>
<arg name="param_path" default="$(find-pkg-share autonomous_emergency_braking)/config/autonomous_emergency_braking.param.yaml"/>
<arg name="param_path" default="$(find-pkg-share autoware_autonomous_emergency_braking)/config/autonomous_emergency_braking.param.yaml"/>
<arg name="input_pointcloud" default="/perception/obstacle_segmentation/pointcloud"/>
<arg name="input_velocity" default="/vehicle/status/velocity_status"/>
<arg name="input_imu" default="/sensing/imu/imu_data"/>
<arg name="input_odometry" default="/localization/kinematic_state"/>
<arg name="input_predicted_trajectory" default="/control/trajectory_follower/lateral/predicted_trajectory"/>

<node pkg="autonomous_emergency_braking" exec="autonomous_emergency_braking" name="autonomous_emergency_braking" output="screen">
<node pkg="autoware_autonomous_emergency_braking" exec="autoware_autonomous_emergency_braking" name="autonomous_emergency_braking" output="screen">
<!-- load config files -->
<param from="$(var param_path)"/>
<!-- remap topic name -->
Expand Down
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>autonomous_emergency_braking</name>
<name>autoware_autonomous_emergency_braking</name>
<version>0.1.0</version>
<description>Autonomous Emergency Braking package as a ROS 2 node</description>
<maintainer email="takamasa.horibe@tier4.jp">Takamasa Horibe</maintainer>
Expand All @@ -17,6 +17,7 @@
<depend>autoware_control_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_system_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>diagnostic_updater</depend>
<depend>geometry_msgs</depend>
Expand All @@ -34,7 +35,6 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
<depend>vehicle_info_util</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
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 "autonomous_emergency_braking/node.hpp"
#include "autoware_autonomous_emergency_braking/node.hpp"

#include <pcl_ros/transforms.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>
Expand Down Expand Up @@ -60,7 +60,7 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point &

Polygon2d createPolygon(
const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & next_pose,
const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width)
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double expand_width)
{
Polygon2d polygon;

Expand Down Expand Up @@ -102,7 +102,7 @@ Polygon2d createPolygon(

AEB::AEB(const rclcpp::NodeOptions & node_options)
: Node("AEB", node_options),
vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()),
vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()),
collision_data_keeper_(this->get_clock())
{
// Publisher
Expand Down
Loading

0 comments on commit 50ea679

Please sign in to comment.