Skip to content

Made fields in python structs assigned per-instance instead of at the class scope#351

Open
alexnavtt wants to merge 8 commits intoPickNikRobotics:mainfrom
alexnavtt:main
Open

Made fields in python structs assigned per-instance instead of at the class scope#351
alexnavtt wants to merge 8 commits intoPickNikRobotics:mainfrom
alexnavtt:main

Conversation

@alexnavtt
Copy link
Copy Markdown

As stated in #313, struct variables declared in python modules were declared at the class scope, causing unwanted state sharing in certain circumstances. This PR fixes that by declaring all fields within an __init__ function, including sub-struct instances.

As an examples of changes made, I'll highlight my use case and what changed. The parameter definition file is located here. When setting multiple depth camera sensors via this parameter set, I noticed that the camera_info parameter would be shared and take the last set value across all Map entries. This issue could also appear when creating multiple Params instances.

This is the generated code prior to the changes:

class simulation_parameters:

    class Params:
        # for detecting if the parameter struct has been updated
        stamp_ = Time()

        object_names = None
        sensor_names = None
        robot_names = None
        world_frame = "odom"
        class __Objects:
            class __MapObjectNames:
                object_type = None
                dimensions = [0.0]
                mesh_scale = 1.0
                file_path = ""
                location = [0.0, 0.0, 0.0]
                yaw = 0.0
                pitch = 0.0
                roll = 0.0
                parent = ""
                rgb = [0.5, 0.5, 0.5]
            __map_type = __MapObjectNames
            def add_entry(self, name):
                if not hasattr(self, name):
                    setattr(self, name, self.__map_type())
                return getattr(self, name)
            def get_entry(self, name):
                return getattr(self, name)
        objects = __Objects()
        class __Robots:
            class __MapRobotNames:
                urdf_path = None
                namespace = None
                xacro_args = ""
                odometry_frame = "odom"
                odometry_topic = "odom"
                update_rate = 10.0
                class __InitialTransform:
                    translation = [0.0, 0.0, 0.0]
                    yaw = 0.0
                    pitch = 0.0
                    roll = 0.0
                initial_transform = __InitialTransform()
            __map_type = __MapRobotNames
            def add_entry(self, name):
                if not hasattr(self, name):
                    setattr(self, name, self.__map_type())
                return getattr(self, name)
            def get_entry(self, name):
                return getattr(self, name)
        robots = __Robots()
        class __Sensors:
            class __MapSensorNames:
                sensor_type = None
                update_rate = 10.0
                topic = "/lidar_points"
                best_effort = False
                frame_id = None
                noise_std_dev = 0.0
                min_range = 0.0
                max_range = 0.0
                class __LidarConfig:
                    min_horizontal_angle = -180.0
                    max_horizontal_angle = 180.0
                    min_vertical_angle = 0.0
                    max_vertical_angle = 0.0
                    num_vertical_channels = 16
                    num_horizontal_channels = 512
                lidar_config = __LidarConfig()
                class __DepthConfig:
                    fx = 0.0
                    fy = 0.0
                    cx = 0.0
                    cy = 0.0
                    horizontal_resolution = 0
                    vertical_resolution = 0
                    info_topic = ""
                    encoding = "32FC1"
                depth_config = __DepthConfig()
                class __RgbConfig:
                    fx = 0.0
                    fy = 0.0
                    cx = 0.0
                    cy = 0.0
                    horizontal_resolution = 0
                    vertical_resolution = 0
                    info_topic = ""
                    encoding = "rgb8"
                rgb_config = __RgbConfig()
            __map_type = __MapSensorNames
            def add_entry(self, name):
                if not hasattr(self, name):
                    setattr(self, name, self.__map_type())
                return getattr(self, name)
            def get_entry(self, name):
                return getattr(self, name)
        sensors = __Sensors()

And this is the generated code after the changes:

