Skip to content

Commit

Permalink
feat!: replace autoware_auto_msgs with autoware_msgs
Browse files Browse the repository at this point in the history
Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>
  • Loading branch information
mitsudome-r committed Apr 25, 2024
1 parent 425e122 commit c013e83
Show file tree
Hide file tree
Showing 30 changed files with 106 additions and 122 deletions.
4 changes: 0 additions & 4 deletions build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,6 @@ repositories:
type: git
url: https://github.com/autowarefoundation/autoware_internal_msgs.git
version: main
core/external/autoware_auto_msgs:
type: git
url: https://github.com/tier4/autoware_auto_msgs.git
version: tier4/main
# universe
universe/autoware.universe:
type: git
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <motion_utils/trajectory/trajectory.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <tier4_debug_msgs/msg/float32_stamped.hpp>

Expand All @@ -36,15 +36,15 @@ class LateralErrorPublisher : public rclcpp::Node
double yaw_threshold_to_search_closest_;

/* States */
autoware_auto_planning_msgs::msg::Trajectory::SharedPtr
autoware_planning_msgs::msg::Trajectory::SharedPtr
current_trajectory_ptr_; //!< @brief reference trajectory
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr
current_vehicle_pose_ptr_; //!< @brief current EKF pose
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr
current_ground_truth_pose_ptr_; //!< @brief current GNSS pose

/* Publishers and Subscribers */
rclcpp::Subscription<autoware_auto_planning_msgs::msg::Trajectory>::SharedPtr
rclcpp::Subscription<autoware_planning_msgs::msg::Trajectory>::SharedPtr
sub_trajectory_; //!< @brief subscription for reference trajectory
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
sub_vehicle_pose_; //!< @brief subscription for vehicle pose
Expand All @@ -60,7 +60,7 @@ class LateralErrorPublisher : public rclcpp::Node
/**
* @brief set current_trajectory_ with received message
*/
void onTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr);
void onTrajectory(const autoware_planning_msgs::msg::Trajectory::SharedPtr);
/**
* @brief set current_vehicle_pose_ with received message
*/
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_debug_tools/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>

