Skip to content

Commit da2aded

Browse files
authored
feat: merge initialpose auto direct (#454)
1 parent 26c02e3 commit da2aded

File tree

4 files changed

+45
-137
lines changed

4 files changed

+45
-137
lines changed

.vscode/settings.json

-2
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,6 @@
3535
"${env:HOME}/ros_ws/awf/install/driving_log_replayer_msgs/local/lib/python3.10/dist-packages",
3636
"${env:HOME}/ros_ws/awf/install/tier4_debug_msgs/local/lib/python3.10/dist-packages",
3737
"${env:HOME}/ros_ws/awf/install/driving_log_replayer_analyzer/local/lib/python3.10/dist-packages",
38-
"${env:HOME}/ros_ws/awf/install/autoware_adapi_v1_msgs/local/lib/python3.10/dist-packages",
3938
"${env:HOME}/ros_ws/awf/install/tier4_localization_msgs/local/lib/python3.10/dist-packages",
4039
"${env:HOME}/ros_ws/awf/install/tier4_api_msgs/local/lib/python3.10/dist-packages",
4140
"${env:HOME}/ros_ws/awf/install/tier4_perception_msgs/local/lib/python3.10/dist-packages",
@@ -53,7 +52,6 @@
5352
"${env:HOME}/ros_ws/awf/install/driving_log_replayer_msgs/local/lib/python3.10/dist-packages",
5453
"${env:HOME}/ros_ws/awf/install/tier4_debug_msgs/local/lib/python3.10/dist-packages",
5554
"${env:HOME}/ros_ws/awf/install/driving_log_replayer_analyzer/local/lib/python3.10/dist-packages",
56-
"${env:HOME}/ros_ws/awf/install/autoware_adapi_v1_msgs/local/lib/python3.10/dist-packages",
5755
"${env:HOME}/ros_ws/awf/install/tier4_localization_msgs/local/lib/python3.10/dist-packages",
5856
"${env:HOME}/ros_ws/awf/install/tier4_api_msgs/local/lib/python3.10/dist-packages",
5957
"${env:HOME}/ros_ws/awf/install/tier4_perception_msgs/local/lib/python3.10/dist-packages",

dependency.repos

+2-2
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,8 @@ repositories:
1919
# universe
2020
universe/external/tier4_autoware_msgs:
2121
type: git
22-
url: https://github.com/tier4/tier4_autoware_msgs.git
23-
version: tier4/universe
22+
url: https://github.com/YamatoAndo/tier4_autoware_msgs.git # Undo after PRs are merged.
23+
version: feat/tier4_localization_msgs/add_initilizelocalization_srv # Undo after PRs are merged.
2424
# simulator
2525
simulator/perception_eval:
2626
type: git

driving_log_replayer/driving_log_replayer/evaluator.py

+42-132
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818
from typing import Any
1919
from typing import TYPE_CHECKING
2020

21-
from autoware_adapi_v1_msgs.srv import InitializeLocalization
2221
from autoware_auto_perception_msgs.msg import ObjectClassification
2322
from autoware_auto_perception_msgs.msg import TrafficLight
2423
from builtin_interfaces.msg import Time as Stamp
@@ -45,7 +44,7 @@
4544
from tf2_ros import TransformException
4645
from tf2_ros import TransformListener
4746
from tf_transformations import euler_from_quaternion
48-
from tier4_localization_msgs.srv import InitializeLocalization as T4InitializeLocalization
47+
from tier4_localization_msgs.srv import InitializeLocalization
4948
from tier4_localization_msgs.srv import PoseWithCovarianceStamped as PoseWithCovarianceStampedSrv
5049
import yaml
5150

@@ -55,8 +54,7 @@
5554
from driving_log_replayer.scenario import load_scenario
5655

5756
if TYPE_CHECKING:
58-
from autoware_adapi_v1_msgs.msg import ResponseStatus
59-
from autoware_common_msgs.msg import ResponseStatus as CommonResponseStatus
57+
from autoware_common_msgs.msg import ResponseStatus
6058

6159

6260
class DLREvaluator(Node):
@@ -113,15 +111,9 @@ def __init__(self, name: str, scenario_class: Callable, result_class: Callable)
113111
# initial pose estimation
114112
self._initial_pose_running: bool = False
115113
self._initial_pose_success: bool = False
116-
self._initial_pose = self.set_initial_pose()
114+
self._initial_pose, self._initial_pose_method = self.set_initial_pose()
117115
self.start_initialpose_service()
118116

119-
# initial pose estimation
120-
self._direct_initial_pose_running: bool = False
121-
self._direct_initial_pose_success: bool = False
122-
self._direct_initial_pose = self.set_direct_initial_pose()
123-
self.start_direct_initialpose_service()
124-
125117
self._current_time = Time().to_msg()
126118
self._prev_time = Time().to_msg()
127119
self._clock_stop_counter = 0
@@ -169,8 +161,6 @@ def timer_cb(
169161
register_loop_func()
170162
if self._initial_pose is not None:
171163
self.call_initialpose_service()
172-
if self._direct_initial_pose is not None:
173-
self.call_direct_initialpose_service()
174164
self._clock_stop_counter = (
175165
self._clock_stop_counter + 1 if self._current_time == self._prev_time else 0
176166
)
@@ -186,29 +176,20 @@ def start_initialpose_service(self) -> None:
186176
return
187177
self._initial_pose_client = self.create_client(
188178
InitializeLocalization,
189-
"/api/localization/initialize",
190-
)
191-
self._map_fit_client = self.create_client(
192-
PoseWithCovarianceStampedSrv,
193-
"/map/map_height_fitter/service",
179+
"/localization/initialize",
194180
)
195-
196181
while not self._initial_pose_client.wait_for_service(timeout_sec=1.0):
197182
self.get_logger().warning("initial pose service not available, waiting again...")
198-
while not self._map_fit_client.wait_for_service(timeout_sec=1.0):
199-
self.get_logger().warning("map height fitter service not available, waiting again...")
200183

201-
def start_direct_initialpose_service(self) -> None:
202-
self.get_logger().info("start direct initialpose service")
203-
if self._direct_initial_pose is None:
204-
return
205-
self._direct_initial_pose_client = self.create_client(
206-
T4InitializeLocalization,
207-
"/localization/initialize",
208-
)
209-
210-
while not self._direct_initial_pose_client.wait_for_service(timeout_sec=1.0):
211-
self.get_logger().warning("direct initial pose service not available, waiting again...")
184+
if self._initial_pose_method == InitializeLocalization.Request.AUTO:
185+
self._map_fit_client = self.create_client(
186+
PoseWithCovarianceStampedSrv,
187+
"/map/map_height_fitter/service",
188+
)
189+
while not self._map_fit_client.wait_for_service(timeout_sec=1.0):
190+
self.get_logger().warning(
191+
"map height fitter service not available, waiting again...",
192+
)
212193

213194
def call_initialpose_service(self) -> None:
214195
if self._initial_pose is None or self._initial_pose_success or self._initial_pose_running:
@@ -218,17 +199,29 @@ def call_initialpose_service(self) -> None:
218199
)
219200
self._initial_pose_running = True
220201
self._initial_pose.header.stamp = self._current_time
221-
future_map_fit = self._map_fit_client.call_async(
222-
PoseWithCovarianceStampedSrv.Request(pose_with_covariance=self._initial_pose),
223-
)
224-
future_map_fit.add_done_callback(self.map_fit_cb)
202+
if self._initial_pose_method == InitializeLocalization.Request.AUTO:
203+
future_map_fit = self._map_fit_client.call_async(
204+
PoseWithCovarianceStampedSrv.Request(pose_with_covariance=self._initial_pose),
205+
)
206+
future_map_fit.add_done_callback(self.map_fit_cb)
207+
else:
208+
future_direct_init_pose = self._initial_pose_client.call_async(
209+
InitializeLocalization.Request(
210+
method=self._initial_pose_method,
211+
pose_with_covariance=[self._initial_pose],
212+
),
213+
)
214+
future_direct_init_pose.add_done_callback(self.initial_pose_cb)
225215

226216
def map_fit_cb(self, future: Future) -> None:
227217
result = future.result()
228218
if result is not None:
229219
if result.success:
230220
future_init_pose = self._initial_pose_client.call_async(
231-
InitializeLocalization.Request(pose=[result.pose_with_covariance]),
221+
InitializeLocalization.Request(
222+
method=self._initial_pose_method,
223+
pose_with_covariance=[result.pose_with_covariance],
224+
),
232225
)
233226
future_init_pose.add_done_callback(self.initial_pose_cb)
234227
else:
@@ -240,26 +233,6 @@ def map_fit_cb(self, future: Future) -> None:
240233
self._initial_pose_running = False
241234
self.get_logger().error(f"Exception for service: {future.exception()}")
242235

243-
def call_direct_initialpose_service(self) -> None:
244-
if (
245-
self._direct_initial_pose is None
246-
or self._direct_initial_pose_success
247-
or self._direct_initial_pose_running
248-
):
249-
return
250-
self.get_logger().info(
251-
f"call direct initial_pose time: {self._current_time.sec}.{self._current_time.nanosec}",
252-
)
253-
self._direct_initial_pose_running = True
254-
self._direct_initial_pose.header.stamp = self._current_time
255-
future_direct_init_pose = self._direct_initial_pose_client.call_async(
256-
T4InitializeLocalization.Request(
257-
method=T4InitializeLocalization.Request.DIRECT,
258-
pose_with_covariance=[self._direct_initial_pose],
259-
),
260-
)
261-
future_direct_init_pose.add_done_callback(self.direct_initial_pose_cb)
262-
263236
def initial_pose_cb(self, future: Future) -> None:
264237
result = future.result()
265238
if result is not None:
@@ -273,19 +246,6 @@ def initial_pose_cb(self, future: Future) -> None:
273246
# free self._initial_pose_running
274247
self._initial_pose_running = False
275248

276-
def direct_initial_pose_cb(self, future: Future) -> None:
277-
result = future.result()
278-
if result is not None:
279-
res_status: CommonResponseStatus = result.status
280-
self._direct_initial_pose_success = res_status.success
281-
self.get_logger().info(
282-
f"direct_initial_pose_success: {self._initial_pose_success}",
283-
) # debug msg
284-
else:
285-
self.get_logger().error(f"Exception for service: {future.exception()}")
286-
# free self._initial_pose_running
287-
self._direct_initial_pose_running = False
288-
289249
def lookup_transform(
290250
self,
291251
stamp: Stamp,
@@ -324,67 +284,17 @@ def transform_stamped_with_euler_angle(cls, transform_stamped: TransformStamped)
324284
}
325285
return tf_euler
326286

327-
def set_initial_pose(self) -> PoseWithCovarianceStamped | None:
328-
if not hasattr(self._scenario.Evaluation, "InitialPose"):
329-
return None
330-
if self._scenario.Evaluation.InitialPose is None:
331-
return None
332-
initial_pose: InitialPose = self._scenario.Evaluation.InitialPose
333-
covariance = np.array(
334-
[
335-
0.25,
336-
0.0,
337-
0.0,
338-
0.0,
339-
0.0,
340-
0.0,
341-
0.0,
342-
0.25,
343-
0.0,
344-
0.0,
345-
0.0,
346-
0.0,
347-
0.0,
348-
0.0,
349-
0.0,
350-
0.0,
351-
0.0,
352-
0.0,
353-
0.0,
354-
0.0,
355-
0.0,
356-
0.0,
357-
0.0,
358-
0.0,
359-
0.0,
360-
0.0,
361-
0.0,
362-
0.0,
363-
0.0,
364-
0.0,
365-
0.0,
366-
0.0,
367-
0.0,
368-
0.0,
369-
0.0,
370-
0.06853892326654787,
371-
],
372-
)
373-
pose = PoseWithCovariance(
374-
pose=Pose(
375-
position=Point(**initial_pose.position.model_dump()),
376-
orientation=Quaternion(**initial_pose.orientation.model_dump()),
377-
),
378-
covariance=covariance,
379-
)
380-
return PoseWithCovarianceStamped(header=Header(frame_id="map"), pose=pose)
381-
382-
def set_direct_initial_pose(self) -> PoseWithCovarianceStamped | None:
383-
if not hasattr(self._scenario.Evaluation, "DirectInitialPose"):
384-
return None
385-
if self._scenario.Evaluation.DirectInitialPose is None:
386-
return None
387-
initial_pose: InitialPose = self._scenario.Evaluation.DirectInitialPose
287+
def set_initial_pose(self) -> tuple[PoseWithCovarianceStamped | None, int | None]:
288+
auto_pose = getattr(self._scenario.Evaluation, "InitialPose", None)
289+
direct_pose = getattr(self._scenario.Evaluation, "DirectInitialPose", None)
290+
if auto_pose is None and direct_pose is None:
291+
return None, None
292+
if auto_pose is not None:
293+
initial_pose: InitialPose = auto_pose
294+
pose_method: int = InitializeLocalization.Request.AUTO
295+
if direct_pose is not None:
296+
initial_pose: InitialPose = direct_pose
297+
pose_method: int = InitializeLocalization.Request.DIRECT
388298
covariance = np.array(
389299
[
390300
0.25,
@@ -432,7 +342,7 @@ def set_direct_initial_pose(self) -> PoseWithCovarianceStamped | None:
432342
),
433343
covariance=covariance,
434344
)
435-
return PoseWithCovarianceStamped(header=Header(frame_id="map"), pose=pose)
345+
return PoseWithCovarianceStamped(header=Header(frame_id="map"), pose=pose), pose_method
436346

437347
@classmethod
438348
def get_perception_label_str(cls, classification: ObjectClassification) -> str:

driving_log_replayer/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@
1616

1717
<build_depend>autoware_cmake</build_depend>
1818

19-
<depend>autoware_adapi_v1_msgs</depend>
2019
<depend>autoware_auto_mapping_msgs</depend>
2120
<depend>autoware_auto_perception_msgs</depend>
21+
<depend>autoware_common_msgs</depend>
2222
<depend>diagnostic_msgs</depend>
2323
<depend>driving_log_replayer_msgs</depend>
2424
<depend>example_interfaces</depend>

0 commit comments

Comments
 (0)