Skip to content

Commit b6518dd

Browse files
satoshi-otago-sakayori
authored andcommitted
feat(rtc_interface)!: add new field to rtc cooperate status (autowarefoundation#6933)
* feat(rtc_interface): add new field Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * feat(bvp): support new rtc cooperate status Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * feat(bpp): support new rtc cooperate status Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 3cc9924 commit b6518dd

File tree

14 files changed

+47
-24
lines changed

14 files changed

+47
-24
lines changed

planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,10 @@ void AvoidanceByLaneChangeInterface::updateRTCStatus(
5757
return (dir == Direction::LEFT) ? "left" : "right";
5858
});
5959

60+
const auto state = isWaitingApproval() ? State::WAITING_FOR_EXECUTION : State::RUNNING;
61+
6062
rtc_interface_ptr_map_.at(direction)->updateCooperateStatus(
61-
uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now());
63+
uuid_map_.at(direction), isExecutionReady(), state, start_distance, finish_distance,
64+
clock_->now());
6265
}
6366
} // namespace behavior_path_planner

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -77,15 +77,17 @@ class AvoidanceModule : public SceneModuleInterface
7777
{
7878
if (candidate.lateral_shift > 0.0) {
7979
rtc_interface_ptr_map_.at("left")->updateCooperateStatus(
80-
uuid_map_.at("left"), isExecutionReady(), candidate.start_distance_to_path_change,
81-
candidate.finish_distance_to_path_change, clock_->now());
80+
uuid_map_.at("left"), isExecutionReady(), State::WAITING_FOR_EXECUTION,
81+
candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change,
82+
clock_->now());
8283
candidate_uuid_ = uuid_map_.at("left");
8384
return;
8485
}
8586
if (candidate.lateral_shift < 0.0) {
8687
rtc_interface_ptr_map_.at("right")->updateCooperateStatus(
87-
uuid_map_.at("right"), isExecutionReady(), candidate.start_distance_to_path_change,
88-
candidate.finish_distance_to_path_change, clock_->now());
88+
uuid_map_.at("right"), isExecutionReady(), State::WAITING_FOR_EXECUTION,
89+
candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change,
90+
clock_->now());
8991
candidate_uuid_ = uuid_map_.at("right");
9092
return;
9193
}

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/type_alias.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
#include <autoware_auto_vehicle_msgs/msg/turn_indicators_command.hpp>
2929
#include <tier4_planning_msgs/msg/avoidance_debug_msg.hpp>
3030
#include <tier4_planning_msgs/msg/avoidance_debug_msg_array.hpp>
31+
#include <tier4_rtc_msgs/msg/state.hpp>
3132
#include <visualization_msgs/msg/marker_array.hpp>
3233

3334
namespace behavior_path_planner
@@ -49,6 +50,7 @@ using visualization_msgs::msg::MarkerArray;
4950
// tier4 msgs
5051
using tier4_planning_msgs::msg::AvoidanceDebugMsg;
5152
using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
53+
using tier4_rtc_msgs::msg::State;
5254

5355
// tier4 utils functions
5456
using tier4_autoware_utils::appendMarkerArray;

planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141
#include <tier4_planning_msgs/msg/stop_factor.hpp>
4242
#include <tier4_planning_msgs/msg/stop_reason.hpp>
4343
#include <tier4_planning_msgs/msg/stop_reason_array.hpp>
44+
#include <tier4_rtc_msgs/msg/state.hpp>
4445
#include <unique_identifier_msgs/msg/uuid.hpp>
4546
#include <visualization_msgs/msg/detail/marker_array__struct.hpp>
4647

@@ -67,6 +68,7 @@ using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
6768
using tier4_planning_msgs::msg::StopFactor;
6869
using tier4_planning_msgs::msg::StopReason;
6970
using tier4_planning_msgs::msg::StopReasonArray;
71+
using tier4_rtc_msgs::msg::State;
7072
using unique_identifier_msgs::msg::UUID;
7173
using visualization_msgs::msg::MarkerArray;
7274
using PlanResult = PathWithLaneId::SharedPtr;
@@ -503,8 +505,9 @@ class SceneModuleInterface
503505
{
504506
for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) {
505507
if (ptr) {
508+
const auto state = isWaitingApproval() ? State::WAITING_FOR_EXECUTION : State::RUNNING;
506509
ptr->updateCooperateStatus(
507-
uuid_map_.at(module_name), isExecutionReady(), start_distance, finish_distance,
510+
uuid_map_.at(module_name), isExecutionReady(), state, start_distance, finish_distance,
508511
clock_->now());
509512
}
510513
}

planning/behavior_velocity_blind_spot_module/src/manager.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,8 @@ void BlindSpotModuleManager::launchNewModules(
7979
logger_.get_child("blind_spot_module"), clock_));
8080
generateUUID(module_id);
8181
updateRTCStatus(
82-
getUUID(module_id), true, std::numeric_limits<double>::lowest(), path.header.stamp);
82+
getUUID(module_id), true, State::WAITING_FOR_EXECUTION, std::numeric_limits<double>::lowest(),
83+
path.header.stamp);
8384
}
8485
}
8586

