Skip to content

Commit

Permalink
Adjust mock scenarios to new API
Browse files Browse the repository at this point in the history
Signed-off-by: Mateusz Palczuk <mateusz.palczuk@robotec.ai>
  • Loading branch information
TauTheLepton committed Jul 31, 2024
1 parent 1869aa1 commit 8940b3e
Show file tree
Hide file tree
Showing 4 changed files with 34 additions and 18 deletions.
2 changes: 1 addition & 1 deletion mock/cpp_mock_scenarios/src/spawn/spawn_in_map_frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ class SpawnInMapFrameScenario : public cpp_mock_scenarios::CppScenarioNode
const auto map_pose = traffic_simulator::pose::toMapPose(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
120545, 0.0, 0.0, api_.getHdmapUtils()));
if (api_.reachPosition("ego", map_pose, 0.1)) {
if (api_.getEntity("ego")->reachPosition(map_pose, 0.1)) {
stop(cpp_mock_scenarios::Result::SUCCESS);
} else {
stop(cpp_mock_scenarios::Result::FAILURE);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,14 @@ class SynchronizedAction : public cpp_mock_scenarios::CppScenarioNode

void onUpdate() override
{
auto npc = api_.getEntity("npc");
auto ego = api_.getEntity("ego");

// SUCCESS
if (
api_.requestSynchronize("npc", "ego", ego_target, npc_target, 0, 0.5) &&
api_.reachPosition("ego", ego_target, 1.0) && api_.reachPosition("npc", npc_target, 1.0) &&
api_.getCurrentTwist("npc").linear.x < 0.5) {
npc->requestSynchronize("ego", ego_target, npc_target, 0, 0.5) &&
ego->reachPosition(ego_target, 1.0) && npc->reachPosition(npc_target, 1.0) &&
npc->getCurrentTwist().linear.x < 0.5) {
stop(cpp_mock_scenarios::Result::SUCCESS);
}

Expand All @@ -67,24 +70,29 @@ class SynchronizedAction : public cpp_mock_scenarios::CppScenarioNode
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34976, 20, 0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("ego", 3);
api_.requestSpeedChange("ego", 3, true);

auto ego = api_.getEntity("ego");
ego->setLinearVelocity(3);
ego->requestSpeedChange(3, true);

std::vector<geometry_msgs::msg::Pose> goal_poses;
goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose(
34579, 20, 0, api_.getHdmapUtils()));
api_.requestAssignRoute("ego", goal_poses);
ego->requestAssignRoute(goal_poses);

api_.spawn(
"npc",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34576, 0, 0, api_.getHdmapUtils()),
getVehicleParameters());

auto npc = api_.getEntity("npc");

std::vector<geometry_msgs::msg::Pose> npc_goal_poses;
npc_goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose(
34564, 20, 0, api_.getHdmapUtils()));
api_.requestAssignRoute("npc", npc_goal_poses);
api_.setLinearVelocity("npc", 6);
npc->requestAssignRoute(npc_goal_poses);
npc->setLinearVelocity(6);
}

auto getSampleLaneletPose(const traffic_simulator::LaneletPose & lanelet_pose)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,14 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode

void onUpdate() override
{
auto npc = api_.getEntity("npc");
auto ego = api_.getEntity("ego");

// SUCCESS
if (
api_.requestSynchronize("npc", "ego", ego_target, npc_target, 2, 0.5) &&
api_.reachPosition("ego", ego_target, 1.0) && api_.reachPosition("npc", npc_target, 1.0) &&
api_.getCurrentTwist("npc").linear.x < 2.5) {
npc->requestSynchronize("ego", ego_target, npc_target, 2, 0.5) &&
ego->reachPosition(ego_target, 1.0) && npc->reachPosition(npc_target, 1.0) &&
npc->getCurrentTwist().linear.x < 2.5) {
stop(cpp_mock_scenarios::Result::SUCCESS);
}

Expand All @@ -67,24 +70,29 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34976, 20, 0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("ego", 3);
api_.requestSpeedChange("ego", 3, true);

auto ego = api_.getEntity("ego");
ego->setLinearVelocity(3);
ego->requestSpeedChange(3, true);

std::vector<geometry_msgs::msg::Pose> goal_poses;
goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose(
34579, 20, 0, api_.getHdmapUtils()));
api_.requestAssignRoute("ego", goal_poses);
ego->requestAssignRoute(goal_poses);

api_.spawn(
"npc",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34576, 0, 0, api_.getHdmapUtils()),
getVehicleParameters());

auto npc = api_.getEntity("npc");

std::vector<geometry_msgs::msg::Pose> npc_goal_poses;
npc_goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose(
34564, 20, 0, api_.getHdmapUtils()));
api_.requestAssignRoute("npc", npc_goal_poses);
api_.setLinearVelocity("npc", 6);
npc->requestAssignRoute(npc_goal_poses);
npc->setLinearVelocity(6);
}

auto getSampleLaneletPose(const traffic_simulator::LaneletPose & lanelet_pose)
Expand Down
2 changes: 1 addition & 1 deletion mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ class TrafficSimulationDemoScenario : public cpp_mock_scenarios::CppScenarioNode
"obstacle", traffic_simulator::helper::constructPose(10, 5, 0, 0, 0, -1.57),
getMiscObjectParameters());
api_.getEntity("obstacle")
->setCanonicalizedStatus(
->setStatus(
ego_entity->getMapPose(), traffic_simulator::helper::constructPose(10, 5, 0, 0, 0, -1.57),
traffic_simulator::helper::constructActionStatus());

Expand Down

0 comments on commit 8940b3e

Please sign in to comment.