Skip to content

Commit c66f3e9

Browse files
authored
Merge pull request tier4#1319 from tier4/test/synchronized-action-kashiwanoha-map
fix: Change map of synchronized action's test
2 parents 7b53541 + fd70911 commit c66f3e9

File tree

2 files changed

+20
-18
lines changed

2 files changed

+20
-18
lines changed

mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action.cpp

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -30,18 +30,17 @@ class SynchronizedAction : public cpp_mock_scenarios::CppScenarioNode
3030
explicit SynchronizedAction(const rclcpp::NodeOptions & option)
3131
: cpp_mock_scenarios::CppScenarioNode(
3232
"synchronized_action",
33-
ament_index_cpp::get_package_share_directory("simple_cross_map") + "/map", "lanelet2_map.osm",
33+
ament_index_cpp::get_package_share_directory("kashiwanoha_map") + "/map", "lanelet2_map.osm",
3434
__FILE__, false, option)
3535
{
3636
start();
3737
}
3838

3939
private:
40-
bool requested = false;
4140
const traffic_simulator::CanonicalizedLaneletPose ego_target =
42-
traffic_simulator::helper::constructCanonicalizedLaneletPose(147, 0, 0, api_.getHdmapUtils());
41+
traffic_simulator::helper::constructCanonicalizedLaneletPose(34585, 0, 0, api_.getHdmapUtils());
4342
const traffic_simulator::CanonicalizedLaneletPose npc_target =
44-
traffic_simulator::helper::constructCanonicalizedLaneletPose(133, 0, 0, api_.getHdmapUtils());
43+
traffic_simulator::helper::constructCanonicalizedLaneletPose(34570, 0, 0, api_.getHdmapUtils());
4544

4645
void onUpdate() override
4746
{
@@ -54,7 +53,7 @@ class SynchronizedAction : public cpp_mock_scenarios::CppScenarioNode
5453
}
5554

5655
// FAILURES
57-
if (api_.getCurrentTime() >= 9.0) {
56+
if (api_.getCurrentTime() >= 30.0) {
5857
stop(cpp_mock_scenarios::Result::FAILURE);
5958
}
6059
if (api_.checkCollision("ego", "npc")) {
@@ -65,23 +64,25 @@ class SynchronizedAction : public cpp_mock_scenarios::CppScenarioNode
6564
{
6665
api_.spawn(
6766
"ego",
68-
traffic_simulator::helper::constructCanonicalizedLaneletPose(7, 40, 0, api_.getHdmapUtils()),
67+
traffic_simulator::helper::constructCanonicalizedLaneletPose(
68+
34976, 20, 0, api_.getHdmapUtils()),
6969
getVehicleParameters());
7070
api_.setLinearVelocity("ego", 3);
7171
api_.requestSpeedChange("ego", 3, true);
7272

7373
std::vector<geometry_msgs::msg::Pose> goal_poses;
7474
goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose(
75-
154, 20, 0, api_.getHdmapUtils()));
75+
34579, 20, 0, api_.getHdmapUtils()));
7676
api_.requestAssignRoute("ego", goal_poses);
7777

7878
api_.spawn(
7979
"npc",
80-
traffic_simulator::helper::constructCanonicalizedLaneletPose(14, 15, 0, api_.getHdmapUtils()),
80+
traffic_simulator::helper::constructCanonicalizedLaneletPose(
81+
34576, 0, 0, api_.getHdmapUtils()),
8182
getVehicleParameters());
8283
std::vector<geometry_msgs::msg::Pose> npc_goal_poses;
8384
npc_goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose(
84-
140, 20, 0, api_.getHdmapUtils()));
85+
34564, 20, 0, api_.getHdmapUtils()));
8586
api_.requestAssignRoute("npc", npc_goal_poses);
8687
api_.setLinearVelocity("npc", 6);
8788
}

mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action_with_speed.cpp

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -30,18 +30,17 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode
3030
explicit SynchronizedActionWithSpeed(const rclcpp::NodeOptions & option)
3131
: cpp_mock_scenarios::CppScenarioNode(
3232
"synchronized_action_with_speed",
33-
ament_index_cpp::get_package_share_directory("simple_cross_map") + "/map", "lanelet2_map.osm",
33+
ament_index_cpp::get_package_share_directory("kashiwanoha_map") + "/map", "lanelet2_map.osm",
3434
__FILE__, false, option)
3535
{
3636
start();
3737
}
3838

3939
private:
40-
bool requested = false;
4140
const traffic_simulator::CanonicalizedLaneletPose ego_target =
42-
traffic_simulator::helper::constructCanonicalizedLaneletPose(147, 0, 0, api_.getHdmapUtils());
41+
traffic_simulator::helper::constructCanonicalizedLaneletPose(34585, 0, 0, api_.getHdmapUtils());
4342
const traffic_simulator::CanonicalizedLaneletPose npc_target =
44-
traffic_simulator::helper::constructCanonicalizedLaneletPose(133, 0, 0, api_.getHdmapUtils());
43+
traffic_simulator::helper::constructCanonicalizedLaneletPose(34570, 0, 0, api_.getHdmapUtils());
4544

4645
void onUpdate() override
4746
{
@@ -54,7 +53,7 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode
5453
}
5554

5655
// FAILURES
57-
if (api_.getCurrentTime() >= 9.0) {
56+
if (api_.getCurrentTime() >= 30.0) {
5857
stop(cpp_mock_scenarios::Result::FAILURE);
5958
}
6059
if (api_.checkCollision("ego", "npc")) {
@@ -65,23 +64,25 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode
6564
{
6665
api_.spawn(
6766
"ego",
68-
traffic_simulator::helper::constructCanonicalizedLaneletPose(7, 40, 0, api_.getHdmapUtils()),
67+
traffic_simulator::helper::constructCanonicalizedLaneletPose(
68+
34976, 20, 0, api_.getHdmapUtils()),
6969
getVehicleParameters());
7070
api_.setLinearVelocity("ego", 3);
7171
api_.requestSpeedChange("ego", 3, true);
7272

7373
std::vector<geometry_msgs::msg::Pose> goal_poses;
7474
goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose(
75-
154, 20, 0, api_.getHdmapUtils()));
75+
34579, 20, 0, api_.getHdmapUtils()));
7676
api_.requestAssignRoute("ego", goal_poses);
7777

7878
api_.spawn(
7979
"npc",
80-
traffic_simulator::helper::constructCanonicalizedLaneletPose(14, 15, 0, api_.getHdmapUtils()),
80+
traffic_simulator::helper::constructCanonicalizedLaneletPose(
81+
34576, 0, 0, api_.getHdmapUtils()),
8182
getVehicleParameters());
8283
std::vector<geometry_msgs::msg::Pose> npc_goal_poses;
8384
npc_goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose(
84-
140, 20, 0, api_.getHdmapUtils()));
85+
34564, 20, 0, api_.getHdmapUtils()));
8586
api_.requestAssignRoute("npc", npc_goal_poses);
8687
api_.setLinearVelocity("npc", 6);
8788
}

0 commit comments

Comments
 (0)