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

hotfix: FMSのアクセスノードを分離する #132

Merged
merged 2 commits into from
Nov 5, 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
4 changes: 2 additions & 2 deletions src/external_signage/setup.cfg
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
[develop]
script-dir=$base/lib/external_signage
script_dir=$base/lib/external_signage
[install]
install-scripts=$base/lib/external_signage
install_scripts=$base/lib/external_signage
3 changes: 2 additions & 1 deletion src/signage/config/signage_param.yaml
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
signage:
ros__parameters:
signage_stand_alone: true
ignore_emergency_stoppped: false

Check warning on line 4 in src/signage/config/signage_param.yaml

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (stoppped)
ignore_disconnected: false
ignore_manual_driving: false
set_goal_by_distance: false
freeze_emergency: true
goal_distance: 1.0 # meter
check_fms_time: 5.0 # second
check_fms_time: 2.0 # second
emergency_ignore_period: 5.0 # second
emergency_repeat_period: 180.0 # second
accept_start: 5.0 # second
Expand Down
5 changes: 5 additions & 0 deletions src/signage/launch/signage.launch.xml
Original file line number Diff line number Diff line change
@@ -1,10 +1,15 @@
<?xml version="1.0"?>
<launch>
<arg name="signage_param" default="$(find-pkg-share signage)/config/signage_param.yaml" />
<arg name="fms_client_param" default="$(find-pkg-share signage_fms_client)/config/fms_client_param.yaml" />
<arg name="debug_mode" default="false" />
<node pkg="signage" exec="signage" output="screen">
<param from="$(var signage_param)"/>
<param name="debug_mode" value="$(var debug_mode)" />
</node>
<node pkg="external_signage" exec="external_signage" output="screen" />

<node pkg="signage_fms_client" exec="signage_fms_client" output="screen" >
<param from="$(var fms_client_param)"/>
</node>
</launch>
3 changes: 2 additions & 1 deletion src/signage/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<version>0.1.0</version>
<description>The signage package</description>

<maintainer email="[email protected]">yabuta</maintainer>

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

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (yabuta)

<license>Apache License 2.0</license>
<exec_depend>ament_index_python</exec_depend>
Expand All @@ -12,14 +12,15 @@

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

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

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (pulsectl)
<depend>rclpy</depend>
<depend>signage_fms_client</depend>
<depend>std_srvs</depend>
<depend>tier4_api_msgs</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_external_api_msgs</depend>
<depend>tier4_hmi_msgs</depend>
<depend>external_signage</depend>

<export>
<build_type>ament_python</build_type>
Expand Down
4 changes: 2 additions & 2 deletions src/signage/setup.cfg
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
[develop]
script-dir=$base/lib/signage
script_dir=$base/lib/signage
[install]
install-scripts=$base/lib/signage
install_scripts=$base/lib/signage
14 changes: 14 additions & 0 deletions src/signage/src/signage/autoware_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

import rclpy
from dataclasses import dataclass
from autoware_adapi_v1_msgs.msg import (

Check warning on line 6 in src/signage/src/signage/autoware_interface.py

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (adapi)
RouteState,
MrmState,
OperationModeState,
Expand All @@ -11,6 +11,7 @@
LocalizationInitializationState,
VelocityFactorArray,
)
from std_msgs.msg import String
import signage.signage_utils as utils
from tier4_debug_msgs.msg import Float64Stamped
from tier4_external_api_msgs.msg import DoorStatus
Expand All @@ -28,6 +29,7 @@
goal_distance: float = 1000.0
motion_state: int = 0
localization_init_state: int = 0
active_schedule: str = ""


class AutowareInterface:
Expand Down Expand Up @@ -80,7 +82,7 @@
self._sub_motion_state = node.create_subscription(
MotionState, "/api/motion/state", self.sub_motion_state_callback, api_qos
)
self._sub_localiztion_initializtion_state = node.create_subscription(

Check warning on line 85 in src/signage/src/signage/autoware_interface.py

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (localiztion)

Check warning on line 85 in src/signage/src/signage/autoware_interface.py

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (initializtion)
LocalizationInitializationState,
"/api/localization/initialization_state",
self.sub_localization_initialization_state_callback,
Expand All @@ -92,6 +94,12 @@
self.sub_velocity_factors_callback,
sub_qos,
)
self._sub_active_schedule = node.create_subscription(
String,
"/signage/active_schedule",
self.sub_active_schedule_callback,
sub_qos,
)
if not self._parameter.debug_mode:
self._autoware_connection_time = self._node.get_clock().now()
self._node.create_timer(1, self.reset_timer)
Expand Down Expand Up @@ -158,3 +166,9 @@
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))

