@@ -30,18 +30,17 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode
30
30
explicit SynchronizedActionWithSpeed (const rclcpp::NodeOptions & option)
31
31
: cpp_mock_scenarios::CppScenarioNode(
32
32
" 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",
34
34
__FILE__, false, option)
35
35
{
36
36
start ();
37
37
}
38
38
39
39
private:
40
- bool requested = false ;
41
40
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());
43
42
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());
45
44
46
45
void onUpdate () override
47
46
{
@@ -54,7 +53,7 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode
54
53
}
55
54
56
55
// FAILURES
57
- if (api_.getCurrentTime () >= 9 .0 ) {
56
+ if (api_.getCurrentTime () >= 30 .0 ) {
58
57
stop (cpp_mock_scenarios::Result::FAILURE);
59
58
}
60
59
if (api_.checkCollision (" ego" , " npc" )) {
@@ -65,23 +64,25 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode
65
64
{
66
65
api_.spawn (
67
66
" ego" ,
68
- traffic_simulator::helper::constructCanonicalizedLaneletPose (7 , 40 , 0 , api_.getHdmapUtils ()),
67
+ traffic_simulator::helper::constructCanonicalizedLaneletPose (
68
+ 34976 , 20 , 0 , api_.getHdmapUtils ()),
69
69
getVehicleParameters ());
70
70
api_.setLinearVelocity (" ego" , 3 );
71
71
api_.requestSpeedChange (" ego" , 3 , true );
72
72
73
73
std::vector<geometry_msgs::msg::Pose> goal_poses;
74
74
goal_poses.emplace_back (traffic_simulator::helper::constructCanonicalizedLaneletPose (
75
- 154 , 20 , 0 , api_.getHdmapUtils ()));
75
+ 34579 , 20 , 0 , api_.getHdmapUtils ()));
76
76
api_.requestAssignRoute (" ego" , goal_poses);
77
77
78
78
api_.spawn (
79
79
" npc" ,
80
- traffic_simulator::helper::constructCanonicalizedLaneletPose (14 , 15 , 0 , api_.getHdmapUtils ()),
80
+ traffic_simulator::helper::constructCanonicalizedLaneletPose (
81
+ 34576 , 0 , 0 , api_.getHdmapUtils ()),
81
82
getVehicleParameters ());
82
83
std::vector<geometry_msgs::msg::Pose> npc_goal_poses;
83
84
npc_goal_poses.emplace_back (traffic_simulator::helper::constructCanonicalizedLaneletPose (
84
- 140 , 20 , 0 , api_.getHdmapUtils ()));
85
+ 34564 , 20 , 0 , api_.getHdmapUtils ()));
85
86
api_.requestAssignRoute (" npc" , npc_goal_poses);
86
87
api_.setLinearVelocity (" npc" , 6 );
87
88
}
0 commit comments