class simulation_parameters:

    class Params:
        def __init__(self):
            # for detecting if the parameter struct has been updated
            self.stamp_ = Time()

            self.object_names = None
            self.sensor_names = None
            self.robot_names = None
            self.world_frame = "odom"
            self.objects = self.__Objects()
            self.robots = self.__Robots()
            self.sensors = self.__Sensors()
        class __Objects:
            def __init__(self):
                pass # no explicit fields in a map
            class __MapObjectNames:
                def __init__(self):
                    self.object_type = None
                    self.dimensions = [0.0]
                    self.mesh_scale = 1.0
                    self.file_path = ""
                    self.location = [0.0, 0.0, 0.0]
                    self.yaw = 0.0
                    self.pitch = 0.0
                    self.roll = 0.0
                    self.parent = ""
                    self.rgb = [0.5, 0.5, 0.5]
            __map_type = __MapObjectNames
            def add_entry(self, name):
                if not hasattr(self, name):
                    setattr(self, name, self.__map_type())
                return getattr(self, name)
            def get_entry(self, name):
                return getattr(self, name)
        class __Robots:
            def __init__(self):
                pass # no explicit fields in a map
            class __MapRobotNames:
                def __init__(self):
                    self.urdf_path = None
                    self.namespace = None
                    self.xacro_args = ""
                    self.odometry_frame = "odom"
                    self.odometry_topic = "odom"
                    self.update_rate = 10.0
                    self.initial_transform = self.__InitialTransform()
                class __InitialTransform:
                    def __init__(self):
                        self.translation = [0.0, 0.0, 0.0]
                        self.yaw = 0.0
                        self.pitch = 0.0
                        self.roll = 0.0
            __map_type = __MapRobotNames
            def add_entry(self, name):
                if not hasattr(self, name):
                    setattr(self, name, self.__map_type())
                return getattr(self, name)
            def get_entry(self, name):
                return getattr(self, name)
        class __Sensors:
            def __init__(self):
                pass # no explicit fields in a map
            class __MapSensorNames:
                def __init__(self):
                    self.sensor_type = None
                    self.update_rate = 10.0
                    self.topic = "/lidar_points"
                    self.best_effort = False
                    self.frame_id = None
                    self.noise_std_dev = 0.0
                    self.min_range = 0.0
                    self.max_range = 0.0
                    self.lidar_config = self.__LidarConfig()
                    self.depth_config = self.__DepthConfig()
                    self.rgb_config = self.__RgbConfig()
                class __LidarConfig:
                    def __init__(self):
                        self.min_horizontal_angle = -180.0
                        self.max_horizontal_angle = 180.0
                        self.min_vertical_angle = 0.0
                        self.max_vertical_angle = 0.0
                        self.num_vertical_channels = 16
                        self.num_horizontal_channels = 512
                class __DepthConfig:
                    def __init__(self):
                        self.fx = 0.0
                        self.fy = 0.0
                        self.cx = 0.0
                        self.cy = 0.0
                        self.horizontal_resolution = 0
                        self.vertical_resolution = 0
                        self.info_topic = ""
                        self.encoding = "32FC1"
                class __RgbConfig:
                    def __init__(self):
                        self.fx = 0.0
                        self.fy = 0.0
                        self.cx = 0.0
                        self.cy = 0.0
                        self.horizontal_resolution = 0
                        self.vertical_resolution = 0
                        self.info_topic = ""
                        self.encoding = "rgb8"
            __map_type = __MapSensorNames
            def add_entry(self, name):
                if not hasattr(self, name):
                    setattr(self, name, self.__map_type())
                return getattr(self, name)
            def get_entry(self, name):
                return getattr(self, name)

I have tested this code in my project and verified that it fixes the issue for me.

Also, this is my first time working with this codebase, so I would appreciate a thourough review making sure I didn't accidentally affect some other part of the system.

@christophfroehlich
Copy link
Copy Markdown
Collaborator

@Mat198 Can you have a look please?

Copy link
Copy Markdown
Collaborator

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for opening this PR. Can you please fix pre-commit issues? and better install it for the future.

Copy link
Copy Markdown

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

