boschresearch / pcg_gazebo

Procedural Generation for Gazebo
https://boschresearch.github.io/pcg_gazebo/
Apache License 2.0
69 stars 24 forks source link

Support plugin with repeated sdf elements #139

Open srmainwaring opened 3 years ago

srmainwaring commented 3 years ago

This project is really excellent, thank you.

I would like to define sdf plugins that have repeated elements, but this is not permitted because the Plugin uses a dict to hold the tags.

https://github.com/boschresearch/pcg_gazebo/blob/72ea73861f841567537618b25a1638726f2964e6/pcg_gazebo/parsers/sdf/plugin.py#L20-L33

My use case is using pcg_gazebo to define and launch models that will be controlled by ArduPilot using the Gazebo-SITL interface and ardupilot_gazebo plugin. This plugin contains a list of <control> elements. For example:

    <plugin name="ardupilot_plugin" filename="libArduPilotPlugin.so">
        <fdm_addr>127.0.0.1</fdm_addr>
        <fdm_port_in>9002</fdm_port_in>
        <connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
        <modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
        <gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
        <imuName>imu_link::imu_sensor</imuName>

        <!-- Control / channels -->

        <!--
            SERVO1_FUNCTION 26 (Ground Steering)
            SERVO1_MIN      1000
            SERVO1_MAX      2000
            SERVO1_TRIM     1500
        -->
        <control channel="0">
            <jointName>steer_joint</jointName>
            <useForce>1</useForce>
            <multiplier>3.141592653</multiplier>
            <offset>-0.5</offset>
            <servo_min>1000</servo_min>
            <servo_max>2000</servo_max>
            <type>POSITION</type>
            <p_gain>10</p_gain>
            <i_gain>0.1</i_gain>
            <d_gain>0.02</d_gain>
            <i_max>1</i_max>
            <i_min>0</i_min>
            <cmd_max>100.0</cmd_max>
            <cmd_min>-100.0</cmd_min>
        </control>

        <!--
            SERVO3_FUNCTION 70 (Throttle)
            SERVO3_MIN      1000
            SERVO3_MAX      2000
            SERVO3_TRIM     1000
        -->
        <control channel="2">
            <jointName>motor_joint</jointName>
            <useForce>1</useForce>
            <multiplier>-800</multiplier>
            <offset>0</offset>
            <servo_min>1000</servo_min>
            <servo_max>2000</servo_max>
            <type>VELOCITY</type>
            <p_gain>0.005</p_gain>
            <i_gain>0.0</i_gain>
            <d_gain>1.0e-5</d_gain>
            <i_max>0.1</i_max>
            <i_min>0</i_min>
            <cmd_max>5.0</cmd_max>
            <cmd_min>-5.0</cmd_min>
        </control>
    </plugin>

I can create a single <control> element with

ardupilot_plugin_args = dict(
    fdm_addr='127.0.0.1',
    fdm_port_in=9002,
    connectionTimeoutMaxCount=5,
    modelXYZToAirplaneXForwardZDown=[0, 0, 0, math.pi, 0, 0],
    gazeboXYZToNED=[0, 0, 0, math.pi, 0, 0],
    imuName='imu_link::imu_sensor',
    control=dict(
            attributes=dict(
                channel='0'
            ),
            value=dict(
                jointName='steer_joint',
                useForce=True,
                multiplier=3.141592653,
                offset=-0.5,
                servo_min=1000,
                servo_max=2000,
                type='POSITION',
                p_gain=10,
                i_gain=0.1,
                d_gain=0.02,
                i_max=1,
                i_min=0,
                cmd_max=100.0,
                cmd_min=-100.0
            )
        )
)

ardupilot_plugin = create_sdf_element('plugin')
ardupilot_plugin.name = 'ardupilot_plugin'
ardupilot_plugin.filename = 'libArduPilotPlugin.so'
ardupilot_plugin.value = ardupilot_plugin_args

but can't see a way of adding additional elements without a code change.