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

feat(rtc_interface)!: add new field to rtc cooperate status #6933

Merged
merged 3 commits into from
May 13, 2024
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 @@ -57,7 +57,10 @@ void AvoidanceByLaneChangeInterface::updateRTCStatus(
return (dir == Direction::LEFT) ? "left" : "right";
});

const auto state = isWaitingApproval() ? State::WAITING_FOR_EXECUTION : State::RUNNING;

rtc_interface_ptr_map_.at(direction)->updateCooperateStatus(
uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now());
uuid_map_.at(direction), isExecutionReady(), state, start_distance, finish_distance,
clock_->now());
}
} // namespace behavior_path_planner
Original file line number Diff line number Diff line change
Expand Up @@ -77,15 +77,17 @@ class AvoidanceModule : public SceneModuleInterface
{
if (candidate.lateral_shift > 0.0) {
rtc_interface_ptr_map_.at("left")->updateCooperateStatus(
uuid_map_.at("left"), isExecutionReady(), candidate.start_distance_to_path_change,
candidate.finish_distance_to_path_change, clock_->now());
uuid_map_.at("left"), isExecutionReady(), State::WAITING_FOR_EXECUTION,
candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change,
clock_->now());
candidate_uuid_ = uuid_map_.at("left");
return;
}
if (candidate.lateral_shift < 0.0) {
rtc_interface_ptr_map_.at("right")->updateCooperateStatus(
uuid_map_.at("right"), isExecutionReady(), candidate.start_distance_to_path_change,
candidate.finish_distance_to_path_change, clock_->now());
uuid_map_.at("right"), isExecutionReady(), State::WAITING_FOR_EXECUTION,
candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change,
clock_->now());
candidate_uuid_ = uuid_map_.at("right");
return;
}
Expand All @@ -108,7 +110,7 @@ class AvoidanceModule : public SceneModuleInterface
motion_utils::calcSignedArcLength(path.points, ego_idx, left_shift.start_pose.position);
const double finish_distance = start_distance + left_shift.relative_longitudinal;
rtc_interface_ptr_map_.at("left")->updateCooperateStatus(
left_shift.uuid, true, start_distance, finish_distance, clock_->now());
left_shift.uuid, true, State::RUNNING, start_distance, finish_distance, clock_->now());
if (finish_distance > -1.0e-03) {
steering_factor_interface_ptr_->updateSteeringFactor(
{left_shift.start_pose, left_shift.finish_pose}, {start_distance, finish_distance},
Expand All @@ -121,7 +123,7 @@ class AvoidanceModule : public SceneModuleInterface
motion_utils::calcSignedArcLength(path.points, ego_idx, right_shift.start_pose.position);
const double finish_distance = start_distance + right_shift.relative_longitudinal;
rtc_interface_ptr_map_.at("right")->updateCooperateStatus(
right_shift.uuid, true, start_distance, finish_distance, clock_->now());
right_shift.uuid, true, State::RUNNING, start_distance, finish_distance, clock_->now());
if (finish_distance > -1.0e-03) {
steering_factor_interface_ptr_->updateSteeringFactor(
{right_shift.start_pose, right_shift.finish_pose}, {start_distance, finish_distance},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include <autoware_auto_vehicle_msgs/msg/turn_indicators_command.hpp>
#include <tier4_planning_msgs/msg/avoidance_debug_msg.hpp>
#include <tier4_planning_msgs/msg/avoidance_debug_msg_array.hpp>
#include <tier4_rtc_msgs/msg/state.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

namespace behavior_path_planner
Expand All @@ -49,6 +50,7 @@ using visualization_msgs::msg::MarkerArray;
// tier4 msgs
using tier4_planning_msgs::msg::AvoidanceDebugMsg;
using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
using tier4_rtc_msgs::msg::State;

// tier4 utils functions
using tier4_autoware_utils::appendMarkerArray;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <tier4_planning_msgs/msg/stop_factor.hpp>
#include <tier4_planning_msgs/msg/stop_reason.hpp>
#include <tier4_planning_msgs/msg/stop_reason_array.hpp>
#include <tier4_rtc_msgs/msg/state.hpp>
#include <unique_identifier_msgs/msg/uuid.hpp>
#include <visualization_msgs/msg/detail/marker_array__struct.hpp>

Expand All @@ -67,6 +68,7 @@ using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
using tier4_planning_msgs::msg::StopFactor;
using tier4_planning_msgs::msg::StopReason;
using tier4_planning_msgs::msg::StopReasonArray;
using tier4_rtc_msgs::msg::State;
using unique_identifier_msgs::msg::UUID;
using visualization_msgs::msg::MarkerArray;
using PlanResult = PathWithLaneId::SharedPtr;
Expand Down Expand Up @@ -490,8 +492,9 @@ class SceneModuleInterface
{
for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) {
if (ptr) {
const auto state = isWaitingApproval() ? State::WAITING_FOR_EXECUTION : State::RUNNING;
ptr->updateCooperateStatus(
uuid_map_.at(module_name), isExecutionReady(), start_distance, finish_distance,
uuid_map_.at(module_name), isExecutionReady(), state, start_distance, finish_distance,
clock_->now());
}
}
Expand Down
3 changes: 2 additions & 1 deletion planning/behavior_velocity_blind_spot_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,8 @@ void BlindSpotModuleManager::launchNewModules(
clock_));
generateUUID(module_id);
updateRTCStatus(
getUUID(module_id), true, std::numeric_limits<double>::lowest(), path.header.stamp);
getUUID(module_id), true, State::WAITING_FOR_EXECUTION, std::numeric_limits<double>::lowest(),
path.header.stamp);
}
}