def sub_active_schedule_callback(self, msg):
try:
self.information.active_schedule = msg.data
except Exception as e:
self._node.get_logger().error("Unable to get the active schedule, ERROR: " + str(e))
5 changes: 5 additions & 0 deletions src/signage/src/signage/parameter_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
debug_mode: bool = False
signage_stand_alone: bool = False
ignore_manual_driving: bool = False
ignore_disconnected: bool = False
ignore_emergency: bool = False
set_goal_by_distance: bool = False
freeze_emergency: bool = True
Expand Down Expand Up @@ -43,11 +44,12 @@

node.declare_parameter("debug_mode", False)
node.declare_parameter("signage_stand_alone", False)
node.declare_parameter("ignore_disconnected", False)
node.declare_parameter("ignore_manual_driving", False)
node.declare_parameter("freeze_emergency", True)
node.declare_parameter("check_fms_time", 5.0)
node.declare_parameter("accept_start", 5.0)
node.declare_parameter("ignore_emergency_stoppped", False)

Check warning on line 52 in src/signage/src/signage/parameter_interface.py

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (stoppped)
node.declare_parameter("set_goal_by_distance", False)
node.declare_parameter("goal_distance", 1.0)
node.declare_parameter("emergency_ignore_period", 5.0)
Expand All @@ -61,6 +63,9 @@
self.parameter.signage_stand_alone = (
node.get_parameter("signage_stand_alone").get_parameter_value().bool_value
)
self.parameter.ignore_disconnected = (
node.get_parameter("ignore_disconnected").get_parameter_value().bool_value
)
self.parameter.ignore_manual_driving = (
node.get_parameter("ignore_manual_driving").get_parameter_value().bool_value
)
Expand All @@ -74,7 +79,7 @@
node.get_parameter("accept_start").get_parameter_value().double_value
)
self.parameter.ignore_emergency = (
node.get_parameter("ignore_emergency_stoppped").get_parameter_value().bool_value

Check warning on line 82 in src/signage/src/signage/parameter_interface.py

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (stoppped)
)
self.parameter.set_goal_by_distance = (
node.get_parameter("set_goal_by_distance").get_parameter_value().bool_value
Expand Down
46 changes: 12 additions & 34 deletions src/signage/src/signage/route_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,10 @@
import os
import json
from datetime import datetime
import aiohttp
import asyncio
from threading import Thread

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 All @@ -36,14 +33,6 @@
self._autoware = autoware_interface
self._parameter = parameter_interface.parameter
self._service_interface = ros_service_interface
self.AUTOWARE_IP = os.getenv("AUTOWARE_IP", "localhost")
self._fms_payload = {
"method": "get",
"url": "https://"
+ os.getenv("FMS_URL", "fms.web.auto")
+ "/v1/projects/{project_id}/environments/{environment_id}/vehicles/{vehicle_id}/active_schedule",
"body": {},
}
self._schedule_details = utils.init_ScheduleDetails()
self._display_details = utils.init_DisplayDetails()
self._current_task_details = utils.init_CurrentTask()
Expand Down Expand Up @@ -207,25 +196,8 @@
self._node.get_logger().error("not able to play the announce, ERROR: {}".format(str(e)))

def process_station_list_from_fms(self, force_update=False):
if not self._processing_thread:
self._processing_thread = True
thread = Thread(target=asyncio.run(self.fms_thread()), args=(force_update,))
thread.setDaemon(True)
thread.start()
self._processing_thread = False

async def fms_thread(self, force_update=False):
try:
async with aiohttp.ClientSession() as session:
async with session.post(
f"http://{self.AUTOWARE_IP}:4711/v1/services/order",
json=self._fms_payload,
timeout=10,
) as response:
data = await response.json()

self._fms_check_time = self._node.get_clock().now()

data = json.loads(self._autoware.information.active_schedule)
if not data:
self._schedule_details = utils.init_ScheduleDetails()
self._display_details = utils.init_DisplayDetails()
Expand All @@ -235,6 +207,8 @@
self._fms_check_time = self._node.get_clock().now()
raise Exception("same schedule, skip")

self._fms_check_time = self._node.get_clock().now()

self._schedule_details = utils.update_schedule_details(data)

self._display_details.route_name = utils.get_route_name(
Expand Down Expand Up @@ -403,9 +377,6 @@
self._current_task_details.depart_time, self._node.get_clock().now().to_msg().sec
)

self._node.get_logger().info("_reach_final: " + str(self._reach_final))
self._node.get_logger().info("remain_minute: " + str(remain_minute))

if self._reach_final:
# display arrive to final station
self._display_phrase = utils.handle_phrase("final")
Expand All @@ -426,7 +397,10 @@
self._announced_depart = True
elif self._is_driving:
# handle text and announce while bus is running
if self._autoware.information.goal_distance < 100:
if (
self._autoware.information.goal_distance < 100
and self._autoware.information.goal_distance > 0
):
# display text and announce if the goal is within 100m
self._display_phrase = utils.handle_phrase("arriving")
if not self._announced_arrive:
Expand All @@ -453,7 +427,11 @@
self._viewController.next_station_list = self._display_details.next_station_list
self._viewController.display_phrase = self._display_phrase

if self._autoware.is_disconnected:
if (
self._autoware.is_disconnected
and not self._parameter.ignore_disconnected
and not self._parameter.ignore_emergency
):
view_mode = "emergency_stopped"
elif (
not self._autoware.information.autoware_control
Expand Down
3 changes: 3 additions & 0 deletions src/signage_fms_client/config/fms_client_param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
signage:
ros__parameters:
post_request_time: 8.0 # second
7 changes: 7 additions & 0 deletions src/signage_fms_client/launch/signage_fms_client.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<?xml version="1.0"?>
<launch>
<arg name="fms_client_param" default="$(find-pkg-share signage)/config/fms_client_param.yaml" />
<node pkg="signage_fms_client" exec="signage_fms_client" output="screen" >
<param from="$(var signage_param)"/>
</node>
</launch>
17 changes: 17 additions & 0 deletions src/signage_fms_client/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0"?>
<package format="2">
<name>signage_fms_client</name>
<version>0.1.0</version>
<description>The fms client for signage</description>

<maintainer email="[email protected]">tkhmy</maintainer>

Check warning on line 7 in src/signage_fms_client/package.xml

View workflow job for this annotation

GitHub Actions / spellcheck

Unknown word (tkhmy)

<license>Apache License 2.0</license>
<exec_depend>ament_index_python</exec_depend>

<depend>rclpy</depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
Empty file.
4 changes: 4 additions & 0 deletions src/signage_fms_client/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/signage_fms_client
[install]
install_scripts=$base/lib/signage_fms_client
47 changes: 47 additions & 0 deletions src/signage_fms_client/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
#!/usr/bin/env python3

import os

from setuptools import setup


def package_files(directory):
paths = []
for (path, directories, filenames) in os.walk(directory):
for filename in filenames:
paths.append(os.path.join(path, filename))
return paths


package_name = "signage_fms_client"
setup(
name=package_name,
version="0.1.0",
package_dir={"": "src"},
packages=[package_name],
data_files=[
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
("share/" + package_name, ["package.xml"]),
("share/" + package_name + "/launch", ["launch/signage_fms_client.launch.xml"]),
("share/" + package_name + "/config", ["config/fms_client_param.yaml"]),
],
install_requires=["setuptools"],
zip_safe=True,
author="Kah Hooi Tan",
maintainer="Kah Hooi Tan",
maintainer_email="[email protected]",
keywords=["ROS"],
classifiers=[
"Intended Audience :: Developers",
"License :: OSI Approved :: Apache Software License",
"Programming Language :: Python",
"Topic :: Software Development",
],
description=("for fms client with signage"),
license="TODO",
entry_points={
"console_scripts": [
"signage_fms_client = signage_fms_client.signage_fms_client:main",
]
},
)
4 changes: 4 additions & 0 deletions src/signage_fms_client/src/signage_fms_client/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# This Python file uses the following encoding: utf-8

# if__name__ == "__main__":
# pass
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
# This Python file uses the following encoding: utf-8
import os

import rclpy
from rclpy.node import Node

import requests
from std_msgs.msg import String


class FMSClient(Node):
def __init__(self, node):
self._node = node
node.declare_parameter("post_request_time", 8.0)
self._post_request_time = (
node.get_parameter("post_request_time").get_parameter_value().double_value
)
self._fms_payload = {
"method": "get",
"url": "https://"
+ os.getenv("FMS_URL", "fms.web.auto")
+ "/v1/projects/{project_id}/environments/{environment_id}/vehicles/{vehicle_id}/active_schedule",
"body": {},
}
self.AUTOWARE_IP = os.getenv("AUTOWARE_IP", "localhost")
self.schedule_pub_ = node.create_publisher(String, "/signage/active_schedule", 10)
self.timer = node.create_timer(self._post_request_time + 0.5, self.pub_schedule)

def pub_schedule(self):
try:
msg = String()
respond = requests.post(
"http://{}:4711/v1/services/order".format(self.AUTOWARE_IP),
json=self._fms_payload,
timeout=self._post_request_time,
)
msg.data = respond.text
self.schedule_pub_.publish(msg)
except Exception as e:
self._node.get_logger().warning(
"Unable to get the task from FMS, ERROR: " + str(e), throttle_duration_sec=5
)


def main(args=None):

rclpy.init(args=args)
node = Node("signage_fms_client")

signage_fms_client = FMSClient(node)

while True:
rclpy.spin_once(node, timeout_sec=0.01)


if __name__ == "__main__":
main()
Loading