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

Make VDA5050 version customizable #53

Merged
merged 5 commits into from
Jul 1, 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
45 changes: 41 additions & 4 deletions vda5050_connector/vda5050_connector_py/mqtt_bridge.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
from vda5050_connector_py.utils import convert_ros_message_to_json
from vda5050_connector_py.utils import get_vda5050_ts

from vda5050_connector_py.vda5050_controller import DEFAULT_PROTOCOL_VERSION
from vda5050_connector_py.vda5050_controller import DEFAULT_PROTOCOL_VERSION, SUPPORTED_PROTOCOL_VERSIONS

# ROS msgs / srvs / actions
from vda5050_msgs.msg import Action as VDAAction
Expand Down Expand Up @@ -194,6 +194,32 @@ def generate_vda_instant_action_msg(instant_action):
return vda_instant_action


def generate_vda5050_topic_alias(vda_version):
"""
Create an alias for the current vda5050 version. The aliases are needed to
create the mqtt topics.
Args:
----
vda_version (string): VDA5050 version with format x.x.x.
Raises:
------
ValueError if the alias is not within the supported values.
Returns
-------
The alias of the version. For example, for the version '2.0.0', the alias is
'v2'
"""
if vda_version in SUPPORTED_PROTOCOL_VERSIONS:
return f"v{vda_version[0]}"
else:
raise ValueError(
f"Invalid protocol major version. Supported versions are: {SUPPORTED_PROTOCOL_VERSIONS},"
f"but got {vda_version}"
)

class MQTTBridge(Node):
"""Translates VDA5050 MQTT messages from and to ROS2."""

Expand All @@ -209,6 +235,9 @@ def __init__(self):
mqtt_username = read_str_parameter(self, "mqtt_username", "")
mqtt_password = read_str_parameter(self, "mqtt_password", "")

self.vda5050_version = read_str_parameter(self, "vda5050_protocol_version", "2.0.0")
self.vda5050_version_alias = generate_vda5050_topic_alias(self.vda5050_version)

self._manufacturer_name = read_str_parameter(
self, "manufacturer_name", "robots"
)
Expand Down Expand Up @@ -238,6 +267,7 @@ def __init__(self):
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
topic="connection",
major_version=self.vda5050_version_alias,
)

# NOTE: will payload cannot be set dynamically or updated
Expand All @@ -247,7 +277,7 @@ def __init__(self):
will_payload = convert_ros_message_to_json(
VDAConnection(
header_id=0,
version=DEFAULT_PROTOCOL_VERSION,
version=self.vda5050_version,
timestamp="1970-01-01T12:00:00.00Z",
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
Expand Down Expand Up @@ -278,19 +308,21 @@ def on_connect_mqtt(self, client, userdata, flags, rc):
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
topic="order",
major_version=self.vda5050_version_alias,
)
)
self.mqtt_client.subscribe(
get_vda5050_mqtt_topic(
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
topic="instantActions",
major_version=self.vda5050_version_alias
)
)
self._publish_connection(
msg=VDAConnection(
header_id=0,
version=DEFAULT_PROTOCOL_VERSION,
version=self.vda5050_version,
timestamp=get_vda5050_ts(),
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
Expand Down Expand Up @@ -405,7 +437,7 @@ def on_shutdown(self):

offline_message = VDAConnection(
header_id=0,
version=DEFAULT_PROTOCOL_VERSION,
version=self.vda5050_version,
timestamp=get_vda5050_ts(),
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
Expand All @@ -424,13 +456,15 @@ def on_shutdown(self):
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
topic="order",
major_version=self.vda5050_version_alias
)
)
self.mqtt_client.unsubscribe(
get_vda5050_mqtt_topic(
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
topic="instantActions",
major_version=self.vda5050_version_alias
)
)

Expand Down Expand Up @@ -463,6 +497,7 @@ def _publish_state(self, msg: VDAOrderState):
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
topic="state",
major_version=self.vda5050_version_alias
)
self._publish_to_topic(msg, topic)

Expand All @@ -485,6 +520,7 @@ def _publish_connection(self, msg: VDAConnection):
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
topic="connection",
major_version=self.vda5050_version_alias
)
self._publish_to_topic(msg, topic)

Expand All @@ -501,5 +537,6 @@ def _publish_visualization(self, msg: VDAVisualization):
manufacturer=self._manufacturer_name,
serial_number=self._serial_number,
topic="visualization",
major_version=self.vda5050_version_alias
)
self._publish_to_topic(msg, topic)
2 changes: 1 addition & 1 deletion vda5050_connector/vda5050_connector_py/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ def convert_ros_message_to_json(msg):


def get_vda5050_mqtt_topic(
manufacturer, serial_number, topic, interface_name="uagv", major_version="v1"
manufacturer, serial_number, topic, major_version, interface_name="uagv",
):
"""
Return suggested VDA5050 MQTT topics.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@
DEFAULT_SERIAL_NUMBER = "robot_1"
DEFAULT_PROTOCOL_VERSION = "2.0.0"
DEFAULT_STARTING_NODE_ID = ""
SUPPORTED_PROTOCOL_VERSIONS = ["1.1.0", "2.0.0"]

DEFAULT_GET_STATE_SVC_NAME = "adapter/get_state"
DEFAULT_SUPPORTED_ACTIONS_SVC_NAME = "adapter/supported_actions"
Expand Down
Loading