<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
<depend>rclcpp</depend>
Expand Down
4 changes: 2 additions & 2 deletions common/tier4_debug_tools/src/lateral_error_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ LateralErrorPublisher::LateralErrorPublisher(const rclcpp::NodeOptions & node_op
declare_parameter("yaw_threshold_to_search_closest", M_PI / 4.0);

/* Publishers and Subscribers */
sub_trajectory_ = create_subscription<autoware_auto_planning_msgs::msg::Trajectory>(
sub_trajectory_ = create_subscription<autoware_planning_msgs::msg::Trajectory>(
"~/input/reference_trajectory", rclcpp::QoS{1},
std::bind(&LateralErrorPublisher::onTrajectory, this, _1));
sub_vehicle_pose_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
Expand All @@ -44,7 +44,7 @@ LateralErrorPublisher::LateralErrorPublisher(const rclcpp::NodeOptions & node_op
}

void LateralErrorPublisher::onTrajectory(
const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg)
const autoware_planning_msgs::msg::Trajectory::SharedPtr msg)
{
current_trajectory_ptr_ = msg;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@

#include <route_handler/route_handler.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>
Expand All @@ -36,9 +36,9 @@

namespace driving_environment_analyzer
{
using autoware_auto_mapping_msgs::msg::HADMapBin;
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_map_msgs::msg::LaneletMapBin;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_planning_msgs::msg::LaneletRoute;
using geometry_msgs::msg::AccelWithCovarianceStamped;
using nav_msgs::msg::Odometry;
Expand All @@ -50,7 +50,7 @@ class DrivingEnvironmentAnalyzer : public rclcpp::Node

private:
bool isDataReady(const bool use_map_in_bag);
void onMap(const HADMapBin::ConstSharedPtr map_msg);
void onMap(const LaneletMapBin::ConstSharedPtr map_msg);
void analyze();

bool has_map_data_{false};
Expand All @@ -59,7 +59,7 @@ class DrivingEnvironmentAnalyzer : public rclcpp::Node

route_handler::RouteHandler route_handler_;
LaneletRoute::ConstSharedPtr route_ptr_{nullptr};
rclcpp::Subscription<HADMapBin>::SharedPtr sub_map_;
rclcpp::Subscription<LaneletMapBin>::SharedPtr sub_map_;
rclcpp::TimerBase::SharedPtr timer_;
rosbag2_cpp::Reader reader_;
};
Expand Down
5 changes: 2 additions & 3 deletions driving_environment_analyzer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,10 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_tf2</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>behavior_path_planner_common</depend>
<depend>geometry_msgs</depend>
<depend>interpolation</depend>
Expand Down
8 changes: 4 additions & 4 deletions driving_environment_analyzer/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,7 +275,7 @@ DrivingEnvironmentAnalyzer::DrivingEnvironmentAnalyzer(const rclcpp::NodeOptions
timer_ = rclcpp::create_timer(
this, get_clock(), 100ms, std::bind(&DrivingEnvironmentAnalyzer::analyze, this));

sub_map_ = create_subscription<HADMapBin>(
sub_map_ = create_subscription<LaneletMapBin>(
"input/lanelet2_map", rclcpp::QoS{1}.transient_local(),
std::bind(&DrivingEnvironmentAnalyzer::onMap, this, _1));

Expand All @@ -292,7 +292,7 @@ bool DrivingEnvironmentAnalyzer::isDataReady(const bool use_map_in_bag)
const std::string topic_map = "/map/vector_map";

rclcpp::Serialization<LaneletRoute> serializer_route;
rclcpp::Serialization<HADMapBin> serializer_map;
rclcpp::Serialization<LaneletMapBin> serializer_map;

rosbag2_storage::StorageFilter filter;
filter.topics.emplace_back(topic_route);
Expand All @@ -311,7 +311,7 @@ bool DrivingEnvironmentAnalyzer::isDataReady(const bool use_map_in_bag)

if (data->topic_name == topic_map) {
rclcpp::SerializedMessage serialized_msg(*data->serialized_data);
const auto deserialized_message = std::make_shared<HADMapBin>();
const auto deserialized_message = std::make_shared<LaneletMapBin>();
serializer_route.deserialize_message(&serialized_msg, deserialized_message.get());
route_handler_.setMap(*deserialized_message);
has_map_data_ = true;
Expand All @@ -331,7 +331,7 @@ bool DrivingEnvironmentAnalyzer::isDataReady(const bool use_map_in_bag)
return true;
}

void DrivingEnvironmentAnalyzer::onMap(const HADMapBin::ConstSharedPtr msg)
void DrivingEnvironmentAnalyzer::onMap(const LaneletMapBin::ConstSharedPtr msg)
{
route_handler_.setMap(*msg);
has_map_data_ = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,11 @@
#include "rclcpp/rclcpp.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"

#include "autoware_auto_planning_msgs/msg/path.hpp"
#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp"
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "tier4_debug_msgs/msg/float64_multi_array_stamped.hpp"
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"

#include <iostream>
#include <map>
Expand All @@ -35,11 +35,11 @@

namespace planning_debug_tools
{
using autoware_auto_planning_msgs::msg::Path;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::Path;
using autoware_planning_msgs::msg::Trajectory;
using nav_msgs::msg::Odometry;
using planning_debug_tools::msg::TrajectoryDebugInfo;
using tier4_planning_msgs::msg::PathWithLaneId;

template <typename T>
class TrajectoryAnalyzer
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,21 +19,21 @@
#include "rclcpp/rclcpp.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"

#include "autoware_auto_planning_msgs/msg/path.hpp"
#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp"
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"

#include <vector>

namespace planning_debug_tools
{

using autoware_auto_planning_msgs::msg::PathPoint;
using autoware_auto_planning_msgs::msg::PathPointWithLaneId;
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
using autoware_planning_msgs::msg::PathPoint;
using autoware_planning_msgs::msg::TrajectoryPoint;
using tier4_autoware_utils::calcDistance2d;
using tier4_autoware_utils::getPoint;
using tier4_autoware_utils::getRPY;
using tier4_planning_msgs::msg::PathPointWithLaneId;

double getVelocity(const PathPoint & p)
{
Expand Down
2 changes: 1 addition & 1 deletion planning/planning_debug_tools/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

<build_depend>rosidl_default_generators</build_depend>

<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
<depend>nav_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,12 @@

import time

from autoware_auto_control_msgs.msg import AckermannControlCommand
from autoware_auto_planning_msgs.msg import Path
from autoware_auto_planning_msgs.msg import PathWithLaneId
from autoware_auto_planning_msgs.msg import Trajectory
from autoware_auto_vehicle_msgs.msg import Engage
from autoware_auto_vehicle_msgs.msg import VelocityReport
from autoware_control_msgs.msg import Control
from autoware_planning_msgs.msg import Path
from tier4_planning_msgs.msg import PathWithLaneId
from autoware_planning_msgs.msg import Trajectory
from autoware_vehicle_msgs.msg import Engage
from autoware_vehicle_msgs.msg import VelocityReport
from geometry_msgs.msg import Pose
from nav_msgs.msg import Odometry
import numpy as np
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,10 @@
from subprocess import check_output
import time

from autoware_auto_perception_msgs.msg import DetectedObjects
from autoware_auto_perception_msgs.msg import PredictedObjects
from autoware_auto_perception_msgs.msg import TrackedObjects
from autoware_auto_perception_msgs.msg import TrafficSignalArray as AutoTrafficSignalArray
from autoware_perception_msgs.msg import TrafficSignalArray
from autoware_perception_msgs.msg import DetectedObjects
from autoware_perception_msgs.msg import PredictedObjects
from autoware_perception_msgs.msg import TrackedObjects
from autoware_perception_msgs.msg import TrafficLightGroupArray
from geometry_msgs.msg import PoseStamped
from geometry_msgs.msg import PoseWithCovarianceStamped
from nav_msgs.msg import Odometry
Expand All @@ -45,7 +44,6 @@ def __init__(self, args, name):
self.rosbag_objects_data = []
self.rosbag_ego_odom_data = []
self.rosbag_traffic_signals_data = []
self.is_auto_traffic_signals = False

# subscriber
self.sub_odom = self.create_subscription(
Expand Down Expand Up @@ -91,15 +89,9 @@ def __init__(self, args, name):
self.load_rosbag(args.bag)
print("Ended loading rosbag")

# temporary support old auto msgs
if self.is_auto_traffic_signals:
self.auto_traffic_signals_pub = self.create_publisher(
AutoTrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1
)
else:
self.traffic_signals_pub = self.create_publisher(
TrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1
)
self.traffic_signals_pub = self.create_publisher(
TrafficLightGroupArray, "/perception/traffic_light_recognition/traffic_signals", 1
)

# wait for ready to publish/subscribe
time.sleep(1.0)
Expand Down Expand Up @@ -136,9 +128,6 @@ def load_rosbag(self, rosbag2_path: str):
self.rosbag_ego_odom_data.append((stamp, msg))
if topic == traffic_signals_topic:
self.rosbag_traffic_signals_data.append((stamp, msg))
self.is_auto_traffic_signals = (
"autoware_auto_perception_msgs" in type(msg).__module__
)

def kill_online_perception_node(self):
# kill node if required
Expand Down
14 changes: 7 additions & 7 deletions planning/planning_debug_tools/scripts/trajectory_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,11 @@

import argparse

from autoware_auto_planning_msgs.msg import Path
from autoware_auto_planning_msgs.msg import PathPoint
from autoware_auto_planning_msgs.msg import PathPointWithLaneId
from autoware_auto_planning_msgs.msg import PathWithLaneId
from autoware_auto_planning_msgs.msg import Trajectory
from autoware_auto_planning_msgs.msg import TrajectoryPoint
from autoware_auto_vehicle_msgs.msg import VelocityReport
from autoware_planning_msgs.msg import Path
from autoware_planning_msgs.msg import PathPoint
from autoware_planning_msgs.msg import Trajectory
from autoware_planning_msgs.msg import TrajectoryPoint
from autoware_vehicle_msgs.msg import VelocityReport
from geometry_msgs.msg import Pose
from matplotlib import animation
import matplotlib.pyplot as plt
Expand All @@ -33,6 +31,8 @@
from rclpy.node import Node
from tf2_ros.buffer import Buffer
from tf2_ros.transform_listener import TransformListener
from tier4_planning_msgs.msg import PathPointWithLaneId
from tier4_planning_msgs.msg import PathWithLaneId
from tier4_planning_msgs.msg import VelocityLimit

parser = argparse.ArgumentParser()
Expand Down
22 changes: 11 additions & 11 deletions simulator/simulator_compatibility_test/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -147,22 +147,22 @@ Detailed process

| Name | Type | Description |
| ---------------------------------------- | ------------------------------------------------------- | ------------------ |
| `/vehicle/status/control_mode` | `autoware_auto_vehicle_msgs::msg::ControlModeReport` | for [Test Case #1] |
| `/vehicle/status/gear_status` | `autoware_auto_vehicle_msgs::msg::GearReport` | for [Test Case #2] |
| `/vehicle/status/velocity_status` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | for [Test Case #3] |
| `/vehicle/status/steering_status` | `autoware_auto_vehicle_msgs::msg::SteeringReport` | for [Test Case #4] |
| `/vehicle/status/turn_indicators_status` | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport` | for [Test Case #5] |
| `/vehicle/status/hazard_lights_status` | `autoware_auto_vehicle_msgs::msg::HazardLightsReport` | for [Test Case #6] |
| `/vehicle/status/control_mode` | `autoware_vehicle_msgs::msg::ControlModeReport` | for [Test Case #1] |
| `/vehicle/status/gear_status` | `autoware_vehicle_msgs::msg::GearReport` | for [Test Case #2] |
| `/vehicle/status/velocity_status` | `autoware_vehicle_msgs::msg::VelocityReport` | for [Test Case #3] |
| `/vehicle/status/steering_status` | `autoware_vehicle_msgs::msg::SteeringReport` | for [Test Case #4] |
| `/vehicle/status/turn_indicators_status` | `autoware_vehicle_msgs::msg::TurnIndicatorsReport` | for [Test Case #5] |
| `/vehicle/status/hazard_lights_status` | `autoware_vehicle_msgs::msg::HazardLightsReport` | for [Test Case #6] |

### Output

| Name | Type | Description |
| -------------------------------------- | ---------------------------------------------------- | ---------------------- |
| `/control/command/control_mode_cmd` | `autoware_auto_vehicle_msgs/ControlModeCommand` | for [Test Case #1] |
| `/control/command/gear_cmd` | `autoware_auto_vehicle_msgs/GearCommand` | for [Test Case #2] |
| `/control/command/control_cmd` | `autoware_auto_vehicle_msgs/AckermannControlCommand` | for [Test Case #3, #4] |
| `/vehicle/status/steering_status` | `autoware_auto_vehicle_msgs/TurnIndicatorsCommand` | for [Test Case #5] |
| `/control/command/turn_indicators_cmd` | `autoware_auto_vehicle_msgs/HazardLightsCommand` | for [Test Case #6] |
| `/control/command/control_mode_cmd` | `autoware_vehicle_msgs/ControlModeCommand` | for [Test Case #1] |
| `/control/command/gear_cmd` | `autoware_vehicle_msgs/GearCommand` | for [Test Case #2] |
| `/control/command/control_cmd` | `autoware_vehicle_msgs/AckermannControlCommand` | for [Test Case #3, #4] |
| `/vehicle/status/steering_status` | `autoware_vehicle_msgs/TurnIndicatorsCommand` | for [Test Case #5] |
| `/control/command/turn_indicators_cmd` | `autoware_vehicle_msgs/HazardLightsCommand` | for [Test Case #6] |

## Parameters

Expand Down
16 changes: 8 additions & 8 deletions simulator/simulator_compatibility_test/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,14 @@
<maintainer email="shumpei.wakabayashi@tier4.jp">Shumpei Wakabayashi</maintainer>
<license>TODO: License declaration</license>

<depend>autoware_auto_control_msgs</depend>
<depend>autoware_auto_geometry_msgs</depend>
<depend>autoware_auto_mapping_msgs</depend>
<depend>autoware_auto_msgs</depend>
<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_system_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_geometry_msgs</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_system_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>rclpy</depend>

<test_depend>ament_copyright</test_depend>
Expand Down
Loading

0 comments on commit c013e83

Please sign in to comment.