Skip to content

Commit

Permalink
fix(behavior_velocity_planner_common): sync activation when safety st…
Browse files Browse the repository at this point in the history
…atus is set (autowarefoundation#5697)

* fix(behavior_velocity_planner_common): sync activation when safety status is set

Signed-off-by: Fumiya Watanabe <[email protected]>

* Update planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp

Co-authored-by: Kyoichi Sugahara <[email protected]>

* Update planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp

Co-authored-by: Tomoya Kimura <[email protected]>

---------

Signed-off-by: Fumiya Watanabe <[email protected]>
Co-authored-by: Kyoichi Sugahara <[email protected]>
Co-authored-by: Tomoya Kimura <[email protected]>
  • Loading branch information
3 people authored and danielsanchezaran committed Dec 15, 2023
1 parent db2de55 commit 5772243
Show file tree
Hide file tree
Showing 4 changed files with 28 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ class SceneModuleInterface
boost::optional<int> getFirstStopPathPointIndex() { return first_stop_path_point_index_; }

void setActivation(const bool activated) { activated_ = activated; }
void setRTCEnabled(const bool enable_rtc) { rtc_enabled_ = enable_rtc; }
bool isActivated() const { return activated_; }
bool isSafe() const { return safe_; }
double getDistance() const { return distance_; }
Expand All @@ -98,6 +99,7 @@ class SceneModuleInterface
const int64_t module_id_;
bool activated_;
bool safe_;
bool rtc_enabled_;
double distance_;
rclcpp::Logger logger_;
rclcpp::Clock::SharedPtr clock_;
Expand All @@ -106,8 +108,15 @@ class SceneModuleInterface
boost::optional<int> first_stop_path_point_index_;
VelocityFactorInterface velocity_factor_;

void setSafe(const bool safe) { safe_ = safe; }
void setSafe(const bool safe)
{
safe_ = safe;
if (!rtc_enabled_) {
syncActivation();
}
}
void setDistance(const double distance) { distance_ = distance; }
void syncActivation() { setActivation(isSafe()); }

size_t findEgoSegmentIndex(
const std::vector<autoware_auto_planning_msgs::msg::PathPointWithLaneId> & points) const;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -218,6 +218,7 @@ void SceneModuleManagerInterfaceWithRTC::setActivation()
for (const auto & scene_module : scene_modules_) {
const UUID uuid = getUUID(scene_module->getModuleId());
scene_module->setActivation(rtc_interface_.isActivated(uuid));
scene_module->setRTCEnabled(rtc_interface_.isRTCEnabled(uuid));
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ class RTCInterface
void clearCooperateStatus();
bool isActivated(const UUID & uuid) const;
bool isRegistered(const UUID & uuid) const;
bool isRTCEnabled(const UUID & uuid) const;
void lockCommandUpdate();
void unlockCommandUpdate();

Expand Down
16 changes: 16 additions & 0 deletions planning/rtc_interface/src/rtc_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -280,6 +280,22 @@ bool RTCInterface::isRegistered(const UUID & uuid) const
return itr != registered_status_.statuses.end();
}

bool RTCInterface::isRTCEnabled(const UUID & uuid) const
{
std::lock_guard<std::mutex> lock(mutex_);
const auto itr = std::find_if(
registered_status_.statuses.begin(), registered_status_.statuses.end(),
[uuid](auto & s) { return s.uuid == uuid; });

if (itr != registered_status_.statuses.end()) {
return !itr->auto_mode;
}

RCLCPP_WARN_STREAM(
getLogger(), "[isRTCEnabled] uuid : " << to_string(uuid) << " is not found." << std::endl);
return is_auto_mode_init_;
}

void RTCInterface::lockCommandUpdate()
{
is_locked_ = true;
Expand Down

0 comments on commit 5772243

Please sign in to comment.