planning/behavior_velocity_crosswalk_module/src/manager.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -190,8 +190,8 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path)
190190
clock_));
191191
generateUUID(crosswalk_lanelet_id);
192192
updateRTCStatus(
193-
getUUID(crosswalk_lanelet_id), true, std::numeric_limits<double>::lowest(),
194-
path.header.stamp);
193+
getUUID(crosswalk_lanelet_id), true, State::WAITING_FOR_EXECUTION,
194+
std::numeric_limits<double>::lowest(), path.header.stamp);
195195
};
196196

197197
const auto crosswalk_reg_elem_map = planning_utils::getRegElemMapOnPath<Crosswalk>(

planning/behavior_velocity_detection_area_module/src/manager.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,8 @@ void DetectionAreaModuleManager::launchNewModules(
6666
logger_.get_child("detection_area_module"), clock_));
6767
generateUUID(module_id);
6868
updateRTCStatus(
69-
getUUID(module_id), true, std::numeric_limits<double>::lowest(), path.header.stamp);
69+
getUUID(module_id), true, State::WAITING_FOR_EXECUTION,
70+
std::numeric_limits<double>::lowest(), path.header.stamp);
7071
}
7172
}
7273
}

planning/behavior_velocity_intersection_module/src/manager.cpp

+6-5
Original file line numberDiff line numberDiff line change
@@ -345,10 +345,10 @@ void IntersectionModuleManager::launchNewModules(
345345
const UUID uuid = getUUID(new_module->getModuleId());
346346
const auto occlusion_uuid = new_module->getOcclusionUUID();
347347
rtc_interface_.updateCooperateStatus(
348-
uuid, true, std::numeric_limits<double>::lowest(), std::numeric_limits<double>::lowest(),
349-
clock_->now());
348+
uuid, true, State::RUNNING, std::numeric_limits<double>::lowest(),
349+
std::numeric_limits<double>::lowest(), clock_->now());
350350
occlusion_rtc_interface_.updateCooperateStatus(
351-
occlusion_uuid, true, std::numeric_limits<double>::lowest(),
351+
occlusion_uuid, true, State::RUNNING, std::numeric_limits<double>::lowest(),
352352
std::numeric_limits<double>::lowest(), clock_->now());
353353
registerModule(std::move(new_module));
354354
}
@@ -404,12 +404,13 @@ void IntersectionModuleManager::sendRTC(const Time & stamp)
404404
const UUID uuid = getUUID(scene_module->getModuleId());
405405
const bool safety =
406406
scene_module->isSafe() && (!intersection_module->isOcclusionFirstStopRequired());
407-
updateRTCStatus(uuid, safety, scene_module->getDistance(), stamp);
407+
updateRTCStatus(uuid, safety, State::RUNNING, scene_module->getDistance(), stamp);
408408
const auto occlusion_uuid = intersection_module->getOcclusionUUID();
409409
const auto occlusion_distance = intersection_module->getOcclusionDistance();
410410
const auto occlusion_safety = intersection_module->getOcclusionSafety();
411411
occlusion_rtc_interface_.updateCooperateStatus(
412-
occlusion_uuid, occlusion_safety, occlusion_distance, occlusion_distance, stamp);
412+
occlusion_uuid, occlusion_safety, State::RUNNING, occlusion_distance, occlusion_distance,
413+
stamp);
413414

414415
// ==========================================================================================
415416
// module debug data

planning/behavior_velocity_no_stopping_area_module/src/manager.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,8 @@ void NoStoppingAreaModuleManager::launchNewModules(
6868
clock_));
6969
generateUUID(module_id);
7070
updateRTCStatus(
71-
getUUID(module_id), true, std::numeric_limits<double>::lowest(), path.header.stamp);
71+
getUUID(module_id), true, State::WAITING_FOR_EXECUTION,
72+
std::numeric_limits<double>::lowest(), path.header.stamp);
7273
}
7374
}
7475
}

planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
3232
#include <tier4_planning_msgs/msg/stop_reason.hpp>
3333
#include <tier4_planning_msgs/msg/stop_reason_array.hpp>
34+
#include <tier4_rtc_msgs/msg/state.hpp>
3435
#include <tier4_v2x_msgs/msg/infrastructure_command_array.hpp>
3536
#include <unique_identifier_msgs/msg/uuid.hpp>
3637

@@ -58,6 +59,7 @@ using tier4_debug_msgs::msg::Float64Stamped;
5859
using tier4_planning_msgs::msg::StopFactor;
5960
using tier4_planning_msgs::msg::StopReason;
6061
using tier4_rtc_msgs::msg::Module;
62+
using tier4_rtc_msgs::msg::State;
6163
using unique_identifier_msgs::msg::UUID;
6264

6365
struct ObjectOfInterest
@@ -235,9 +237,10 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface
235237
virtual void setActivation();
236238

