Skip to content

Commit

Permalink
fix conflict
Browse files Browse the repository at this point in the history
  • Loading branch information
yabuta committed Jan 29, 2024
2 parents b06dc27 + fb7476e commit b2e4398
Show file tree
Hide file tree
Showing 7 changed files with 110 additions and 3 deletions.
2 changes: 2 additions & 0 deletions src/signage/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,13 @@
<exec_depend>signage_version</exec_depend>

<depend>autoware_auto_system_msgs</depend>
<depend>python-pulsectl-pip</depend>

Check warning on line 14 in src/signage/package.xml

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (pulsectl)
<depend>rclpy</depend>
<depend>tier4_api_msgs</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_external_api_msgs</depend>
<depend>tier4_hmi_msgs</depend>
<depend>diagnostic_updater</depend>

<export>
<build_type>ament_python</build_type>
Expand Down
37 changes: 37 additions & 0 deletions src/signage/src/signage/announce_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,17 @@
# -*- coding: utf-8 -*-
# This Python file uses the following encoding: utf-8

import os

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
from tier4_external_api_msgs.msg import ResponseStatus


# The higher the value, the higher the priority
PRIORITY_DICT = {
Expand All @@ -20,6 +28,8 @@
"going_to_arrive": 1,
}

CURRENT_VOLUME_PATH = "/opt/autoware/volume.txt"


class AnnounceControllerProperty:
def __init__(self, node, autoware_interface, parameter_interface):
Expand All @@ -35,6 +45,18 @@ def __init__(self, node, autoware_interface, parameter_interface):
self._package_path = get_package_share_directory("signage") + "/resource/sound/"
self._check_playing_timer = self._node.create_timer(1, self.check_playing_callback)

self._pulse = Pulse()
if os.path.isfile(CURRENT_VOLUME_PATH):
with open(CURRENT_VOLUME_PATH, "r") as f:
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 54 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)
self._node.create_service(SetVolume, "~/set/volume", self.set_volume)

def process_pending_announce(self):
try:
for play_sound in self._pending_announce_list:
Expand Down Expand Up @@ -112,3 +134,18 @@ def announce_going_to_depart_and_arrive(self, message):
# To stop repeat announcement
self.send_announce(message)
self._prev_depart_and_arrive_type = message

def publish_volume_callback(self):
self._sink = self._pulse.get_sink_by_name(self._pulse.server_info().default_sink_name)
self._get_volume_pub.publish(Float32(data=self._sink.volume.value_flat))

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 145 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
except Exception:
response.status.code = ResponseStatus.ERROR
return response
28 changes: 28 additions & 0 deletions src/signage/src/signage/autoware_diagnostic.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
# -*- coding: utf-8 -*-
# Copyright (c) 2020 Tier IV, Inc. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

# ========================================================================
# This code is used to public the diagnostic to autoware and let autoware
# to decide the hazard level
# ========================================================================

import diagnostic_updater

class AutowareDiagnostic():
def init_updater(self, node, name, update_function, hardware_id):
updater = diagnostic_updater.Updater(node, 1)
updater.setHardwareID(hardware_id)
updater.add(name, update_function)
return updater
19 changes: 17 additions & 2 deletions src/signage/src/signage/autoware_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@
OperationModeState,
MotionState,
LocalizationInitializationState,
VelocityFactorArray,
)
import signage.signage_utils as utils
from tier4_debug_msgs.msg import Float64Stamped
from tier4_external_api_msgs.msg import DoorStatus


@dataclass
class AutowareInformation:
autoware_control: bool = False
Expand All @@ -31,6 +31,7 @@ class AutowareInterface:
def __init__(self, node):
self._node = node
self.information = AutowareInformation()
self.is_disconnected = False

sub_qos = rclpy.qos.QoSProfile(
history=rclpy.qos.QoSHistoryPolicy.KEEP_LAST,
Expand Down Expand Up @@ -81,13 +82,22 @@ def __init__(self, node):
self.sub_localization_initialization_state_callback,
api_qos,
)
self._sub_velocity_factors = node.create_subscription(
VelocityFactorArray,
"/api/planning/velocity_factors",
self.sub_velocity_factors_callback,
sub_qos,
)
self._autoware_connection_time = self._node.get_clock().now()
self._node.create_timer(2, self.reset_timer)

def reset_timer(self):
if utils.check_timeout(self._node.get_clock().now(), self._autoware_connection_time, 10):
self.information = AutowareInformation()
self._node.get_logger().error("Autoware disconnected", throttle_duration_sec=10)
self.is_disconnected = True
else:
self.is_disconnected = False

def sub_operation_mode_callback(self, msg):
try:
Expand Down Expand Up @@ -116,7 +126,6 @@ def sub_vehicle_door_callback(self, msg):

def sub_path_distance_callback(self, msg):
try:
self._autoware_connection_time = self._node.get_clock().now()
self.information.goal_distance = msg.data
except Exception as e:
self._node.get_logger().error("Unable to get the goal distance, ERROR: " + str(e))
Expand All @@ -134,3 +143,9 @@ def sub_localization_initialization_state_callback(self, msg):
self._node.get_logger().error(
"Unable to get the localization init state, ERROR: " + str(e)
)

def sub_velocity_factors_callback(self, msg):
try:
self._autoware_connection_time = self._node.get_clock().now()
except Exception as e:
self._node.get_logger().error("Unable to get the velocity factors, ERROR: " + str(e))
20 changes: 20 additions & 0 deletions src/signage/src/signage/heartbeat.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# !/usr/bin/env python3
# -*- coding: utf-8 -*-

from signage.autoware_diagnostic import AutowareDiagnostic
from diagnostic_msgs.msg import DiagnosticStatus

class Heartbeat:
def __init__(self, node):
self._node = node

self._diagnostic_updater = AutowareDiagnostic().init_updater(
self._node,
"/system/signage_connection : signage heartbeat",
self.handle_heartbeat_diagnostics,
"none",
)

def handle_heartbeat_diagnostics(self, stat):
stat.summary(DiagnosticStatus.OK, "signage is working")
return stat
4 changes: 3 additions & 1 deletion src/signage/src/signage/route_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -370,7 +370,9 @@ def view_mode_callback(self):
self._viewController.next_station_list = self._display_details.next_station_list
self._viewController.display_phrase = self._display_phrase

if (
if self._autoware.is_disconnected:
view_mode = "emergency_stopped"
elif (
not self._autoware.information.autoware_control
and not self._parameter.ignore_manual_driving
):
Expand Down
3 changes: 3 additions & 0 deletions src/signage/src/signage/signage.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import rclpy
from rclpy.node import Node

from signage.heartbeat import Heartbeat
from signage.view_controller import ViewControllerProperty
from signage.announce_controller import AnnounceControllerProperty
from signage.autoware_interface import AutowareInterface
Expand All @@ -25,6 +26,8 @@ def main(args=None):
app = QApplication(sys.argv)
engine = QQmlApplicationEngine()

heartbeat = Heartbeat(node)
autoware_interface = AutowareInterface(node)
autoware_interface = AutowareInterface(node)
parameter_interface = ParameterInterface(node)
ros_service_interface = RosServiceInterface(node, parameter_interface)
Expand Down

0 comments on commit b2e4398

Please sign in to comment.