This PR updates the Python code generation path so generated parameter “struct” fields are initialized per-instance (in __init__) rather than at class scope, preventing unintended shared state across Params instances and nested sub-structs/maps (as reported in #313).

Changes:

  • Add __init__ methods to generated Python parameter structs and move field initialization into __init__.
  • Update generated Python variable declarations to use self.<field> = ... instead of class attributes.
  • Extend YAML parsing/codegen to support emitting sub-struct instance initialization via a new is_struct path.

Reviewed changes

Copilot reviewed 4 out of 4 changed files in this pull request and generated 4 comments.

File Description
generate_parameter_library_py/generate_parameter_library_py/parse_yaml.py Adds an is_struct path in variable codegen and injects generated “struct instance” fields intended for Python __init__.
generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/parameter_library_header Wraps Params fields in an __init__ method and updates stamp_ to self.stamp_.
generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_variable Switches generated assignments to self.<name> = ....
generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_struct Adds __init__ for all generated struct classes and removes class-scope instantiation.

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Comment thread generate_parameter_library_py/generate_parameter_library_py/parse_yaml.py Outdated
Comment thread generate_parameter_library_py/generate_parameter_library_py/parse_yaml.py Outdated
Comment on lines +25 to +33
def __init__(self):
{%- filter indent(width=4) %}
# for detecting if the parameter struct has been updated
stamp_ = Time()
self.stamp_ = Time()

{{field_content-}}
{{sub_struct_content-}}
{% endfilter -%}
{{sub_struct_content-}}
{%- endfilter %}
Copy link

Copilot AI May 1, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This change fixes a subtle runtime behavior (instance state isolation), but there isn’t an automated test asserting that two Params() instances (or two map entries) don’t share mutable defaults (lists / nested structs). Adding a regression test that instantiates multiple Params objects and verifies nested fields are independent would help prevent this from reappearing.

Copilot uses AI. Check for mistakes.
@alexnavtt
Copy link
Copy Markdown
Author

Hmm, I was accidentally working under the assumption that parse_yaml.py was only used for Python code, but I see that that isn't quite correct. I'll have to take another look find a way to cleanly scope it to just python code

@Mat198
Copy link
Copy Markdown
Contributor

Mat198 commented May 1, 2026

@Mat198 Can you have a look please?

Yeah. Sure!

@alexnavtt
Copy link
Copy Markdown
Author

Alright, I reworked my solution to add python-specific fields to the Jinja data for both declare_struct and parameter_library_header. My older solution of making sub-struct instantiation a struct field has been pretty much entirely reverted in favor of this format. This also ensures that the change only affects python code, since those templates are the only ones to use the new data

@Mat198
Copy link
Copy Markdown
Contributor

Mat198 commented May 1, 2026

Thanks for your contribution @alexnavtt!

Could you please remove the module reload from the consistency test (test_params_consistency.py)? This shoudn't be necessary with this fix.

    def setUp(self):
        # Reload the module to reset class-level attribute state between tests.
        # See: https://github.com/PickNikRobotics/generate_parameter_library/issues/313
        importlib.reload(generate_parameter_module_example.admittance_parameters)
        from generate_parameter_module_example.admittance_parameters import (
            admittance_controller as ac,
        )

        self.ac = ac

@alexnavtt
Copy link
Copy Markdown
Author

Done

Copy link
Copy Markdown
Collaborator

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you please add a test for this (as suggested by copilot, too)?
@Mat198 If the changes are working for you, please leave a review via github UI. Thanks!

@Mat198
Copy link
Copy Markdown
Contributor

Mat198 commented May 3, 2026

Hey @alexnavtt, the consistency tests are failling. It's very easy to fix but I don't have ter permissions to edit it. Just fix the import of the admitance_controller parameters:

# ...
from generate_parameter_module_example.admittance_parameters import admittance_controller
# ...
class TestParamsConsistency(unittest.TestCase):
#...
    def setUp(self):
        # ...
        self.listener = admittance_controller.ParamListener(self.node)

To run the tests locally, you need to build with tests enabled:
colcon build --symlink-install --cmake-args -DBUILD_TESTING=ON

Them run the tests:
colcon test --event-handlers console_start_end+ console_cohesion+

To run the precommit tests you can use:
pre-commit run --all-files

Or install them:
pre-commit install

Copy link
Copy Markdown
Contributor

@Mat198 Mat198 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The consistency test is broken as stated in the previous comment.

@alexnavtt
Copy link
Copy Markdown
Author

Alright, I've added tests for both the problem that I was seeing the shared state in maps, and the problem that @Mat198 was seeing with shared state across instances:

def test_params_do_not_share_state(self):
    params1 = self.listener.get_params()
    params1.pid.rate = 1.0
    params2 = self.listener.get_params()
    params2.pid.rate = 2.0
    self.assertNotEqual(params1.pid.rate, params2.pid.rate)
    self.node.set_parameters([Parameter('pid.rate', value='3.0')])
    params2 = self.listener.get_params()
    self.assertNotEqual(params1.pid.rate, params2.pid.rate)

def test_maps_do_not_share_state(self):
    self.node.set_parameters(
        [
            Parameter(
                'nested_map_struct.A.nested_struct.nested_struct_field',
                value='valueA',
            ),
            Parameter(
                'nested_map_struct.B.nested_struct.nested_struct_field',
                value='valueB',
            ),
        ]
    )
    params = self.listener.get_params()
    self.assertNotEqual(
        params.nested_map_struct.get_entry('A').nested_struct.nested_struct_field,
        params.nested_map_struct.get_entry('B').nested_struct.nested_struct_field,
    )

This is the result on main:
image

And this is the result with the patch:
image

Copy link
Copy Markdown
Contributor

@Mat198 Mat198 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Great work, @alexnavtt! LGTM

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants