Skip to content

Commit

Permalink
feat(autoware_mission_planner)!: feat(autoware_mission_planner_univer…
Browse files Browse the repository at this point in the history
…se)!: add _universe suffix to package name (#9941)

Signed-off-by: Ryohsuke Mitsudome <[email protected]>
  • Loading branch information
mitsudome-r authored Jan 21, 2025
1 parent a3bd66f commit 0ac8580
Show file tree
Hide file tree
Showing 35 changed files with 78 additions and 76 deletions.
2 changes: 1 addition & 1 deletion codecov.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -194,7 +194,7 @@ component_management:
- planning/autoware_external_velocity_limit_selector/**
- planning/autoware_freespace_planner/**
- planning/autoware_freespace_planning_algorithms/**
- planning/autoware_mission_planner/**
- planning/autoware_mission_planner_universe/**
# - planning/autoware_objects_of_interest_marker_interface/**
- planning/autoware_obstacle_cruise_planner/**
# - planning/autoware_obstacle_stop_planner/**
Expand Down
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
<launch>
<arg name="mission_planner_param_path" default="$(find-pkg-share autoware_mission_planner)/config/mission_planner.param.yaml"/>
<arg name="mission_planner_param_path" default="$(find-pkg-share autoware_mission_planner_universe)/config/mission_planner.param.yaml"/>
<group>
<include file="$(find-pkg-share autoware_mission_planner)/launch/mission_planner.launch.xml">
<include file="$(find-pkg-share autoware_mission_planner_universe)/launch/mission_planner.launch.xml">
<arg name="mission_planner_param_path" value="$(var mission_planner_param_path)"/>
</include>
</group>
<group>
<include file="$(find-pkg-share autoware_mission_planner)/launch/goal_pose_visualizer.launch.xml"/>
<include file="$(find-pkg-share autoware_mission_planner_universe)/launch/goal_pose_visualizer.launch.xml"/>
</group>
</launch>
2 changes: 1 addition & 1 deletion launch/tier4_planning_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@
<exec_depend>autoware_external_velocity_limit_selector</exec_depend>
<exec_depend>autoware_freespace_planner</exec_depend>
<exec_depend>autoware_glog_component</exec_depend>
<exec_depend>autoware_mission_planner</exec_depend>
<exec_depend>autoware_mission_planner_universe</exec_depend>
<exec_depend>autoware_obstacle_cruise_planner</exec_depend>
<exec_depend>autoware_obstacle_stop_planner</exec_depend>
<exec_depend>autoware_path_optimizer</exec_depend>
Expand Down
2 changes: 1 addition & 1 deletion planning/.pages
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ nav:
- 'About Freespace Planner': planning/autoware_freespace_planner
- 'Algorithm': planning/autoware_freespace_planning_algorithms
- 'RRT*': planning/autoware_freespace_planning_algorithms/rrtstar
- 'Mission Planner': planning/autoware_mission_planner
- 'Mission Planner': planning/autoware_mission_planner_universe
- 'Motion Planning':
- 'Path Optimizer':
- 'About Path Optimizer': planning/autoware_path_optimizer
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package autoware_mission_planner
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package autoware_mission_planner_universe
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.40.0 (2024-12-12)
-------------------
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_mission_planner)
project(autoware_mission_planner_universe)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand All @@ -9,7 +9,7 @@ ament_auto_add_library(goal_pose_visualizer_component SHARED
)

rclcpp_components_register_node(goal_pose_visualizer_component
PLUGIN "autoware::mission_planner::GoalPoseVisualizer"
PLUGIN "autoware::mission_planner_universe::GoalPoseVisualizer"
EXECUTABLE goal_pose_visualizer
)

Expand All @@ -21,20 +21,20 @@ ament_auto_add_library(${PROJECT_NAME}_component SHARED
)

rclcpp_components_register_node(${PROJECT_NAME}_component
PLUGIN "autoware::mission_planner::MissionPlanner"
PLUGIN "autoware::mission_planner_universe::MissionPlanner"
EXECUTABLE mission_planner
)

rclcpp_components_register_node(${PROJECT_NAME}_component
PLUGIN "autoware::mission_planner::RouteSelector"
PLUGIN "autoware::mission_planner_universe::RouteSelector"
EXECUTABLE route_selector
)

ament_auto_add_library(${PROJECT_NAME}_lanelet2_plugins SHARED
src/lanelet2_plugins/default_planner.cpp
src/lanelet2_plugins/utility_functions.cpp
)
pluginlib_export_plugin_description_file(autoware_mission_planner plugins/plugin_description.xml)
pluginlib_export_plugin_description_file(autoware_mission_planner_universe plugins/plugin_description.xml)

if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__MISSION_PLANNER__MISSION_PLANNER_PLUGIN_HPP_
#define AUTOWARE__MISSION_PLANNER__MISSION_PLANNER_PLUGIN_HPP_
#ifndef AUTOWARE__MISSION_PLANNER_UNIVERSE__MISSION_PLANNER_PLUGIN_HPP_
#define AUTOWARE__MISSION_PLANNER_UNIVERSE__MISSION_PLANNER_PLUGIN_HPP_

#include <rclcpp/rclcpp.hpp>

Expand All @@ -24,7 +24,7 @@

#include <vector>

namespace autoware::mission_planner
namespace autoware::mission_planner_universe
{

class PlannerPlugin
Expand All @@ -45,6 +45,6 @@ class PlannerPlugin
virtual void clearRoute() = 0;
};

} // namespace autoware::mission_planner
} // namespace autoware::mission_planner_universe

#endif // AUTOWARE__MISSION_PLANNER__MISSION_PLANNER_PLUGIN_HPP_
#endif // AUTOWARE__MISSION_PLANNER_UNIVERSE__MISSION_PLANNER_PLUGIN_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<arg name="route_topic_name" default="/planning/mission_planning/route"/>
<arg name="echo_back_goal_pose_topic_name" default="/planning/mission_planning/echo_back_goal_pose"/>

<node pkg="autoware_mission_planner" exec="goal_pose_visualizer" name="goal_pose_visualizer" output="screen">
<node pkg="autoware_mission_planner_universe" exec="goal_pose_visualizer" name="goal_pose_visualizer" output="screen">
<remap from="input/route" to="$(var route_topic_name)"/>
<remap from="output/goal_pose" to="$(var echo_back_goal_pose_topic_name)"/>
</node>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@
<arg name="modified_goal_topic_name" default="/planning/scenario_planning/modified_goal"/>
<arg name="map_topic_name" default="/map/vector_map"/>
<arg name="visualization_topic_name" default="/planning/mission_planning/route_marker"/>
<arg name="mission_planner_param_path" default="$(find-pkg-share autoware_mission_planner)/config/mission_planner.param.yaml"/>
<arg name="mission_planner_param_path" default="$(find-pkg-share autoware_mission_planner_universe)/config/mission_planner.param.yaml"/>

<node_container pkg="rclcpp_components" exec="component_container_mt" name="mission_planner_container" namespace="">
<composable_node pkg="autoware_mission_planner" plugin="autoware::mission_planner::MissionPlanner" name="mission_planner" namespace="">
<composable_node pkg="autoware_mission_planner_universe" plugin="autoware::mission_planner_universe::MissionPlanner" name="mission_planner" namespace="">
<param from="$(var mission_planner_param_path)"/>
<remap from="~/input/modified_goal" to="$(var modified_goal_topic_name)"/>
<remap from="~/input/vector_map" to="$(var map_topic_name)"/>
Expand All @@ -16,7 +16,7 @@
<remap from="~/state" to="state"/>
<remap from="~/debug/route_marker" to="$(var visualization_topic_name)"/>
</composable_node>
<composable_node pkg="autoware_mission_planner" plugin="autoware::mission_planner::RouteSelector" name="route_selector" namespace="">
<composable_node pkg="autoware_mission_planner_universe" plugin="autoware::mission_planner_universe::RouteSelector" name="route_selector" namespace="">
<remap from="~/planner/clear_route" to="mission_planner/clear_route"/>
<remap from="~/planner/set_lanelet_route" to="mission_planner/set_lanelet_route"/>
<remap from="~/planner/set_waypoint_route" to="mission_planner/set_waypoint_route"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?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>autoware_mission_planner</name>
<name>autoware_mission_planner_universe</name>
<version>0.40.0</version>
<description>The autoware_mission_planner package</description>
<description>The autoware_mission_planner_universe package</description>
<maintainer email="[email protected]">Takagi, Isamu</maintainer>
<maintainer email="[email protected]">Kosuke Takeuchi</maintainer>
<maintainer email="[email protected]">Ryohsuke Mitsudome</maintainer>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<library path="autoware_mission_planner_universe_lanelet2_plugins">
<class type="autoware::mission_planner_universe::lanelet2::DefaultPlanner" base_class_type="autoware::mission_planner_universe::PlannerPlugin"/>
</library>
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "goal_pose_visualizer.hpp"

namespace autoware::mission_planner
namespace autoware::mission_planner_universe
{
GoalPoseVisualizer::GoalPoseVisualizer(const rclcpp::NodeOptions & node_options)
: Node("goal_pose_visualizer", node_options)
Expand All @@ -34,7 +34,7 @@ void GoalPoseVisualizer::echo_back_route_callback(
goal_pose.pose = msg->goal_pose;
pub_goal_pose_->publish(goal_pose);
}
} // namespace autoware::mission_planner
} // namespace autoware::mission_planner_universe

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner::GoalPoseVisualizer)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner_universe::GoalPoseVisualizer)
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>

namespace autoware::mission_planner
namespace autoware::mission_planner_universe
{
class GoalPoseVisualizer : public rclcpp::Node
{
Expand All @@ -35,5 +35,5 @@ class GoalPoseVisualizer : public rclcpp::Node
const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr msg);
};

} // namespace autoware::mission_planner
} // namespace autoware::mission_planner_universe
#endif // GOAL_POSE_VISUALIZER__GOAL_POSE_VISUALIZER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#include <limits>
#include <vector>

namespace autoware::mission_planner::lanelet2
namespace autoware::mission_planner_universe::lanelet2
{

void DefaultPlanner::initialize_common(rclcpp::Node * node)
Expand Down Expand Up @@ -383,8 +383,9 @@ void DefaultPlanner::clearRoute()
route_handler_.clearRoute();
}

} // namespace autoware::mission_planner::lanelet2
} // namespace autoware::mission_planner_universe::lanelet2

#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(
autoware::mission_planner::lanelet2::DefaultPlanner, autoware::mission_planner::PlannerPlugin)
autoware::mission_planner_universe::lanelet2::DefaultPlanner,
autoware::mission_planner_universe::PlannerPlugin)
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_
#define LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_

#include <autoware/mission_planner/mission_planner_plugin.hpp>
#include <autoware/mission_planner_universe/mission_planner_plugin.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rclcpp/rclcpp.hpp>
Expand All @@ -29,7 +29,7 @@

#include <vector>

namespace autoware::mission_planner::lanelet2
namespace autoware::mission_planner_universe::lanelet2
{

struct DefaultPlannerParameters
Expand All @@ -40,7 +40,7 @@ struct DefaultPlannerParameters
bool check_footprint_inside_lanes;
};

class DefaultPlanner : public mission_planner::PlannerPlugin
class DefaultPlanner : public mission_planner_universe::PlannerPlugin
{
public:
DefaultPlanner() : vehicle_info_(), is_graph_ready_(false), param_(), node_(nullptr) {}
Expand Down Expand Up @@ -101,6 +101,6 @@ class DefaultPlanner : public mission_planner::PlannerPlugin
Pose refine_goal_height(const Pose & goal, const RouteSections & route_sections);
};

} // namespace autoware::mission_planner::lanelet2
} // namespace autoware::mission_planner_universe::lanelet2

#endif // LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <limits>
#include <vector>

namespace autoware::mission_planner::lanelet2
namespace autoware::mission_planner_universe::lanelet2
{
autoware::universe_utils::Polygon2d convert_linear_ring_to_polygon(
autoware::universe_utils::LinearRing2d footprint)
Expand Down Expand Up @@ -158,4 +158,4 @@ geometry_msgs::msg::Pose get_closest_centerline_pose(
return convertBasicPoint3dToPose(refined_point, lane_yaw);
}

} // namespace autoware::mission_planner::lanelet2
} // namespace autoware::mission_planner_universe::lanelet2
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@

#include <vector>

namespace autoware::mission_planner::lanelet2
namespace autoware::mission_planner_universe::lanelet2
{
using RouteSections = std::vector<autoware_planning_msgs::msg::LaneletSegment>;

Expand Down Expand Up @@ -64,5 +64,5 @@ geometry_msgs::msg::Pose get_closest_centerline_pose(
const lanelet::ConstLanelets & road_lanelets, const geometry_msgs::msg::Pose & point,
autoware::vehicle_info_utils::VehicleInfo vehicle_info);

} // namespace autoware::mission_planner::lanelet2
} // namespace autoware::mission_planner_universe::lanelet2
#endif // LANELET2_PLUGINS__UTILITY_FUNCTIONS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include <tf2/utils.h>

namespace autoware::mission_planner
namespace autoware::mission_planner_universe
{

ArrivalChecker::ArrivalChecker(rclcpp::Node * node) : vehicle_stop_checker_(node)
Expand Down Expand Up @@ -72,4 +72,4 @@ bool ArrivalChecker::is_arrived(const PoseStamped & pose) const
return vehicle_stop_checker_.isVehicleStopped(duration_);
}

} // namespace autoware::mission_planner
} // namespace autoware::mission_planner_universe
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>

namespace autoware::mission_planner
namespace autoware::mission_planner_universe
{

class ArrivalChecker
Expand All @@ -44,6 +44,6 @@ class ArrivalChecker
autoware::motion_utils::VehicleStopChecker vehicle_stop_checker_;
};

} // namespace autoware::mission_planner
} // namespace autoware::mission_planner_universe

#endif // MISSION_PLANNER__ARRIVAL_CHECKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -32,13 +32,14 @@
#include <utility>
#include <vector>

namespace autoware::mission_planner
namespace autoware::mission_planner_universe
{

MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options)
: Node("mission_planner", options),
arrival_checker_(this),
plugin_loader_("autoware_mission_planner", "autoware::mission_planner::PlannerPlugin"),
plugin_loader_(
"autoware_mission_planner_universe", "autoware::mission_planner_universe::PlannerPlugin"),
tf_buffer_(get_clock()),
tf_listener_(tf_buffer_),
odometry_(nullptr),
Expand All @@ -52,8 +53,8 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options)
minimum_reroute_length_ = declare_parameter<double>("minimum_reroute_length");
allow_reroute_in_autonomous_mode_ = declare_parameter<bool>("allow_reroute_in_autonomous_mode");

planner_ =
plugin_loader_.createSharedInstance("autoware::mission_planner::lanelet2::DefaultPlanner");
planner_ = plugin_loader_.createSharedInstance(
"autoware::mission_planner_universe::lanelet2::DefaultPlanner");
planner_->initialize(this);

const auto durable_qos = rclcpp::QoS(1).transient_local();
Expand Down Expand Up @@ -671,7 +672,7 @@ bool MissionPlanner::check_reroute_safety(
accumulated_length, safety_length);
return false;
}
} // namespace autoware::mission_planner
} // namespace autoware::mission_planner_universe

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner::MissionPlanner)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner_universe::MissionPlanner)
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "arrival_checker.hpp"
#include "autoware/universe_utils/ros/polling_subscriber.hpp"

#include <autoware/mission_planner/mission_planner_plugin.hpp>
#include <autoware/mission_planner_universe/mission_planner_plugin.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <autoware/universe_utils/ros/logger_level_configure.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
Expand All @@ -45,7 +45,7 @@
#include <string>
#include <vector>

namespace autoware::mission_planner
namespace autoware::mission_planner_universe
{

using autoware_adapi_v1_msgs::msg::OperationModeState;
Expand Down Expand Up @@ -150,6 +150,6 @@ class MissionPlanner : public rclcpp::Node
pub_processing_time_;
};

} // namespace autoware::mission_planner
} // namespace autoware::mission_planner_universe

#endif // MISSION_PLANNER__MISSION_PLANNER_HPP_
Loading

0 comments on commit 0ac8580

Please sign in to comment.