Skip to content

Commit

Permalink
feat!: replace scenario msg from tier4_planning_msgs to autoware_inte…
Browse files Browse the repository at this point in the history
…rnal_planning_msgs (autowarefoundation#10180)

Signed-off-by: Ryohsuke Mitsudome <[email protected]>
  • Loading branch information
mitsudome-r authored Feb 26, 2025
1 parent 769673c commit f0cd1a5
Show file tree
Hide file tree
Showing 14 changed files with 51 additions and 48 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,10 @@
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <autoware_internal_planning_msgs/msg/scenario.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tier4_planning_msgs/msg/scenario.hpp>

#include <grid_map_msgs/msg/grid_map.h>
#include <message_filters/subscriber.h>
Expand Down Expand Up @@ -107,7 +107,8 @@ class CostmapGenerator : public rclcpp::Node
sub_points_{this, "~/input/points_no_ground", autoware::universe_utils::SingleDepthSensorQoS()};
autoware::universe_utils::InterProcessPollingSubscriber<PredictedObjects> sub_objects_{
this, "~/input/objects"};
autoware::universe_utils::InterProcessPollingSubscriber<tier4_planning_msgs::msg::Scenario>
autoware::universe_utils::InterProcessPollingSubscriber<
autoware_internal_planning_msgs::msg::Scenario>
sub_scenario_{this, "~/input/scenario"};

rclcpp::TimerBase::SharedPtr timer_;
Expand All @@ -120,7 +121,7 @@ class CostmapGenerator : public rclcpp::Node
PointsToCostmap points2costmap_{};
ObjectsToCostmap objects2costmap_;

tier4_planning_msgs::msg::Scenario::ConstSharedPtr scenario_;
autoware_internal_planning_msgs::msg::Scenario::ConstSharedPtr scenario_;

struct LayerName
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -335,7 +335,7 @@ bool CostmapGenerator::isActive()
if (!scenario_) return false;
const auto & s = scenario_->activating_scenarios;
return std::any_of(s.begin(), s.end(), [](const auto scenario) {
return scenario == tier4_planning_msgs::msg::Scenario::PARKING;
return scenario == autoware_internal_planning_msgs::msg::Scenario::PARKING;
});
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <vector>

using autoware::costmap_generator::CostmapGenerator;
using tier4_planning_msgs::msg::Scenario;
using autoware_internal_planning_msgs::msg::Scenario;

class TestCostmapGenerator : public ::testing::Test
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,13 @@
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <autoware_internal_planning_msgs/msg/scenario.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <std_msgs/msg/bool.hpp>
#include <tier4_planning_msgs/msg/scenario.hpp>

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
Expand Down Expand Up @@ -76,6 +76,7 @@ using autoware::freespace_planning_algorithms::PlannerCommonParam;
using autoware::freespace_planning_algorithms::RRTStar;
using autoware::freespace_planning_algorithms::RRTStarParam;
using autoware::freespace_planning_algorithms::VehicleShape;
using autoware_internal_planning_msgs::msg::Scenario;
using autoware_planning_msgs::msg::LaneletRoute;
using autoware_planning_msgs::msg::Trajectory;
using geometry_msgs::msg::PoseArray;
Expand All @@ -84,7 +85,6 @@ using geometry_msgs::msg::TransformStamped;
using geometry_msgs::msg::Twist;
using nav_msgs::msg::OccupancyGrid;
using nav_msgs::msg::Odometry;
using tier4_planning_msgs::msg::Scenario;

struct NodeParam
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,13 @@

#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_planning_msgs/msg/scenario.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
#include <geometry_msgs/msg/pose_array.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_planning_msgs/msg/scenario.hpp>

#include <deque>
#include <vector>
Expand All @@ -34,14 +34,14 @@ namespace autoware::freespace_planner::utils
{
using autoware::freespace_planning_algorithms::PlannerWaypoint;
using autoware::freespace_planning_algorithms::PlannerWaypoints;
using autoware_internal_planning_msgs::msg::Scenario;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::PoseArray;
using geometry_msgs::msg::PoseStamped;
using geometry_msgs::msg::TransformStamped;
using nav_msgs::msg::Odometry;
using tier4_planning_msgs::msg::Scenario;

PoseArray trajectory_to_pose_array(const Trajectory & trajectory);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ void publishMandatoryTopics(
autoware::test_utils::makeCostMapMsg());
test_manager->publishInput(
test_target_node, "freespace_planner/input/scenario",
autoware::test_utils::makeScenarioMsg(tier4_planning_msgs::msg::Scenario::PARKING));
autoware::test_utils::makeScenarioMsg(autoware_internal_planning_msgs::msg::Scenario::PARKING));
}

