Skip to content

Commit

Permalink
port pedestrian_follow_lane scenario
Browse files Browse the repository at this point in the history
Signed-off-by: Masaya Kataoka <[email protected]>
  • Loading branch information
hakuturu583 committed Feb 10, 2025
1 parent 32df61a commit 3cb555c
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,15 +38,15 @@ target_link_libraries(reverse_walk_at_road
zmq
)

# ament_auto_add_executable(pedestrian_follow_lane
# pedestrian_follow_lane.cpp
# )
# target_link_libraries(pedestrian_follow_lane
# ${PROTOBUF_LIBRARY}
# pthread
# sodium
# zmq
# )
ament_auto_add_executable(pedestrian_follow_lane
pedestrian_follow_lane.cpp
)
target_link_libraries(pedestrian_follow_lane
${PROTOBUF_LIBRARY}
pthread
sodium
zmq
)

# ament_auto_add_executable(stop_line_running
# stop_line_running.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,11 @@ class PedestrianFollowLane : public cpp_mock_scenarios::CppScenarioNode
void onUpdate() override
{
const auto t = api_.getCurrentTime();
if (
static_cast<traffic_simulator::LaneletPose>(api_.getEntityStatus("ego").getLaneletPose())
.lanelet_id == checkpoint_ids_.at(step_)) {
step_++;
const auto & ego = api_.getEntity("ego");
if (const auto & lanelet_pose = ego.getCanonicalizedLaneletPose()) {
if (lanelet_pose.value().getLaneletPose().lanelet_id == checkpoint_ids_.at(step_)) {
step_++;
}
}
if (step_ == static_cast<int>(checkpoint_ids_.size())) {
stop(cpp_mock_scenarios::Result::SUCCESS);
Expand All @@ -63,17 +64,17 @@ class PedestrianFollowLane : public cpp_mock_scenarios::CppScenarioNode
api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34426, 10.0, 0),
getPedestrianParameters(), traffic_simulator::PedestrianBehavior::contextGamma());
api_.requestSpeedChange(
"ego", 4.0, traffic_simulator::speed_change::Transition::LINEAR,
auto & ego = api_.getEntity("ego");
ego.requestSpeedChange(
4.0, traffic_simulator::speed_change::Transition::LINEAR,
traffic_simulator::speed_change::Constraint(
traffic_simulator::speed_change::Constraint::Type::LONGITUDINAL_ACCELERATION, 1.0),
true);
api_.requestAssignRoute(
"ego", std::vector<traffic_simulator::CanonicalizedLaneletPose>{
traffic_simulator::helper::constructCanonicalizedLaneletPose(35016, 0.0, 0),
traffic_simulator::helper::constructCanonicalizedLaneletPose(35026, 0.0, 0),
traffic_simulator::helper::constructCanonicalizedLaneletPose(35036, 0.0, 0),
traffic_simulator::helper::constructCanonicalizedLaneletPose(34981, 1.0, 0)});
ego.requestAssignRoute(std::vector<traffic_simulator::CanonicalizedLaneletPose>{
traffic_simulator::helper::constructCanonicalizedLaneletPose(35016, 0.0, 0),
traffic_simulator::helper::constructCanonicalizedLaneletPose(35026, 0.0, 0),
traffic_simulator::helper::constructCanonicalizedLaneletPose(35036, 0.0, 0),
traffic_simulator::helper::constructCanonicalizedLaneletPose(34981, 1.0, 0)});
}
};

Expand Down

0 comments on commit 3cb555c

Please sign in to comment.