Expand Down
4 changes: 2 additions & 2 deletions planning/behavior_velocity_crosswalk_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,8 +190,8 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path)
clock_));
generateUUID(crosswalk_lanelet_id);
updateRTCStatus(
getUUID(crosswalk_lanelet_id), true, std::numeric_limits<double>::lowest(),
path.header.stamp);
getUUID(crosswalk_lanelet_id), true, State::WAITING_FOR_EXECUTION,
std::numeric_limits<double>::lowest(), path.header.stamp);
};

const auto crosswalk_reg_elem_map = planning_utils::getRegElemMapOnPath<Crosswalk>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,8 @@ void DetectionAreaModuleManager::launchNewModules(
logger_.get_child("detection_area_module"), clock_));
generateUUID(module_id);
updateRTCStatus(
getUUID(module_id), true, std::numeric_limits<double>::lowest(), path.header.stamp);
getUUID(module_id), true, State::WAITING_FOR_EXECUTION,
std::numeric_limits<double>::lowest(), path.header.stamp);
}
}
}
Expand Down
11 changes: 6 additions & 5 deletions planning/behavior_velocity_intersection_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -345,10 +345,10 @@ void IntersectionModuleManager::launchNewModules(
const UUID uuid = getUUID(new_module->getModuleId());
const auto occlusion_uuid = new_module->getOcclusionUUID();
rtc_interface_.updateCooperateStatus(
uuid, true, std::numeric_limits<double>::lowest(), std::numeric_limits<double>::lowest(),
clock_->now());
uuid, true, State::RUNNING, std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::lowest(), clock_->now());
occlusion_rtc_interface_.updateCooperateStatus(
occlusion_uuid, true, std::numeric_limits<double>::lowest(),
occlusion_uuid, true, State::RUNNING, std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::lowest(), clock_->now());
registerModule(std::move(new_module));
}
Expand Down Expand Up @@ -404,12 +404,13 @@ void IntersectionModuleManager::sendRTC(const Time & stamp)
const UUID uuid = getUUID(scene_module->getModuleId());
const bool safety =
scene_module->isSafe() && (!intersection_module->isOcclusionFirstStopRequired());
updateRTCStatus(uuid, safety, scene_module->getDistance(), stamp);
updateRTCStatus(uuid, safety, State::RUNNING, scene_module->getDistance(), stamp);
const auto occlusion_uuid = intersection_module->getOcclusionUUID();
const auto occlusion_distance = intersection_module->getOcclusionDistance();
const auto occlusion_safety = intersection_module->getOcclusionSafety();
occlusion_rtc_interface_.updateCooperateStatus(
occlusion_uuid, occlusion_safety, occlusion_distance, occlusion_distance, stamp);
occlusion_uuid, occlusion_safety, State::RUNNING, occlusion_distance, occlusion_distance,
stamp);

// ==========================================================================================
// module debug data
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,8 @@ void NoStoppingAreaModuleManager::launchNewModules(
clock_));
generateUUID(module_id);
updateRTCStatus(
getUUID(module_id), true, std::numeric_limits<double>::lowest(), path.header.stamp);
getUUID(module_id), true, State::WAITING_FOR_EXECUTION,
std::numeric_limits<double>::lowest(), path.header.stamp);
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
#include <tier4_planning_msgs/msg/stop_reason.hpp>
#include <tier4_planning_msgs/msg/stop_reason_array.hpp>
#include <tier4_rtc_msgs/msg/state.hpp>
#include <tier4_v2x_msgs/msg/infrastructure_command_array.hpp>
#include <unique_identifier_msgs/msg/uuid.hpp>

Expand Down Expand Up @@ -58,6 +59,7 @@ using tier4_debug_msgs::msg::Float64Stamped;
using tier4_planning_msgs::msg::StopFactor;
using tier4_planning_msgs::msg::StopReason;
using tier4_rtc_msgs::msg::Module;
using tier4_rtc_msgs::msg::State;
using unique_identifier_msgs::msg::UUID;