// the following tests are disable because they randomly fail
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode(
sub_planning_velocity_ = create_subscription<tier4_planning_msgs::msg::VelocityLimit>(
"/planning/scenario_planning/current_max_velocity", qos_transient_local,
std::bind(&RemainingDistanceTimeCalculatorNode::on_velocity_limit, this, _1));
sub_scenario_ = this->create_subscription<tier4_planning_msgs::msg::Scenario>(
sub_scenario_ = this->create_subscription<autoware_internal_planning_msgs::msg::Scenario>(
"~/input/scenario", 1, std::bind(&RemainingDistanceTimeCalculatorNode::on_scenario, this, _1));

pub_mission_remaining_distance_time_ = create_publisher<MissionRemainingDistanceTime>(
Expand Down Expand Up @@ -106,7 +106,7 @@ void RemainingDistanceTimeCalculatorNode::on_velocity_limit(
}

void RemainingDistanceTimeCalculatorNode::on_scenario(
const tier4_planning_msgs::msg::Scenario::ConstSharedPtr & msg)
const autoware_internal_planning_msgs::msg::Scenario::ConstSharedPtr & msg)
{
scenario_ = msg;
has_received_scenario_ = true;
Expand All @@ -119,7 +119,7 @@ void RemainingDistanceTimeCalculatorNode::on_timer()
}

// check if the scenario is parking or not
if (scenario_->current_scenario == tier4_planning_msgs::msg::Scenario::PARKING) {
if (scenario_->current_scenario == autoware_internal_planning_msgs::msg::Scenario::PARKING) {
remaining_distance_ = 0.0;
remaining_time_ = 0.0;
publish_mission_remaining_distance_time();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@
#include <remaining_distance_time_calculator_parameters.hpp>

#include <autoware_internal_msgs/msg/mission_remaining_distance_time.hpp>
#include <autoware_internal_planning_msgs/msg/scenario.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/vector3.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_planning_msgs/msg/scenario.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>

#include <lanelet2_core/Forward.h>
Expand Down Expand Up @@ -56,7 +56,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node
rclcpp::Subscription<HADMapBin>::SharedPtr sub_map_;
rclcpp::Subscription<Odometry>::SharedPtr sub_odometry_;
rclcpp::Subscription<VelocityLimit>::SharedPtr sub_planning_velocity_;
rclcpp::Subscription<tier4_planning_msgs::msg::Scenario>::SharedPtr sub_scenario_;
rclcpp::Subscription<autoware_internal_planning_msgs::msg::Scenario>::SharedPtr sub_scenario_;

rclcpp::Publisher<MissionRemainingDistanceTime>::SharedPtr pub_mission_remaining_distance_time_;

Expand All @@ -73,7 +73,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node
geometry_msgs::msg::Pose current_vehicle_pose_;
geometry_msgs::msg::Vector3 current_vehicle_velocity_;
geometry_msgs::msg::Pose goal_pose_;
tier4_planning_msgs::msg::Scenario::ConstSharedPtr scenario_;
autoware_internal_planning_msgs::msg::Scenario::ConstSharedPtr scenario_;
bool has_received_route_;
bool has_received_scenario_;
double velocity_limit_;
Expand All @@ -90,7 +90,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node
void on_route(const LaneletRoute::ConstSharedPtr & msg);
void on_map(const HADMapBin::ConstSharedPtr & msg);
void on_velocity_limit(const VelocityLimit::ConstSharedPtr & msg);
void on_scenario(const tier4_planning_msgs::msg::Scenario::ConstSharedPtr & msg);
void on_scenario(const autoware_internal_planning_msgs::msg::Scenario::ConstSharedPtr & msg);

/**
* @brief calculate mission remaining distance
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,13 +20,13 @@

#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <autoware_internal_planning_msgs/msg/scenario.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <std_msgs/msg/bool.hpp>
#include <tier4_planning_msgs/msg/scenario.hpp>

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_routing/RoutingGraph.h>
Expand Down Expand Up @@ -79,12 +79,12 @@ class ScenarioSelectorNode : public rclcpp::Node

inline bool isCurrentLaneDriving() const
{
return current_scenario_ == tier4_planning_msgs::msg::Scenario::LANEDRIVING;
return current_scenario_ == autoware_internal_planning_msgs::msg::Scenario::LANEDRIVING;
}

inline bool isCurrentParking() const
{
return current_scenario_ == tier4_planning_msgs::msg::Scenario::PARKING;
return current_scenario_ == autoware_internal_planning_msgs::msg::Scenario::PARKING;
}

rclcpp::TimerBase::SharedPtr timer_;
Expand All @@ -96,7 +96,7 @@ class ScenarioSelectorNode : public rclcpp::Node
sub_lane_driving_trajectory_;
rclcpp::Subscription<autoware_planning_msgs::msg::Trajectory>::SharedPtr sub_parking_trajectory_;
rclcpp::Publisher<autoware_planning_msgs::msg::Trajectory>::SharedPtr pub_trajectory_;
rclcpp::Publisher<tier4_planning_msgs::msg::Scenario>::SharedPtr pub_scenario_;
rclcpp::Publisher<autoware_internal_planning_msgs::msg::Scenario>::SharedPtr pub_scenario_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
pub_processing_time_;

Expand Down
45 changes: 23 additions & 22 deletions planning/autoware_scenario_selector/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,10 +132,10 @@ bool isStopped(
autoware_planning_msgs::msg::Trajectory::ConstSharedPtr ScenarioSelectorNode::getScenarioTrajectory(
const std::string & scenario)
{
if (scenario == tier4_planning_msgs::msg::Scenario::LANEDRIVING) {
if (scenario == autoware_internal_planning_msgs::msg::Scenario::LANEDRIVING) {
return lane_driving_trajectory_;
}
if (scenario == tier4_planning_msgs::msg::Scenario::PARKING) {
if (scenario == autoware_internal_planning_msgs::msg::Scenario::PARKING) {
return parking_trajectory_;
}
RCLCPP_ERROR_STREAM(this->get_logger(), "invalid scenario argument: " << scenario);
Expand All @@ -151,25 +151,25 @@ std::string ScenarioSelectorNode::selectScenarioByPosition()
const auto is_in_parking_lot =
isInParkingLot(route_handler_->getLaneletMapPtr(), current_pose_->pose.pose);

if (current_scenario_ == tier4_planning_msgs::msg::Scenario::EMPTY) {
if (current_scenario_ == autoware_internal_planning_msgs::msg::Scenario::EMPTY) {
if (is_in_lane && is_goal_in_lane) {
return tier4_planning_msgs::msg::Scenario::LANEDRIVING;
return autoware_internal_planning_msgs::msg::Scenario::LANEDRIVING;
} else if (is_in_parking_lot) {
return tier4_planning_msgs::msg::Scenario::PARKING;
return autoware_internal_planning_msgs::msg::Scenario::PARKING;
}
return tier4_planning_msgs::msg::Scenario::LANEDRIVING;
return autoware_internal_planning_msgs::msg::Scenario::LANEDRIVING;
}

if (current_scenario_ == tier4_planning_msgs::msg::Scenario::LANEDRIVING) {
if (current_scenario_ == autoware_internal_planning_msgs::msg::Scenario::LANEDRIVING) {
if (is_in_parking_lot && !is_goal_in_lane) {
return tier4_planning_msgs::msg::Scenario::PARKING;
return autoware_internal_planning_msgs::msg::Scenario::PARKING;
}
}

if (current_scenario_ == tier4_planning_msgs::msg::Scenario::PARKING) {
if (current_scenario_ == autoware_internal_planning_msgs::msg::Scenario::PARKING) {
if (is_parking_completed_ && is_in_lane) {
is_parking_completed_ = false;
return tier4_planning_msgs::msg::Scenario::LANEDRIVING;
return autoware_internal_planning_msgs::msg::Scenario::LANEDRIVING;
}
}

Expand All @@ -193,11 +193,12 @@ void ScenarioSelectorNode::updateCurrentScenario()
if (enable_mode_switching_) {
if (isCurrentLaneDriving()) {
current_scenario_ = isSwitchToParking(is_stopped)
? tier4_planning_msgs::msg::Scenario::PARKING
? autoware_internal_planning_msgs::msg::Scenario::PARKING
: current_scenario_;
} else if (isCurrentParking()) {
current_scenario_ = isSwitchToLaneDriving() ? tier4_planning_msgs::msg::Scenario::LANEDRIVING
: current_scenario_;
current_scenario_ = isSwitchToLaneDriving()
? autoware_internal_planning_msgs::msg::Scenario::LANEDRIVING
: current_scenario_;
}
}

Expand Down Expand Up @@ -274,7 +275,7 @@ void ScenarioSelectorNode::onRoute(
// When the route id is the same (e.g. rerouting with modified goal) keep the current scenario.
// Otherwise, reset the scenario.
if (!route_handler_ || route_handler_->getRouteUuid() != msg->uuid) {
current_scenario_ = tier4_planning_msgs::msg::Scenario::EMPTY;
current_scenario_ = autoware_internal_planning_msgs::msg::Scenario::EMPTY;
}

route_ = msg;
Expand Down Expand Up @@ -375,15 +376,15 @@ void ScenarioSelectorNode::onTimer()
}

// Initialize Scenario
if (current_scenario_ == tier4_planning_msgs::msg::Scenario::EMPTY) {
if (current_scenario_ == autoware_internal_planning_msgs::msg::Scenario::EMPTY) {
current_scenario_ = selectScenarioByPosition();
}

updateCurrentScenario();
tier4_planning_msgs::msg::Scenario scenario;
autoware_internal_planning_msgs::msg::Scenario scenario;
scenario.current_scenario = current_scenario_;

if (current_scenario_ == tier4_planning_msgs::msg::Scenario::PARKING) {
if (current_scenario_ == autoware_internal_planning_msgs::msg::Scenario::PARKING) {
scenario.activating_scenarios.push_back(current_scenario_);
}

Expand All @@ -401,7 +402,7 @@ void ScenarioSelectorNode::onLaneDrivingTrajectory(
{
lane_driving_trajectory_ = msg;

if (current_scenario_ != tier4_planning_msgs::msg::Scenario::LANEDRIVING) {
if (current_scenario_ != autoware_internal_planning_msgs::msg::Scenario::LANEDRIVING) {
return;
}

Expand All @@ -413,7 +414,7 @@ void ScenarioSelectorNode::onParkingTrajectory(
{
parking_trajectory_ = msg;

if (current_scenario_ != tier4_planning_msgs::msg::Scenario::PARKING) {
if (current_scenario_ != autoware_internal_planning_msgs::msg::Scenario::PARKING) {
return;
}

Expand All @@ -438,7 +439,7 @@ void ScenarioSelectorNode::publishTrajectory(

ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_options)
: Node("scenario_selector", node_options),
current_scenario_(tier4_planning_msgs::msg::Scenario::EMPTY),
current_scenario_(autoware_internal_planning_msgs::msg::Scenario::EMPTY),
update_rate_(this->declare_parameter<double>("update_rate")),
th_max_message_delay_sec_(this->declare_parameter<double>("th_max_message_delay_sec")),
th_arrived_distance_m_(this->declare_parameter<double>("th_arrived_distance_m")),
Expand Down Expand Up @@ -478,8 +479,8 @@ ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_opti
this, "input/operation_mode_state", rclcpp::QoS{1});

// Output
pub_scenario_ =
this->create_publisher<tier4_planning_msgs::msg::Scenario>("output/scenario", rclcpp::QoS{1});
pub_scenario_ = this->create_publisher<autoware_internal_planning_msgs::msg::Scenario>(
"output/scenario", rclcpp::QoS{1});
pub_trajectory_ = this->create_publisher<autoware_planning_msgs::msg::Trajectory>(
"output/trajectory", rclcpp::QoS{1});

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();

// set subscriber with topic name: scenario_selector → test_node_
test_manager->subscribeOutput<tier4_planning_msgs::msg::Scenario>("output/scenario");
test_manager->subscribeOutput<autoware_internal_planning_msgs::msg::Scenario>("output/scenario");

return test_manager;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ The Planner Manager's responsibilities include:
| ~/input/traffic_signals || `autoware_perception_msgs::msg::TrafficLightGroupArray` | Traffic signal information from the perception module |
| ~/input/vector_map || `autoware_map_msgs::msg::LaneletMapBin` | Vector map information |
| ~/input/route || `autoware_planning_msgs::msg::LaneletRoute` | Current route from start to goal |
| ~/input/scenario || `tier4_planning_msgs::msg::Scenario` | Launches Behavior Path Planner if current scenario == `Scenario:LaneDriving` |
| ~/input/scenario || `autoware_internal_planning_msgs::msg::Scenario` | Launches Behavior Path Planner if current scenario == `Scenario:LaneDriving` |
| ~/input/lateral_offset || `tier4_planning_msgs::msg::LateralOffset` | Lateral offset to trigger side shift |
| ~/system/operation_mode/state || `autoware_adapi_v1_msgs::msg::OperationModeState` | Allows the planning module to know if vehicle is in autonomous mode or if it can be controlled<sup>[ref](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/operation-mode.md)</sup> |

Expand Down
Loading

0 comments on commit f0cd1a5

Please sign in to comment.