Skip to content

Commit

Permalink
Merge pull request #52 from ipa320/rwu/feature/write_param_value_in_s…
Browse files Browse the repository at this point in the history
…ystem

Write param value in system model [Merge 1st]
  • Loading branch information
ipa-nhg authored Feb 28, 2024
2 parents ead6565 + d372102 commit 01248ab
Show file tree
Hide file tree
Showing 11 changed files with 109 additions and 30 deletions.
5 changes: 3 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,10 @@ For the static code analysis we made available a web interface able to inspect c
```
source /opt/ros/humble/setup.bash
```
3. Back to the folder "ws", create venv
3. Back to the folder "ws", create and active venv
```
python3 -m venv venv --system-site-packages --symlinks
source venv/bin/activate
```
4. Install poetry and install dependencies
run
Expand All @@ -37,7 +38,7 @@ For the static code analysis we made available a web interface able to inspect c
```
5. compile it as ROS package
```
colcon build --packages-select ros2model --symlink-install
python -m colcon build --packages-select ros2model --symlink-install
```

## Run
Expand Down
24 changes: 16 additions & 8 deletions ros2model/api/runtime_parser/rosmodel_runtime_parser.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,13 @@
from rclpy.topic_endpoint_info import TopicEndpointInfo
import rclpy
from rcl_interfaces.msg import ParameterType
import ros2model.core.utils as utils

from collections import namedtuple
from ros2param.api import (
call_list_parameters,
call_describe_parameters,
call_get_parameters,
)

Topic_BlackList = ["/parameter_events", "/rosout"]
Expand All @@ -38,11 +40,11 @@ def get_parameter_type_string(parameter_type):
ParameterType.PARAMETER_INTEGER: "Integer",
ParameterType.PARAMETER_DOUBLE: "Double",
ParameterType.PARAMETER_STRING: "String",
ParameterType.PARAMETER_BYTE_ARRAY: "Array: Byte",
ParameterType.PARAMETER_BOOL_ARRAY: "Array: Boolean",
ParameterType.PARAMETER_INTEGER_ARRAY: "Array: Integer",
ParameterType.PARAMETER_DOUBLE_ARRAY: "Array: Double",
ParameterType.PARAMETER_STRING_ARRAY: "Array: String",
ParameterType.PARAMETER_BYTE_ARRAY: "Array[Byte]",
ParameterType.PARAMETER_BOOL_ARRAY: "Array[Boolean]",
ParameterType.PARAMETER_INTEGER_ARRAY: "Array[Integer]",
ParameterType.PARAMETER_DOUBLE_ARRAY: "Array[Double]",
ParameterType.PARAMETER_STRING_ARRAY: "Array[String]",
ParameterType.PARAMETER_NOT_SET: "Any",
}
return mapping[parameter_type]
Expand Down Expand Up @@ -275,12 +277,18 @@ def get_parameters(self, node, include_hidden_nodes=False):
node_name=self.name.full_name,
parameter_names=sorted_names,
)
for descriptor in des_resp.descriptors:

get_parameters_response = call_get_parameters(
node=node, node_name=self.name.full_name, parameter_names=sorted_names
)

for param_name, pvalue in zip(sorted_names, get_parameters_response.values):
self.parameter.append(
ROSModel.Parameter(
name=descriptor.name,
name=param_name,
namespace=self.name.namespace,
type=get_parameter_type_string(descriptor.type),
type=get_parameter_type_string(pvalue.type),
value=str(utils.get_param_value(pvalue)),
)
)

Expand Down
52 changes: 52 additions & 0 deletions ros2model/core/utils.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
import psutil
from rclpy.parameter import Parameter
from rcl_interfaces.msg import ParameterType


def find_process_by_node_name(node_name, namespace):
for process in psutil.process_iter(["pid", "cmdline"]):
try:
cmdline = process.info["cmdline"]
if namespace in str(cmdline) and node_name in str(cmdline):
cmdline_list = cmdline[0].split("/")
if len(cmdline_list) >= 3:
return cmdline_list[-2], cmdline_list[-1]
except (psutil.NoSuchProcess, psutil.AccessDenied, psutil.ZombieProcess):
pass
return "TODO", "TODO"


def get_param_value(pvalue: Parameter):
if pvalue.type == ParameterType.PARAMETER_BOOL:
label = "Boolean value is:"
value = pvalue.bool_value
elif pvalue.type == ParameterType.PARAMETER_INTEGER:
label = "Integer value is:"
value = pvalue.integer_value
elif pvalue.type == ParameterType.PARAMETER_DOUBLE:
label = "Double value is:"
value = pvalue.double_value
elif pvalue.type == ParameterType.PARAMETER_STRING:
label = "String value is:"
value = pvalue.string_value
elif pvalue.type == ParameterType.PARAMETER_BYTE_ARRAY:
label = "Byte values are:"
value = pvalue.byte_array_value
elif pvalue.type == ParameterType.PARAMETER_BOOL_ARRAY:
label = "Boolean values are:"
value = pvalue.bool_array_value
elif pvalue.type == ParameterType.PARAMETER_INTEGER_ARRAY:
label = "Integer values are:"
value = pvalue.integer_array_value.tolist()
elif pvalue.type == ParameterType.PARAMETER_DOUBLE_ARRAY:
label = "Double values are:"
value = pvalue.double_array_value.tolist()
elif pvalue.type == ParameterType.PARAMETER_STRING_ARRAY:
label = "String values are:"
value = pvalue.string_array_value
elif pvalue.type == ParameterType.PARAMETER_NOT_SET:
label = "Parameter not set."
value = None
else:
return f"Unknown parameter type '{pvalue.type}'"
return value
20 changes: 3 additions & 17 deletions ros2model/verb/runtime_node.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,14 @@
from pathlib import Path

from ros2model.core.utils import find_process_by_node_name

from ros2cli.node.strategy import add_arguments

from ros2model.verb import VerbExtension
from ros2model.api.model_generator.component_generator import ComponentGenerator
import ros2model.api.runtime_parser.rosmodel_runtime_parser as RuntimeParser
import ros2model.core.metamodels.metamodel_ros as ROSModel

import psutil
import sys


class RuntimeNodeVerb(VerbExtension):
"""Create .ros2 for each node in a runtime system"""
Expand Down Expand Up @@ -47,17 +46,6 @@ def name_component_file(self, grapg_name: ROSModel.GraphName):
file_name = f"{grapg_name.namespace[1:]}__{n}"
return file_name

def find_process_by_node_name(self, node_name, namespace):
for process in psutil.process_iter(["pid", "cmdline"]):
try:
cmdline = process.info["cmdline"]
if namespace in str(cmdline) and node_name in str(cmdline):
cmdline_list = cmdline[0].split("/")
return cmdline_list[-2], cmdline_list[-1]
except (psutil.NoSuchProcess, psutil.AccessDenied, psutil.ZombieProcess):
pass
return "TODO", "TODO"

def main(self, *, args):
output_dir = Path(args.output_folder)
if output_dir.is_absolute() != True:
Expand All @@ -74,9 +62,7 @@ def main(self, *, args):
args.include_hidden_nodes,
args.include_hidden_interfaces,
)
package_name, artifact_name = self.find_process_by_node_name(
n.name, n.namespace
)
package_name, artifact_name = find_process_by_node_name(n.name, n.namespace)
runtime_pkg = ROSModel.Package(
name=package_name,
artifact=[ROSModel.Artifact(name=artifact_name, node=[node_instance])],
Expand Down
9 changes: 9 additions & 0 deletions templates/component.ros2.j2
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,15 @@
{% for parameter in node.parameter %}
'{{ parameter.name }}':
type: {{ parameter.type }}
{% if parameter.value != none %}
{% if parameter.type == "String" %}
value: "{{ parameter.value }}"
{% elif parameter.type == "Boolean" %}
value: {{ parameter.value | lower }}
{% else %}
value: {{ parameter.value }}
{% endif %}
{% endif %}
{% endfor %}
{% endif %}
{% endfor %}
Expand Down
15 changes: 15 additions & 0 deletions templates/rossystem.rossystem.j2
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
{% for node in model.nodes %}
"{{ node.name.full_name }}":
from: "TODO.{{ node.name.full_name }}"
{% if node.publisher | length > 0 or node.subscriber | length > 0 or node.actionserver | length > 0 or node.actionclient | length > 0 or node.serviceserver | length > 0 or node.serviceclient | length > 0%}
interfaces:
{% for interface in node.publisher %}
- "{{ interface.name }}": pub-> "TODO::{{ interface.name }}"
Expand All @@ -22,4 +23,18 @@
{% for interface in node.serviceclient %}
- "{{ interface.name }}": sc-> "TODO::{{ interface.name }}"
{% endfor %}
{% endif %}
{% if node.parameter | length > 0 %}
parameters:
{% for parameter in node.parameter %}
- {{ parameter.name }}: "{{ node.name.full_name }}.{{ parameter.name }}"
{% if parameter.type == "String" %}
value: "{{ parameter.value }}"
{% elif parameter.type == "Boolean" %}
value: {{ parameter.value | lower }}
{% else %}
value: {{ parameter.value }}
{% endif %}
{% endfor %}
{% endif %}
{% endfor %}
1 change: 1 addition & 0 deletions test/outputs/test_model.ros2
Original file line number Diff line number Diff line change
Expand Up @@ -22,3 +22,4 @@ test_model:
parameters:
'shadows/min_angle':
type: Double
value: -1.52
3 changes: 3 additions & 0 deletions test/outputs/test_system.rossystem
Original file line number Diff line number Diff line change
Expand Up @@ -9,3 +9,6 @@ test_system:
- "static_map": ac-> "TODO::static_map"
- "static_map": ss-> "TODO::static_map"
- "static_map": sc-> "TODO::static_map"
parameters:
- shadows/min_angle: "/map_server.shadows/min_angle"
value: -1.52
3 changes: 2 additions & 1 deletion test/unittest/test_generate_component.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
# pprint(test_model)

test_dir = "test"
output_folder = "outputs"
output_folder = Path(__file__).parent.parent / "outputs"

expect_result = """
test_model:
Expand All @@ -75,6 +75,7 @@
parameters:
'shadows/min_angle':
type: Double
value: -1.52
"""

Expand Down
2 changes: 1 addition & 1 deletion test/unittest/test_generate_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
)

test_dir = "test"
output_folder = "outputs"
output_folder = Path(__file__).parent.parent / "outputs"

expect_result = """
test_interfaces:
Expand Down
5 changes: 4 additions & 1 deletion test/unittest/test_generate_system.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
pprint(test_model)

test_dir = "test"
output_folder = "outputs"
output_folder = Path(__file__).parent.parent / "outputs"

expect_result = """
test_system:
Expand All @@ -51,6 +51,9 @@
- "static_map": ac-> "TODO::static_map"
- "static_map": ss-> "TODO::static_map"
- "static_map": sc-> "TODO::static_map"
parameters:
- shadows/min_angle: "/map_server.shadows/min_angle"
value: -1.52
"""

Expand Down

0 comments on commit 01248ab

Please sign in to comment.