237239
void updateRTCStatus(
238-
const UUID & uuid, const bool safe, const double distance, const Time & stamp)
240+
const UUID & uuid, const bool safe, const uint8_t state, const double distance,
241+
const Time & stamp)
239242
{
240-
rtc_interface_.updateCooperateStatus(uuid, safe, distance, distance, stamp);
243+
rtc_interface_.updateCooperateStatus(uuid, safe, state, distance, distance, stamp);
241244
}
242245

243246
void removeRTCStatus(const UUID & uuid) { rtc_interface_.removeCooperateStatus(uuid); }

planning/behavior_velocity_planner_common/src/scene_module_interface.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -211,7 +211,8 @@ void SceneModuleManagerInterfaceWithRTC::sendRTC(const Time & stamp)
211211
{
212212
for (const auto & scene_module : scene_modules_) {
213213
const UUID uuid = getUUID(scene_module->getModuleId());
214-
updateRTCStatus(uuid, scene_module->isSafe(), scene_module->getDistance(), stamp);
214+
const auto state = scene_module->isActivated() ? State::RUNNING : State::WAITING_FOR_EXECUTION;
215+
updateRTCStatus(uuid, scene_module->isSafe(), state, scene_module->getDistance(), stamp);
215216
}
216217
publishRTCStatus(stamp);
217218
}

planning/behavior_velocity_traffic_light_module/src/manager.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,8 @@ void TrafficLightModuleManager::launchNewModules(
132132
logger_.get_child("traffic_light_module"), clock_));
133133
generateUUID(lane_id);
134134
updateRTCStatus(
135-
getUUID(lane_id), true, std::numeric_limits<double>::lowest(), path.header.stamp);
135+
getUUID(lane_id), true, State::WAITING_FOR_EXECUTION,
136+
std::numeric_limits<double>::lowest(), path.header.stamp);
136137
}
137138
}
138139
}

planning/rtc_interface/include/rtc_interface/rtc_interface.hpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include "tier4_rtc_msgs/msg/cooperate_status.hpp"
2525
#include "tier4_rtc_msgs/msg/cooperate_status_array.hpp"
2626
#include "tier4_rtc_msgs/msg/module.hpp"
27+
#include "tier4_rtc_msgs/msg/state.hpp"
2728
#include "tier4_rtc_msgs/srv/auto_mode.hpp"
2829
#include "tier4_rtc_msgs/srv/cooperate_commands.hpp"
2930
#include <unique_identifier_msgs/msg/uuid.hpp>
@@ -41,6 +42,7 @@ using tier4_rtc_msgs::msg::CooperateResponse;
4142
using tier4_rtc_msgs::msg::CooperateStatus;
4243
using tier4_rtc_msgs::msg::CooperateStatusArray;
4344
using tier4_rtc_msgs::msg::Module;
45+
using tier4_rtc_msgs::msg::State;
4446
using tier4_rtc_msgs::srv::AutoMode;
4547
using tier4_rtc_msgs::srv::CooperateCommands;
4648
using unique_identifier_msgs::msg::UUID;
@@ -51,8 +53,8 @@ class RTCInterface
5153
RTCInterface(rclcpp::Node * node, const std::string & name, const bool enable_rtc = true);
5254
void publishCooperateStatus(const rclcpp::Time & stamp);
5355
void updateCooperateStatus(
54-
const UUID & uuid, const bool safe, const double start_distance, const double finish_distance,
55-
const rclcpp::Time & stamp);
56+
const UUID & uuid, const bool safe, const uint8_t state, const double start_distance,
57+
const double finish_distance, const rclcpp::Time & stamp);
5658
void removeCooperateStatus(const UUID & uuid);
5759
void clearCooperateStatus();
5860
bool isActivated(const UUID & uuid) const;

planning/rtc_interface/src/rtc_interface.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -201,8 +201,8 @@ void RTCInterface::onTimer()
201201
}
202202

203203
void RTCInterface::updateCooperateStatus(
204-
const UUID & uuid, const bool safe, const double start_distance, const double finish_distance,
205-
const rclcpp::Time & stamp)
204+
const UUID & uuid, const bool safe, const uint8_t state, const double start_distance,
205+
const double finish_distance, const rclcpp::Time & stamp)
206206
{
207207
std::lock_guard<std::mutex> lock(mutex_);
208208
// Find registered status which has same uuid
@@ -218,6 +218,7 @@ void RTCInterface::updateCooperateStatus(
218218
status.module = module_;
219219
status.safe = safe;
220220
status.command_status.type = Command::DEACTIVATE;
221+
status.state.type = State::WAITING_FOR_EXECUTION;
221222
status.start_distance = start_distance;
222223
status.finish_distance = finish_distance;
223224
status.auto_mode = is_auto_mode_enabled_;
@@ -228,6 +229,7 @@ void RTCInterface::updateCooperateStatus(
228229
// If the registered status is found, update status
229230
itr->stamp = stamp;
230231
itr->safe = safe;
232+
itr->state.type = state;
231233
itr->start_distance = start_distance;
232234
itr->finish_distance = finish_distance;
233235
}

0 commit comments

Comments
 (0)