Skip to content

Commit

Permalink
fix(behavior_velocity_planner): fix conflicts
Browse files Browse the repository at this point in the history
Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>
  • Loading branch information
rej55 committed Jun 16, 2022
1 parent ee97f62 commit ef7d71d
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 30 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ class CrosswalkModuleManager : public SceneModuleManagerInterfaceWithRTC
private:
CrosswalkModule::PlannerParam crosswalk_planner_param_;
WalkwayModule::PlannerParam walkway_planner_param_;
rtc_interface::RTCInterface rtc_interface_;

std::vector<lanelet::ConstLanelet> getCrosswalksOnPath(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
Expand All @@ -51,7 +50,7 @@ class CrosswalkModuleManager : public SceneModuleManagerInterfaceWithRTC
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const lanelet::LaneletMapPtr lanelet_map,
const std::shared_ptr<const lanelet::routing::RoutingGraphContainer> & overall_graphs);

void launchNewModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override;

std::function<bool(const std::shared_ptr<SceneModuleInterface> &)> getModuleExpiredFunction(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,9 @@

#include "behavior_velocity_planner/planner_data.hpp"


#include <utilization/util.hpp>
#include <builtin_interfaces/msg/time.hpp>
#include <rtc_interface/rtc_interface.hpp>
#include <utilization/util.hpp>

#include <autoware_auto_planning_msgs/msg/path.hpp>
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
namespace behavior_velocity_planner
{
CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
{
const std::string ns(getModuleName());

Expand Down Expand Up @@ -105,31 +105,6 @@ std::set<int64_t> CrosswalkModuleManager::getCrosswalkIdSetOnPath(
return crosswalk_id_set;
}

} // namespace

CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(node, getModuleName())
{
const std::string ns(getModuleName());

// for crosswalk parameters
auto & cp = crosswalk_planner_param_;
cp.stop_line_distance = node.declare_parameter(ns + ".crosswalk.stop_line_distance", 1.5);
cp.stop_margin = node.declare_parameter(ns + ".crosswalk.stop_margin", 1.0);
cp.slow_margin = node.declare_parameter(ns + ".crosswalk.slow_margin", 2.0);
cp.slow_velocity = node.declare_parameter(ns + ".crosswalk.slow_velocity", 5.0 / 3.6);
cp.stop_predicted_object_prediction_time_margin =
node.declare_parameter(ns + ".crosswalk.stop_predicted_object_prediction_time_margin", 3.0);
cp.external_input_timeout = node.declare_parameter(ns + ".crosswalk.external_input_timeout", 1.0);

// for walkway parameters
auto & wp = walkway_planner_param_;
wp.stop_margin = node.declare_parameter(ns + ".walkway.stop_margin", 1.0);
wp.stop_line_distance = node.declare_parameter(ns + ".walkway.stop_line_distance", 1.0);
wp.stop_duration_sec = node.declare_parameter(ns + ".walkway.stop_duration_sec", 1.0);
wp.external_input_timeout = node.declare_parameter(ns + ".walkway.external_input_timeout", 1.0);
}

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

0 comments on commit ef7d71d

Please sign in to comment.