Skip to content

Commit

Permalink
refactor(crosswalk): use getOrDeclareParameter (autowarefoundation#4765)
Browse files Browse the repository at this point in the history
Signed-off-by: Takamasa Horibe <[email protected]>
  • Loading branch information
TakaHoribe authored Aug 28, 2023
1 parent bb702a6 commit e017725
Showing 1 changed file with 43 additions and 35 deletions.
78 changes: 43 additions & 35 deletions planning/behavior_velocity_crosswalk_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "manager.hpp"

#include <behavior_velocity_planner_common/utilization/util.hpp>
#include <tier4_autoware_utils/ros/parameter.hpp>

#include <limits>
#include <memory>
Expand All @@ -26,86 +27,93 @@ namespace behavior_velocity_planner
{

using lanelet::autoware::Crosswalk;
using tier4_autoware_utils::getOrDeclareParameter;

CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
node.declare_parameter<bool>(std::string(getModuleName()) + ".common.enable_rtc"))
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".common.enable_rtc"))
{
const std::string ns(getModuleName());

// for crosswalk parameters
auto & cp = crosswalk_planner_param_;
cp.show_processing_time = node.declare_parameter<bool>(ns + ".common.show_processing_time");
cp.show_processing_time = getOrDeclareParameter<bool>(node, ns + ".common.show_processing_time");

// param for input data
cp.traffic_light_state_timeout =
node.declare_parameter<double>(ns + ".common.traffic_light_state_timeout");
getOrDeclareParameter<double>(node, ns + ".common.traffic_light_state_timeout");

// param for stop position
cp.stop_distance_from_crosswalk =
node.declare_parameter<double>(ns + ".stop_position.stop_distance_from_crosswalk");
getOrDeclareParameter<double>(node, ns + ".stop_position.stop_distance_from_crosswalk");
cp.stop_distance_from_object =
node.declare_parameter<double>(ns + ".stop_position.stop_distance_from_object");
getOrDeclareParameter<double>(node, ns + ".stop_position.stop_distance_from_object");
cp.far_object_threshold =
node.declare_parameter<double>(ns + ".stop_position.far_object_threshold");
getOrDeclareParameter<double>(node, ns + ".stop_position.far_object_threshold");
cp.stop_position_threshold =
node.declare_parameter<double>(ns + ".stop_position.stop_position_threshold");
getOrDeclareParameter<double>(node, ns + ".stop_position.stop_position_threshold");

// param for ego velocity
cp.min_slow_down_velocity =
node.declare_parameter<double>(ns + ".slow_down.min_slow_down_velocity");
cp.max_slow_down_jerk = node.declare_parameter<double>(ns + ".slow_down.max_slow_down_jerk");
cp.max_slow_down_accel = node.declare_parameter<double>(ns + ".slow_down.max_slow_down_accel");
cp.no_relax_velocity = node.declare_parameter<double>(ns + ".slow_down.no_relax_velocity");
getOrDeclareParameter<double>(node, ns + ".slow_down.min_slow_down_velocity");
cp.max_slow_down_jerk = getOrDeclareParameter<double>(node, ns + ".slow_down.max_slow_down_jerk");
cp.max_slow_down_accel =
getOrDeclareParameter<double>(node, ns + ".slow_down.max_slow_down_accel");
cp.no_relax_velocity = getOrDeclareParameter<double>(node, ns + ".slow_down.no_relax_velocity");

// param for stuck vehicle
cp.stuck_vehicle_velocity =
node.declare_parameter<double>(ns + ".stuck_vehicle.stuck_vehicle_velocity");
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.stuck_vehicle_velocity");
cp.max_stuck_vehicle_lateral_offset =
node.declare_parameter<double>(ns + ".stuck_vehicle.max_stuck_vehicle_lateral_offset");
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.max_stuck_vehicle_lateral_offset");
cp.stuck_vehicle_attention_range =
node.declare_parameter<double>(ns + ".stuck_vehicle.stuck_vehicle_attention_range");
cp.min_acc_for_stuck_vehicle = node.declare_parameter<double>(ns + ".stuck_vehicle.min_acc");
cp.max_jerk_for_stuck_vehicle = node.declare_parameter<double>(ns + ".stuck_vehicle.max_jerk");
cp.min_jerk_for_stuck_vehicle = node.declare_parameter<double>(ns + ".stuck_vehicle.min_jerk");
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.stuck_vehicle_attention_range");
cp.min_acc_for_stuck_vehicle = getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.min_acc");
cp.max_jerk_for_stuck_vehicle =
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.max_jerk");
cp.min_jerk_for_stuck_vehicle =
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.min_jerk");

// param for pass judge logic
cp.ego_pass_first_margin_x =
node.declare_parameter<std::vector<double>>(ns + ".pass_judge.ego_pass_first_margin_x");
getOrDeclareParameter<std::vector<double>>(node, ns + ".pass_judge.ego_pass_first_margin_x");
cp.ego_pass_first_margin_y =
node.declare_parameter<std::vector<double>>(ns + ".pass_judge.ego_pass_first_margin_y");
getOrDeclareParameter<std::vector<double>>(node, ns + ".pass_judge.ego_pass_first_margin_y");
cp.ego_pass_first_additional_margin =
node.declare_parameter<double>(ns + ".pass_judge.ego_pass_first_additional_margin");
getOrDeclareParameter<double>(node, ns + ".pass_judge.ego_pass_first_additional_margin");
cp.ego_pass_later_margin_x =
node.declare_parameter<std::vector<double>>(ns + ".pass_judge.ego_pass_later_margin_x");
getOrDeclareParameter<std::vector<double>>(node, ns + ".pass_judge.ego_pass_later_margin_x");
cp.ego_pass_later_margin_y =
node.declare_parameter<std::vector<double>>(ns + ".pass_judge.ego_pass_later_margin_y");
getOrDeclareParameter<std::vector<double>>(node, ns + ".pass_judge.ego_pass_later_margin_y");
cp.ego_pass_later_additional_margin =
node.declare_parameter<double>(ns + ".pass_judge.ego_pass_later_additional_margin");
getOrDeclareParameter<double>(node, ns + ".pass_judge.ego_pass_later_additional_margin");
cp.max_offset_to_crosswalk_for_yield =
node.declare_parameter<double>(ns + ".pass_judge.max_offset_to_crosswalk_for_yield");
getOrDeclareParameter<double>(node, ns + ".pass_judge.max_offset_to_crosswalk_for_yield");
cp.stop_object_velocity =
node.declare_parameter<double>(ns + ".pass_judge.stop_object_velocity_threshold");
cp.min_object_velocity = node.declare_parameter<double>(ns + ".pass_judge.min_object_velocity");
getOrDeclareParameter<double>(node, ns + ".pass_judge.stop_object_velocity_threshold");
cp.min_object_velocity =
getOrDeclareParameter<double>(node, ns + ".pass_judge.min_object_velocity");
cp.disable_stop_for_yield_cancel =
node.declare_parameter<bool>(ns + ".pass_judge.disable_stop_for_yield_cancel");
getOrDeclareParameter<bool>(node, ns + ".pass_judge.disable_stop_for_yield_cancel");
cp.disable_yield_for_new_stopped_object =
node.declare_parameter<bool>(ns + ".pass_judge.disable_yield_for_new_stopped_object");
getOrDeclareParameter<bool>(node, ns + ".pass_judge.disable_yield_for_new_stopped_object");
cp.timeout_no_intention_to_walk =
node.declare_parameter<double>(ns + ".pass_judge.timeout_no_intention_to_walk");
getOrDeclareParameter<double>(node, ns + ".pass_judge.timeout_no_intention_to_walk");
cp.timeout_ego_stop_for_yield =
node.declare_parameter<double>(ns + ".pass_judge.timeout_ego_stop_for_yield");
getOrDeclareParameter<double>(node, ns + ".pass_judge.timeout_ego_stop_for_yield");

// param for target area & object
cp.crosswalk_attention_range =
node.declare_parameter<double>(ns + ".object_filtering.crosswalk_attention_range");
cp.look_unknown = node.declare_parameter<bool>(ns + ".object_filtering.target_object.unknown");
cp.look_bicycle = node.declare_parameter<bool>(ns + ".object_filtering.target_object.bicycle");
getOrDeclareParameter<double>(node, ns + ".object_filtering.crosswalk_attention_range");
cp.look_unknown =
getOrDeclareParameter<bool>(node, ns + ".object_filtering.target_object.unknown");
cp.look_bicycle =
getOrDeclareParameter<bool>(node, ns + ".object_filtering.target_object.bicycle");
cp.look_motorcycle =
node.declare_parameter<bool>(ns + ".object_filtering.target_object.motorcycle");
getOrDeclareParameter<bool>(node, ns + ".object_filtering.target_object.motorcycle");
cp.look_pedestrian =
node.declare_parameter<bool>(ns + ".object_filtering.target_object.pedestrian");
getOrDeclareParameter<bool>(node, ns + ".object_filtering.target_object.pedestrian");
}

void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path)
Expand Down

0 comments on commit e017725

Please sign in to comment.