Skip to content

Commit

Permalink
feat(behavior_velocity_planner): change planner data update (autoware…
Browse files Browse the repository at this point in the history
…foundation#2531)

Signed-off-by: yutaka <purewater0901@gmail.com>

Signed-off-by: yutaka <purewater0901@gmail.com>
  • Loading branch information
purewater0901 authored Dec 23, 2022
1 parent 1f41e67 commit c958fdd
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@

namespace behavior_velocity_planner
{
using autoware_auto_mapping_msgs::msg::HADMapBin;
using tier4_planning_msgs::msg::VelocityLimit;
class BehaviorVelocityPlannerNode : public rclcpp::Node
{
Expand Down Expand Up @@ -109,6 +110,8 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
PlannerData planner_data_;
BehaviorVelocityPlannerManager planner_manager_;
bool is_driving_forward_{true};
HADMapBin::ConstSharedPtr map_ptr_{nullptr};
bool has_received_map_;

// mutex for planner_data_
std::mutex mutex_;
Expand Down
23 changes: 15 additions & 8 deletions planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,12 +238,7 @@ bool BehaviorVelocityPlannerNode::isDataReady(
RCLCPP_INFO_THROTTLE(get_logger(), clock, 3000, "Waiting for pointcloud");
return false;
}
if (!d.route_handler_) {
RCLCPP_INFO_THROTTLE(
get_logger(), clock, 3000, "Waiting for the initialization of route_handler");
return false;
}
if (!d.route_handler_->isMapMsgReady()) {
if (!map_ptr_) {
RCLCPP_INFO_THROTTLE(get_logger(), clock, 3000, "Waiting for the initialization of map");
return false;
}
Expand Down Expand Up @@ -344,8 +339,8 @@ void BehaviorVelocityPlannerNode::onLaneletMap(
{
std::lock_guard<std::mutex> lock(mutex_);

// Load map
planner_data_.route_handler_ = std::make_shared<route_handler::RouteHandler>(*msg);
map_ptr_ = msg;
has_received_map_ = true;
}

void BehaviorVelocityPlannerNode::onTrafficSignals(
Expand Down Expand Up @@ -419,6 +414,18 @@ void BehaviorVelocityPlannerNode::onTrigger(
return;
}

// Load map and check route handler
if (has_received_map_) {
planner_data_.route_handler_ = std::make_shared<route_handler::RouteHandler>(*map_ptr_);
has_received_map_ = false;
}
if (!planner_data_.route_handler_) {
RCLCPP_INFO_THROTTLE(
get_logger(), *get_clock(), 3000, "Waiting for the initialization of route_handler");
mutex_.unlock();
return;
}

// NOTE: planner_data must not be referenced for multithreading
const auto planner_data = planner_data_;
mutex_.unlock();
Expand Down

0 comments on commit c958fdd

Please sign in to comment.