Skip to content

Commit 7e32f84

Browse files
committed
refactor trajectory_modifier node
applies following refactors to the trajectory_modifier node: - Use ros2 plugin framework to load submodules - Use generate_parameter_library to create parameter struct from schema on build - Use ParamListener to handle initial param loading and online param updates Signed-off-by: Mohammad <alqudah.mohammad@tier4.jp>
1 parent 6b2f6a9 commit 7e32f84

File tree

13 files changed

+219
-218
lines changed

13 files changed

+219
-218
lines changed

planning/autoware_trajectory_modifier/CMakeLists.txt

Lines changed: 26 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -3,18 +3,37 @@ project(autoware_trajectory_modifier)
33

44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
6+
pluginlib_export_plugin_description_file(autoware_trajectory_modifier plugins.xml)
67

7-
ament_auto_add_library(autoware_trajectory_modifier_component SHARED
8+
generate_parameter_library(trajectory_modifier_param
9+
param/trajectory_modifier_parameter_struct.yaml
10+
)
11+
12+
ament_auto_add_library(${PROJECT_NAME} SHARED
813
src/trajectory_modifier.cpp
914
src/utils.cpp
10-
src/trajectory_modifier_plugins/stop_point_fixer.cpp
1115
)
1216

13-
target_link_libraries(autoware_trajectory_modifier_component)
17+
target_link_libraries(${PROJECT_NAME}
18+
trajectory_modifier_param
19+
)
20+
21+
target_compile_options(${PROJECT_NAME} PUBLIC
22+
-Wno-error=deprecated-declarations
23+
)
1424

15-
rclcpp_components_register_node(autoware_trajectory_modifier_component
25+
rclcpp_components_register_node(${PROJECT_NAME}
1626
PLUGIN "autoware::trajectory_modifier::TrajectoryModifier"
17-
EXECUTABLE autoware_trajectory_modifier_node
27+
EXECUTABLE ${PROJECT_NAME}_node
28+
)
29+
30+
ament_auto_add_library(${PROJECT_NAME}_plugins SHARED
31+
src/trajectory_modifier_plugins/stop_point_fixer.cpp
32+
)
33+
34+
target_link_libraries(${PROJECT_NAME}_plugins
35+
${PROJECT_NAME}
36+
trajectory_modifier_param
1837
)
1938

2039
if(BUILD_TESTING)
@@ -26,7 +45,8 @@ if(BUILD_TESTING)
2645
${TEST_SOURCES}
2746
)
2847
target_link_libraries(test_autoware_trajectory_modifier
29-
autoware_trajectory_modifier_component
48+
${PROJECT_NAME}
49+
${PROJECT_NAME}_plugins
3050
)
3151
endif()
3252

planning/autoware_trajectory_modifier/config/trajectory_modifier.param.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
/trajectory_modifier:
1+
/**:
22
ros__parameters:
33
use_stop_point_fixer: true
44

planning/autoware_trajectory_modifier/include/autoware/trajectory_modifier/trajectory_modifier.hpp

Lines changed: 10 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,10 @@
1919
#include "autoware/trajectory_modifier/trajectory_modifier_plugins/trajectory_modifier_plugin_base.hpp"
2020
#include "autoware/trajectory_modifier/trajectory_modifier_structs.hpp"
2121

22+
#include <autoware_trajectory_modifier/trajectory_modifier_param.hpp>
2223
#include <autoware_utils_debug/time_keeper.hpp>
2324
#include <autoware_utils_rclcpp/polling_subscriber.hpp>
25+
#include <pluginlib/class_loader.hpp>
2426
#include <rclcpp/rclcpp.hpp>
2527
#include <rclcpp/subscription.hpp>
2628

@@ -51,16 +53,16 @@ class TrajectoryModifier : public rclcpp::Node
5153

5254
private:
5355
void on_traj(const CandidateTrajectories::ConstSharedPtr msg);
54-
void set_up_params();
5556
void initialize_modifiers();
57+
void load_plugin(const std::string & name);
58+
void unload_plugin(const std::string & name);
5659
void reset_previous_data();
5760
bool initialized_modifiers_{false};
5861

59-
rcl_interfaces::msg::SetParametersResult on_parameter(
60-
const std::vector<rclcpp::Parameter> & parameters);
62+
std::unique_ptr<trajectory_modifier_params::ParamListener> param_listener_;
63+
trajectory_modifier_params::Params params_;
6164

62-
std::vector<std::shared_ptr<plugin::TrajectoryModifierPluginBase>> modifier_plugins_;
63-
std::shared_ptr<plugin::StopPointFixer> stop_point_fixer_ptr_;
65+
void update_params();
6466

6567
rclcpp::Subscription<CandidateTrajectories>::SharedPtr trajectories_sub_;
6668
rclcpp::Publisher<CandidateTrajectories>::SharedPtr trajectories_pub_;
@@ -79,9 +81,10 @@ class TrajectoryModifier : public rclcpp::Node
7981
debug_processing_time_detail_pub_;
8082
mutable std::shared_ptr<autoware_utils_debug::TimeKeeper> time_keeper_{nullptr};
8183

82-
TrajectoryModifierParams params_;
84+
pluginlib::ClassLoader<plugin::TrajectoryModifierPluginBase> plugin_loader_;
85+
std::vector<std::shared_ptr<plugin::TrajectoryModifierPluginBase>> plugins_;
86+
8387
TrajectoryModifierData data_;
84-
OnSetParametersCallbackHandle::SharedPtr set_param_res_;
8588
};
8689

8790
} // namespace autoware::trajectory_modifier

planning/autoware_trajectory_modifier/include/autoware/trajectory_modifier/trajectory_modifier_plugins/stop_point_fixer.hpp

Lines changed: 16 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -27,29 +27,27 @@ namespace autoware::trajectory_modifier::plugin
2727
class StopPointFixer : public TrajectoryModifierPluginBase
2828
{
2929
public:
30-
StopPointFixer(
31-
const std::string & name, rclcpp::Node * node_ptr,
32-
const std::shared_ptr<autoware_utils_debug::TimeKeeper> & time_keeper,
33-
const TrajectoryModifierParams & params);
30+
StopPointFixer() = default;
3431

3532
void modify_trajectory(
36-
TrajectoryPoints & traj_points, const TrajectoryModifierParams & params,
37-
const TrajectoryModifierData & data) override;
38-
void set_up_params() override;
39-
rcl_interfaces::msg::SetParametersResult on_parameter(
40-
const std::vector<rclcpp::Parameter> & parameters) override;
41-
bool is_trajectory_modification_required(
42-
const TrajectoryPoints & traj_points, const TrajectoryModifierParams & params,
43-
const TrajectoryModifierData & data) const override;
33+
TrajectoryPoints & traj_points, const TrajectoryModifierData & data) override;
4434

45-
private:
46-
struct Parameters
35+
[[nodiscard]] bool is_trajectory_modification_required(
36+
const TrajectoryPoints & traj_points, const TrajectoryModifierData & data) const override;
37+
38+
void update_params(const TrajectoryModifierParams & params) override
4739
{
48-
double velocity_threshold_mps{0.1};
49-
double min_distance_threshold_m{1.0};
50-
};
40+
params_ = params.stop_point_fixer;
41+
enabled_ = params.use_stop_point_fixer;
42+
}
43+
44+
const TrajectoryModifierParams::StopPointFixer & get_params() const { return params_; }
5145

52-
Parameters params_;
46+
protected:
47+
void on_initialize(const TrajectoryModifierParams & params) override;
48+
49+
private:
50+
TrajectoryModifierParams::StopPointFixer params_;
5351
};
5452

5553
} // namespace autoware::trajectory_modifier::plugin

planning/autoware_trajectory_modifier/include/autoware/trajectory_modifier/trajectory_modifier_plugins/trajectory_modifier_plugin_base.hpp

Lines changed: 15 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include "autoware/trajectory_modifier/trajectory_modifier_structs.hpp"
2020

2121
#include <autoware/planning_factor_interface/planning_factor_interface.hpp>
22+
#include <autoware_trajectory_modifier/trajectory_modifier_param.hpp>
2223
#include <autoware_utils_debug/time_keeper.hpp>
2324
#include <rclcpp/rclcpp.hpp>
2425

@@ -36,32 +37,35 @@ namespace autoware::trajectory_modifier::plugin
3637
using autoware_internal_planning_msgs::msg::PlanningFactor;
3738
using autoware_planning_msgs::msg::TrajectoryPoint;
3839
using TrajectoryPoints = std::vector<TrajectoryPoint>;
40+
using TrajectoryModifierParams = trajectory_modifier_params::Params;
3941

4042
class TrajectoryModifierPluginBase
4143
{
4244
public:
43-
TrajectoryModifierPluginBase(
45+
TrajectoryModifierPluginBase() = default;
46+
47+
void initialize(
4448
std::string name, rclcpp::Node * node_ptr,
4549
const std::shared_ptr<autoware_utils_debug::TimeKeeper> time_keeper,
4650
[[maybe_unused]] const TrajectoryModifierParams & params)
47-
: name_(std::move(name)), node_ptr_(node_ptr), time_keeper_(time_keeper)
4851
{
52+
name_ = std::move(name);
53+
node_ptr_ = node_ptr;
54+
time_keeper_ = time_keeper;
4955
RCLCPP_DEBUG(
5056
node_ptr_->get_logger(), "instantiated TrajectoryModifierPluginBase: %s", name_.c_str());
57+
on_initialize(params);
5158
}
59+
5260
virtual ~TrajectoryModifierPluginBase() = default;
5361
virtual void modify_trajectory(
54-
TrajectoryPoints & traj_points, const TrajectoryModifierParams & params,
55-
const TrajectoryModifierData & data) = 0;
56-
virtual void set_up_params() = 0;
57-
virtual rcl_interfaces::msg::SetParametersResult on_parameter(
58-
const std::vector<rclcpp::Parameter> & parameters) = 0;
62+
TrajectoryPoints & traj_points, const TrajectoryModifierData & data) = 0;
5963
virtual bool is_trajectory_modification_required(
60-
const TrajectoryPoints & traj_points, const TrajectoryModifierParams & params,
61-
const TrajectoryModifierData & data) const = 0;
64+
const TrajectoryPoints & traj_points, const TrajectoryModifierData & data) const = 0;
6265
std::string get_name() const { return name_; }
6366
rclcpp::Node * get_node_ptr() const { return node_ptr_; }
6467
std::shared_ptr<autoware_utils_debug::TimeKeeper> get_time_keeper() const { return time_keeper_; }
68+
virtual void update_params(const TrajectoryModifierParams & params) = 0;
6569

6670
virtual void publish_planning_factor()
6771
{
@@ -78,8 +82,10 @@ class TrajectoryModifierPluginBase
7882
}
7983

8084
protected:
85+
virtual void on_initialize(const TrajectoryModifierParams & params) = 0;
8186
std::unique_ptr<autoware::planning_factor_interface::PlanningFactorInterface>
8287
planning_factor_interface_;
88+
bool enabled_{true};
8389

8490
private:
8591
std::string name_;

planning/autoware_trajectory_modifier/include/autoware/trajectory_modifier/trajectory_modifier_structs.hpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,11 +22,6 @@ namespace autoware::trajectory_modifier
2222
using geometry_msgs::msg::AccelWithCovarianceStamped;
2323
using nav_msgs::msg::Odometry;
2424

25-
struct TrajectoryModifierParams
26-
{
27-
bool use_stop_point_fixer{true};
28-
};
29-
3025
struct TrajectoryModifierData
3126
{
3227
Odometry current_odometry;

planning/autoware_trajectory_modifier/launch/trajectory_modifier.launch.xml

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,19 @@
44
<arg name="input_odometry" default="/localization/kinematic_state"/>
55
<arg name="input_acceleration" default="/localization/acceleration"/>
66
<arg name="output_candidate_trajectories" default="~/output/candidate_trajectories"/>
7+
<arg name="launch_stop_point_fixer" default="true"/>
8+
<arg name="launch_modules_list_end" default="&quot;&quot;]"/>
9+
<arg name="trajectory_modifier_launch_modules" default="["/>
10+
<let
11+
name="trajectory_modifier_launch_modules"
12+
value="$(eval &quot;'$(var trajectory_modifier_launch_modules)' + 'autoware::trajectory_modifier::plugin::StopPointFixer, '&quot;)"
13+
if="$(var launch_stop_point_fixer)"
14+
/>
15+
<let name="trajectory_modifier_launch_modules" value="$(eval &quot;'$(var trajectory_modifier_launch_modules)' + '$(var launch_modules_list_end)'&quot;)"/>
716

8-
<node pkg="autoware_trajectory_modifier" exec="autoware_trajectory_modifier_node" name="trajectory_modifier" output="screen">
17+
<node pkg="autoware_trajectory_modifier" exec="autoware_trajectory_modifier_node" name="trajectory_modifier" output="screen" launch-prefix="konsole -e gdb -ex run --args">
918
<param from="$(var trajectory_modifier_param_path)"/>
19+
<param name="launch_modules" value="$(var trajectory_modifier_launch_modules)"/>
1020
<remap from="~/input/candidate_trajectories" to="$(var input_candidate_trajectories)"/>
1121
<remap from="~/input/odometry" to="$(var input_odometry)"/>
1222
<remap from="~/input/acceleration" to="$(var input_acceleration)"/>

planning/autoware_trajectory_modifier/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,10 @@
2222
<depend>autoware_utils</depend>
2323
<depend>autoware_utils_debug</depend>
2424
<depend>autoware_utils_rclcpp</depend>
25+
<depend>generate_parameter_library</depend>
2526
<depend>geometry_msgs</depend>
2627
<depend>nav_msgs</depend>
28+
<depend>pluginlib</depend>
2729
<depend>rclcpp</depend>
2830
<depend>rclcpp_components</depend>
2931

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
trajectory_modifier_params:
2+
use_stop_point_fixer:
3+
type: bool
4+
default_value: false
5+
description: Enable the use of stop point fixer
6+
read_only: false
7+
8+
stop_point_fixer:
9+
velocity_threshold_mps:
10+
type: double
11+
default_value: 0.1
12+
description: Velocity threshold below which ego vehicle is considered stationary [m/s]
13+
read_only: false
14+
validation:
15+
gt_eq<>: [0.0]
16+
min_distance_threshold_m:
17+
type: double
18+
default_value: 1.0
19+
description: Minimum distance threshold to trigger trajectory replacement [m]
20+
read_only: false
21+
validation:
22+
gt_eq<>: [0.0]
Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
<?xml version="1.0"?>
2+
<library path="autoware_trajectory_modifier_plugins">
3+
<class type="autoware::trajectory_modifier::plugin::StopPointFixer"
4+
base_class_type="autoware::trajectory_modifier::plugin::TrajectoryModifierPluginBase">
5+
<description>
6+
Modifies the stop point of a trajectory to align with the obstacle stop point
7+
</description>
8+
</class>
9+
</library>

0 commit comments

Comments
 (0)