struct ObjectOfInterest
Expand Down Expand Up @@ -235,9 +237,10 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface
virtual void setActivation();

void updateRTCStatus(
const UUID & uuid, const bool safe, const double distance, const Time & stamp)
const UUID & uuid, const bool safe, const uint8_t state, const double distance,
const Time & stamp)
{
rtc_interface_.updateCooperateStatus(uuid, safe, distance, distance, stamp);
rtc_interface_.updateCooperateStatus(uuid, safe, state, distance, distance, stamp);
}

void removeRTCStatus(const UUID & uuid) { rtc_interface_.removeCooperateStatus(uuid); }
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,8 @@ void SceneModuleManagerInterfaceWithRTC::sendRTC(const Time & stamp)
{
for (const auto & scene_module : scene_modules_) {
const UUID uuid = getUUID(scene_module->getModuleId());
updateRTCStatus(uuid, scene_module->isSafe(), scene_module->getDistance(), stamp);
const auto state = scene_module->isActivated() ? State::RUNNING : State::WAITING_FOR_EXECUTION;
updateRTCStatus(uuid, scene_module->isSafe(), state, scene_module->getDistance(), stamp);
}
publishRTCStatus(stamp);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,8 @@ void TrafficLightModuleManager::launchNewModules(
planner_param_, logger_.get_child("traffic_light_module"), clock_));
generateUUID(module_id);
updateRTCStatus(
getUUID(module_id), true, std::numeric_limits<double>::lowest(), path.header.stamp);
getUUID(module_id), true, State::WAITING_FOR_EXECUTION,
std::numeric_limits<double>::lowest(), path.header.stamp);
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include "tier4_rtc_msgs/msg/cooperate_status.hpp"
#include "tier4_rtc_msgs/msg/cooperate_status_array.hpp"
#include "tier4_rtc_msgs/msg/module.hpp"
#include "tier4_rtc_msgs/msg/state.hpp"
#include "tier4_rtc_msgs/srv/auto_mode.hpp"
#include "tier4_rtc_msgs/srv/cooperate_commands.hpp"
#include <unique_identifier_msgs/msg/uuid.hpp>
Expand All @@ -41,6 +42,7 @@ using tier4_rtc_msgs::msg::CooperateResponse;
using tier4_rtc_msgs::msg::CooperateStatus;
using tier4_rtc_msgs::msg::CooperateStatusArray;
using tier4_rtc_msgs::msg::Module;
using tier4_rtc_msgs::msg::State;
using tier4_rtc_msgs::srv::AutoMode;
using tier4_rtc_msgs::srv::CooperateCommands;
using unique_identifier_msgs::msg::UUID;
Expand All @@ -51,8 +53,8 @@ class RTCInterface
RTCInterface(rclcpp::Node * node, const std::string & name, const bool enable_rtc = true);
void publishCooperateStatus(const rclcpp::Time & stamp);
void updateCooperateStatus(
const UUID & uuid, const bool safe, const double start_distance, const double finish_distance,
const rclcpp::Time & stamp);
const UUID & uuid, const bool safe, const uint8_t state, const double start_distance,
const double finish_distance, const rclcpp::Time & stamp);
void removeCooperateStatus(const UUID & uuid);
void clearCooperateStatus();
bool isActivated(const UUID & uuid) const;
Expand Down
6 changes: 4 additions & 2 deletions planning/rtc_interface/src/rtc_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,33 +201,35 @@
}

void RTCInterface::updateCooperateStatus(
const UUID & uuid, const bool safe, const double start_distance, const double finish_distance,
const rclcpp::Time & stamp)
const UUID & uuid, const bool safe, const uint8_t state, const double start_distance,
const double finish_distance, const rclcpp::Time & stamp)
{
std::lock_guard<std::mutex> lock(mutex_);
// Find registered status which has same uuid
auto itr = std::find_if(
registered_status_.statuses.begin(), registered_status_.statuses.end(),
[uuid](auto & s) { return s.uuid == uuid; });

// If there is no registered status, add it
if (itr == registered_status_.statuses.end()) {
CooperateStatus status;
status.stamp = stamp;
status.uuid = uuid;
status.module = module_;
status.safe = safe;
status.command_status.type = Command::DEACTIVATE;
status.state.type = State::WAITING_FOR_EXECUTION;
status.start_distance = start_distance;
status.finish_distance = finish_distance;
status.auto_mode = is_auto_mode_enabled_;
registered_status_.statuses.push_back(status);
return;
}

// If the registered status is found, update status
itr->stamp = stamp;
itr->safe = safe;
itr->state.type = state;

Check notice on line 232 in planning/rtc_interface/src/rtc_interface.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Excess Number of Function Arguments

RTCInterface::updateCooperateStatus increases from 5 to 6 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.
itr->start_distance = start_distance;
itr->finish_distance = finish_distance;
}
Expand Down
Loading