Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add fix going to depart and arrive announce #108

Merged
merged 3 commits into from
Aug 20, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 1 addition & 4 deletions src/signage/src/signage/announce_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
from PyQt5.QtMultimedia import QSound
from rclpy.duration import Duration
from ament_index_python.packages import get_package_share_directory
from pulsectl import Pulse

Check warning on line 10 in src/signage/src/signage/announce_controller.py

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (pulsectl)

from std_msgs.msg import Float32
from tier4_hmi_msgs.srv import SetVolume
Expand Down Expand Up @@ -50,7 +50,7 @@
self._sink = self._pulse.get_sink_by_name(
self._pulse.server_info().default_sink_name
)
self._pulse.volume_set_all_chans(self._sink, float(f.readline()))

Check warning on line 53 in src/signage/src/signage/announce_controller.py

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (chans)

self._get_volume_pub = self._node.create_publisher(Float32, "~/get/volume", 1)
self._node.create_timer(1.0, self.publish_volume_callback)
Expand Down Expand Up @@ -129,10 +129,7 @@
self.send_announce(message)

def announce_going_to_depart_and_arrive(self, message):
if self._prev_depart_and_arrive_type != message:
# To stop repeat announcement
self.send_announce(message)
self._prev_depart_and_arrive_type = message
self.send_announce(message)

def publish_volume_callback(self):
self._sink = self._pulse.get_sink_by_name(self._pulse.server_info().default_sink_name)
Expand All @@ -141,7 +138,7 @@
def set_volume(self, request, response):
try:
self._sink = self._pulse.get_sink_by_name(self._pulse.server_info().default_sink_name)
self._pulse.volume_set_all_chans(self._sink, request.volume)

Check warning on line 141 in src/signage/src/signage/announce_controller.py

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (chans)
with open(CURRENT_VOLUME_PATH, "w") as f:
f.write(f"{self._sink.volume.value_flat}\n")
response.status.code = ResponseStatus.SUCCESS
Expand Down
29 changes: 24 additions & 5 deletions src/signage/src/signage/route_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
from datetime import datetime
import signage.signage_utils as utils
from tier4_external_api_msgs.msg import DoorStatus
from autoware_adapi_v1_msgs.msg import (

Check warning on line 11 in src/signage/src/signage/route_handler.py

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (adapi)
RouteState,
MrmState,
OperationModeState,
Expand Down Expand Up @@ -61,6 +61,8 @@
self._announce_engage = False
self._in_slow_stop_state = False
self._in_slowing_state = False
self._announced_depart = False
self._announced_arrive = False
self._trigger_external_signage = False

self.process_station_list_from_fms()
Expand Down Expand Up @@ -125,8 +127,8 @@

if (
self._autoware.information.localization_init_state
== LocalizationInitializationState.UNINITIALIZED or
self._autoware.information.autoware_control == False
== LocalizationInitializationState.UNINITIALIZED
or self._autoware.information.autoware_control == False
):
self._prev_motion_state = 0
return
Expand Down Expand Up @@ -276,13 +278,19 @@
# Check whether the vehicle is move in autonomous
self._is_driving = True
self._is_stopping = False
self._announced_depart = False

if (
not self._trigger_external_signage
and self._autoware.information.autoware_control
):
self._service_interface.trigger_external_signage(True)
self._trigger_external_signage = True
if not self._announce_engage and self._parameter.signage_stand_alone and self._autoware.information.autoware_control:
if (
not self._announce_engage
and self._parameter.signage_stand_alone
and self._autoware.information.autoware_control
):
self._announce_interface.send_announce("engage")
self._service_interface.trigger_external_signage(True)
self._trigger_external_signage = True
Expand All @@ -293,6 +301,7 @@
self._is_stopping = True
self._skip_announce = False
self._announce_engage = False
self._announced_arrive = False

if (
self._autoware.information.operation_mode != OperationModeState.AUTONOMOUS
Expand Down Expand Up @@ -323,6 +332,7 @@
if self._autoware.information.goal_distance < self._parameter.goal_distance:
self._is_stopping = True
self._is_driving = False
self._announced_depart = False

if self._reach_final:
self._previous_driving_status = False
Expand Down Expand Up @@ -364,13 +374,21 @@
else:
# the departure time is close (within 1 min), announce going to depart
self._display_phrase = utils.handle_phrase("departing")
self._announce_interface.announce_going_to_depart_and_arrive("going_to_depart")
if not self._announced_depart:
self._announce_interface.announce_going_to_depart_and_arrive(
"going_to_depart"
)
self._announced_depart = True
elif self._is_driving:
# handle text and announce while bus is running
if self._autoware.information.goal_distance < 100:
# display text and announce if the goal is within 100m
self._display_phrase = utils.handle_phrase("arriving")
self._announce_interface.announce_going_to_depart_and_arrive("going_to_arrive")
if not self._announced_arrive:
self._announce_interface.announce_going_to_depart_and_arrive(
"going_to_arrive"
)
self._announced_arrive = True
else:
self._display_phrase = ""
else:
Expand Down Expand Up @@ -413,6 +431,7 @@
view_mode = "stopping"
else:
view_mode = "out_of_service"
self._announced_depart = False

self._viewController.view_mode = view_mode
except Exception as e:
Expand Down
Loading