Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(mission_planner/behavior_path_planner): use transient local for modified goal #5012

Merged
merged 1 commit into from
Sep 19, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,9 @@
turn_signal_publisher_ =
create_publisher<TurnIndicatorsCommand>("~/output/turn_indicators_cmd", 1);
hazard_signal_publisher_ = create_publisher<HazardLightsCommand>("~/output/hazard_lights_cmd", 1);
modified_goal_publisher_ = create_publisher<PoseWithUuidStamped>("~/output/modified_goal", 1);
const auto durable_qos = rclcpp::QoS(1).transient_local();
modified_goal_publisher_ =
create_publisher<PoseWithUuidStamped>("~/output/modified_goal", durable_qos);

Check warning on line 71 in planning/behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

BehaviorPathPlannerNode::BehaviorPathPlannerNode already has high cyclomatic complexity, and now it increases in Lines of Code from 178 to 180. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
stop_reason_publisher_ = create_publisher<StopReasonArray>("~/output/stop_reasons", 1);
reroute_availability_publisher_ =
create_publisher<RerouteAvailability>("~/output/is_reroute_available", 1);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,12 +99,14 @@
rclcpp::QoS(1),
std::bind(&MissionPlanner::on_reroute_availability, this, std::placeholders::_1));

auto qos_transient_local = rclcpp::QoS{1}.transient_local();
const auto durable_qos = rclcpp::QoS(1).transient_local();

Check warning on line 102 in planning/mission_planner/src/mission_planner/mission_planner.cpp

View check run for this annotation

Codecov / codecov/patch

planning/mission_planner/src/mission_planner/mission_planner.cpp#L102

Added line #L102 was not covered by tests
sub_vector_map_ = create_subscription<HADMapBin>(
"input/vector_map", qos_transient_local,
"input/vector_map", durable_qos,
std::bind(&MissionPlanner::on_map, this, std::placeholders::_1));
sub_modified_goal_ = create_subscription<PoseWithUuidStamped>(

Check warning on line 106 in planning/mission_planner/src/mission_planner/mission_planner.cpp

View check run for this annotation

Codecov / codecov/patch

planning/mission_planner/src/mission_planner/mission_planner.cpp#L106

Added line #L106 was not covered by tests
"input/modified_goal", durable_qos,
std::bind(&MissionPlanner::on_modified_goal, this, std::placeholders::_1));

Check warning on line 108 in planning/mission_planner/src/mission_planner/mission_planner.cpp

View check run for this annotation

Codecov / codecov/patch

planning/mission_planner/src/mission_planner/mission_planner.cpp#L108

Added line #L108 was not covered by tests

const auto durable_qos = rclcpp::QoS(1).transient_local();
pub_marker_ = create_publisher<MarkerArray>("debug/route_marker", durable_qos);

const auto adaptor = component_interface_utils::NodeAdaptor(this);
Expand All @@ -119,7 +121,6 @@
adaptor.init_srv(srv_change_route_points_, this, &MissionPlanner::on_change_route_points);
adaptor.init_srv(srv_set_mrm_route_, this, &MissionPlanner::on_set_mrm_route);
adaptor.init_srv(srv_clear_mrm_route_, this, &MissionPlanner::on_clear_mrm_route);
adaptor.init_sub(sub_modified_goal_, this, &MissionPlanner::on_modified_goal);

change_state(RouteState::Message::UNSET);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,12 +75,15 @@ class MissionPlanner : public rclcpp::Node
rclcpp::Subscription<Odometry>::SharedPtr sub_odometry_;
rclcpp::Subscription<HADMapBin>::SharedPtr sub_vector_map_;
rclcpp::Subscription<RerouteAvailability>::SharedPtr sub_reroute_availability_;
rclcpp::Subscription<PoseWithUuidStamped>::SharedPtr sub_modified_goal_;

Odometry::ConstSharedPtr odometry_;
HADMapBin::ConstSharedPtr map_ptr_;
RerouteAvailability::ConstSharedPtr reroute_availability_;
void on_odometry(const Odometry::ConstSharedPtr msg);
void on_map(const HADMapBin::ConstSharedPtr msg);
void on_reroute_availability(const RerouteAvailability::ConstSharedPtr msg);
void on_modified_goal(const PoseWithUuidStamped::ConstSharedPtr msg);

rclcpp::Publisher<MarkerArray>::SharedPtr pub_marker_;
void clear_route();
Expand Down Expand Up @@ -128,8 +131,6 @@ class MissionPlanner : public rclcpp::Node
const ClearMrmRoute::Service::Request::SharedPtr req,
const ClearMrmRoute::Service::Response::SharedPtr res);

component_interface_utils::Subscription<ModifiedGoal>::SharedPtr sub_modified_goal_;
void on_modified_goal(const ModifiedGoal::Message::ConstSharedPtr msg);
void on_change_route(
const SetRoute::Service::Request::SharedPtr req,
const SetRoute::Service::Response::SharedPtr res);
Expand Down
Loading