Skip to content

Conversation

@haumarco
Copy link
Contributor

This PR is part of the split up of #26151

Solved Problem

The DDS bridge could only map single-instance uORB topics to DDS topics. This prevented external systems from publishing multiple instances of the same message type (e.g., multiple positioning sources) through separate DDS topics.

Solution

This PR adds multi-instance uORB topic support to the DDS bridge:

  1. Topic mapping configuration

    • New instances field to specify number of topic instances
    • Suffix pattern support (e.g., _A, _B, _C, _D) for DDS topic names
    • Backward compatible: single-instance topics work as before
  2. Code generation updates

    • Generates PublicationMulti arrays for multi-instance subscriptions
    • Maps multiple DDS topics to single uORB topic with instance field
    • Example: /fmu/in/aux_global_position_Aaux_global_position instance 0

Changelog Entry

For release notes:

Feature: Multi-instance uORB topic support in DDS bridge
- New dds_topics.yaml syntax: `instances: 4` with `suffix: ["_A", "_B", "_C", "_D"]`
- Enables external systems to publish multiple instances of same message type

Test coverage

Tested with aux_global_position topic configured for 4 instances.

Additional Notes

This is a prerequisite for multi-instance AGP fusion in EKF2. The same pattern can be extended to other multi-instance topics (e.g., distance sensors, external odometry sources).

Copy link
Member

@beniaminopozzan beniaminopozzan left a comment

Choose a reason for hiding this comment

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

Thanks for splitting them up @haumarco !

This looks good to me but I'll approve once #26306 is merged

Add dedicated message type for auxiliary global position sources.
Separates aux_global_position from VehicleGlobalPosition topic.
Includes source field for identifying position source type.
Add per-instance parameters (ID, CTRL, MODE, DELAY, NOISE, GATE)
for up to 4 auxiliary global position sources.
- Refactor aux_global_position into manager + per-source AgpSource class
- Support up to 4 independent AGP sources simultaneously
- Dynamic parameter lookup without boilerplate switch statements
- Per-source state tracking and fusion logic
- Update simulator to use new AuxGlobalPosition message
Enable DDS bridge to handle multi-instance uORB topics by mapping
multiple topic instances to a single DDS topic with instance field.
@github-actions
Copy link

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 2016 byte (0.1 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.1% +1.95Ki  +0.1% +1.95Ki    .text
  [NEW] +1.29Ki  [NEW] +1.29Ki    AgpSource::update()
  +0.3%    +576  +0.3%    +576    [section .text]
  [NEW]    +396  [NEW]    +396    AgpSource::checkAndBufferData()
  [NEW]    +316  [NEW]    +316    ucdr_deserialize_aux_global_position()
  [NEW]    +264  [NEW]    +264    AgpSource::isResetAllowed()
  [NEW]    +240  [NEW]    +240    AuxGlobalPosition::touchActiveAgpParams()
 -99.4%    +236 -99.4%    +236    [36 Others]
  [NEW]    +180  [NEW]    +180    AgpSource::AgpSource()
  [NEW]    +180  [NEW]    +180    AuxGlobalPosition::mapSensorIdToSlot()
  +8.7%    +176  +8.7%    +176    RcvTopicsPubs::init()
  +1.0%    +152  +1.0%    +152    px4::parameters
  +0.1%    +148  +0.1%    +148    g_cromfs_image
  [NEW]     +96  [NEW]     +96    AuxGlobalPosition::getAgpParamFloat()
  [NEW]     +84  [NEW]     +84    AuxGlobalPosition::getAgpParamInt32()
  -5.7%     -88  -5.7%     -88    EKF2::~EKF2()
 -23.5%     -92 -23.5%     -92    Ekf::updateParameters()
  -1.7%    -124  -1.7%    -124    on_topic_update()
  [DEL]    -184  [DEL]    -184    AuxGlobalPosition::isResetAllowed()
 -55.2%    -192 -55.2%    -192    Ekf::~Ekf()
 -76.4%    -272 -76.4%    -272    AuxGlobalPosition::AuxGlobalPosition()
  [DEL] -1.38Ki  [DEL] -1.38Ki    AuxGlobalPosition::update()
+0.1%     +16  +0.1%     +16    .ramfunc
  +1.7%      +4  +1.7%      +4    param_get
  +1.4%      +4  +1.4%      +4    param_get_default_value
   +33%      +4   +33%      +4    param_get_index
  +9.1%      +4  +9.1%      +4    param_get_system_default_value
   +14%      +1   +14%      +1    __dq_rem_veneer
 -12.5%      -1 -12.5%      -1    ___ZN3Ekf23constrainStateVariancesEv_veneer
+0.0%    +891  [ = ]       0    .debug_abbrev
+0.1%    +216  [ = ]       0    .debug_aranges
+0.1%    +736  [ = ]       0    .debug_frame
+0.2% +42.0Ki  [ = ]       0    .debug_info
+0.1% +4.14Ki  [ = ]       0    .debug_line
 -42.9%      -3  [ = ]       0    [Unmapped]
  +0.1% +4.14Ki  [ = ]       0    [section .debug_line]
+0.0%    +750  [ = ]       0    .debug_loclists
+0.1%    +465  [ = ]       0    .debug_rnglists
-0.1% -1.85Ki  [ = ]       0    .debug_str
+0.4%      +1  [ = ]       0    .shstrtab
+0.1%    +363  [ = ]       0    .strtab
  [NEW]     +76  [ = ]       0    AgpSource::AgpSource()
  [NEW]     +59  [ = ]       0    AgpSource::checkAndBufferData()
  [NEW]     +38  [ = ]       0    AgpSource::isResetAllowed()
  [NEW]     +51  [ = ]       0    AgpSource::update()
  [NEW]     +47  [ = ]       0    AuxGlobalPosition::getAgpParamFloat()
  [NEW]     +47  [ = ]       0    AuxGlobalPosition::getAgpParamInt32()
  [DEL]     -47  [ = ]       0    AuxGlobalPosition::isResetAllowed()
  [NEW]     +44  [ = ]       0    AuxGlobalPosition::mapSensorIdToSlot()
  [NEW]     +47  [ = ]       0    AuxGlobalPosition::touchActiveAgpParams()
  [DEL]     -60  [ = ]       0    AuxGlobalPosition::update()
  [DEL]     -43  [ = ]       0    AuxGlobalPosition::updateParamsImpl()
  +0.1%     +24  [ = ]       0    [section .strtab]
  [NEW]     +80  [ = ]       0    ucdr_deserialize_aux_global_position()
+0.1%    +384  [ = ]       0    .symtab
  [NEW]     +64  [ = ]       0    AgpSource::AgpSource()
  [NEW]     +48  [ = ]       0    AgpSource::checkAndBufferData()
  [NEW]     +48  [ = ]       0    AgpSource::isResetAllowed()
  [NEW]     +64  [ = ]       0    AgpSource::update()
  [NEW]     +64  [ = ]       0    AuxGlobalPosition::getAgpParamFloat()
  [NEW]     +48  [ = ]       0    AuxGlobalPosition::getAgpParamInt32()
  [DEL]     -16  [ = ]       0    AuxGlobalPosition::isResetAllowed()
  [NEW]     +48  [ = ]       0    AuxGlobalPosition::mapSensorIdToSlot()
  [NEW]     +48  [ = ]       0    AuxGlobalPosition::touchActiveAgpParams()
  [DEL]     -64  [ = ]       0    AuxGlobalPosition::update()
  [DEL]     -32  [ = ]       0    AuxGlobalPosition::updateParamsImpl()
 -14.3%     -16  [ = ]       0    AuxGlobalPosition::~AuxGlobalPosition()
 -33.3%     -16  [ = ]       0    ConstLayer::contains()
   +50%     +16  [ = ]       0    ConstLayer::store()
   +11%     +16  [ = ]       0    EKF2::~EKF2()
 -33.3%     -16  [ = ]       0    RcvTopicsPubs::~RcvTopicsPubs()
   +50%     +16  [ = ]       0    UxrceddsClient::deinit()
 -50.0%     -32  [ = ]       0    UxrceddsClient::init()
 -105.3%     -32  [ = ]       0    [11 Others]
  +1.2%    +144  [ = ]       0    [section .symtab]
 -33.3%     -16  [ = ]       0    ___ZN3Ekf23constrainStateVariancesEv_veneer
-18.1% -1.97Ki  [ = ]       0    [Unmapped]
+0.1% +48.0Ki  +0.1% +1.97Ki    TOTAL

px4_fmu-v6x [Total VM Diff: 1968 byte (0.1 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.1% +1.92Ki  +0.1% +1.92Ki    .text
  [NEW] +1.29Ki  [NEW] +1.29Ki    AgpSource::update()
  +0.4%    +600  +0.4%    +600    [section .text]
  [NEW]    +396  [NEW]    +396    AgpSource::checkAndBufferData()
  [NEW]    +316  [NEW]    +316    ucdr_deserialize_aux_global_position()
  [NEW]    +264  [NEW]    +264    AgpSource::isResetAllowed()
  [NEW]    +240  [NEW]    +240    AuxGlobalPosition::touchActiveAgpParams()
  [NEW]    +180  [NEW]    +180    AgpSource::AgpSource()
  [NEW]    +180  [NEW]    +180    AuxGlobalPosition::mapSensorIdToSlot()
  +8.7%    +176  +8.7%    +176    RcvTopicsPubs::init()
 -99.5%    +168 -99.5%    +168    [21 Others]
  +0.1%    +160  +0.1%    +160    g_cromfs_image
  +1.0%    +152  +1.0%    +152    px4::parameters
  [NEW]     +96  [NEW]     +96    AuxGlobalPosition::getAgpParamFloat()
  [NEW]     +84  [NEW]     +84    AuxGlobalPosition::getAgpParamInt32()
  -5.7%     -88  -5.7%     -88    EKF2::~EKF2()
 -23.5%     -92 -23.5%     -92    Ekf::updateParameters()
  -1.7%    -124  -1.7%    -124    on_topic_update()
  [DEL]    -184  [DEL]    -184    AuxGlobalPosition::isResetAllowed()
 -55.2%    -192 -55.2%    -192    Ekf::~Ekf()
 -76.4%    -272 -76.4%    -272    AuxGlobalPosition::AuxGlobalPosition()
  [DEL] -1.38Ki  [DEL] -1.38Ki    AuxGlobalPosition::update()
+0.0%    +891  [ = ]       0    .debug_abbrev
+0.1%    +216  [ = ]       0    .debug_aranges
+0.2%    +736  [ = ]       0    .debug_frame
+0.2% +40.8Ki  [ = ]       0    .debug_info
+0.1% +4.10Ki  [ = ]       0    .debug_line
  [DEL]      -7  [ = ]       0    [Unmapped]
  +0.1% +4.11Ki  [ = ]       0    [section .debug_line]
+0.0%    +772  [ = ]       0    .debug_loclists
+0.1%    +463  [ = ]       0    .debug_rnglists
  [NEW]      +2  [ = ]       0    [Unmapped]
  +0.1%    +461  [ = ]       0    [section .debug_rnglists]
-0.1% -1.83Ki  [ = ]       0    .debug_str
+0.4%      +1  [ = ]       0    .shstrtab
+0.1%    +363  [ = ]       0    .strtab
  [NEW]     +76  [ = ]       0    AgpSource::AgpSource()
  [NEW]     +59  [ = ]       0    AgpSource::checkAndBufferData()
  [NEW]     +38  [ = ]       0    AgpSource::isResetAllowed()
  [NEW]     +51  [ = ]       0    AgpSource::update()
  [NEW]     +47  [ = ]       0    AuxGlobalPosition::getAgpParamFloat()
  [NEW]     +47  [ = ]       0    AuxGlobalPosition::getAgpParamInt32()
  [DEL]     -47  [ = ]       0    AuxGlobalPosition::isResetAllowed()
  [NEW]     +44  [ = ]       0    AuxGlobalPosition::mapSensorIdToSlot()
  [NEW]     +47  [ = ]       0    AuxGlobalPosition::touchActiveAgpParams()
  [DEL]     -60  [ = ]       0    AuxGlobalPosition::update()
  [DEL]     -43  [ = ]       0    AuxGlobalPosition::updateParamsImpl()
  +0.1%     +24  [ = ]       0    [section .strtab]
  [NEW]     +80  [ = ]       0    ucdr_deserialize_aux_global_position()
+0.1%    +384  [ = ]       0    .symtab
  [NEW]     +64  [ = ]       0    AgpSource::AgpSource()
  [NEW]     +48  [ = ]       0    AgpSource::checkAndBufferData()
  [NEW]     +48  [ = ]       0    AgpSource::isResetAllowed()
  [NEW]     +64  [ = ]       0    AgpSource::update()
  [NEW]     +64  [ = ]       0    AuxGlobalPosition::getAgpParamFloat()
  [NEW]     +48  [ = ]       0    AuxGlobalPosition::getAgpParamInt32()
  [DEL]     -16  [ = ]       0    AuxGlobalPosition::isResetAllowed()
  [NEW]     +48  [ = ]       0    AuxGlobalPosition::mapSensorIdToSlot()
  [NEW]     +48  [ = ]       0    AuxGlobalPosition::touchActiveAgpParams()
  [DEL]     -64  [ = ]       0    AuxGlobalPosition::update()
  [DEL]     -32  [ = ]       0    AuxGlobalPosition::updateParamsImpl()
 -14.3%     -16  [ = ]       0    AuxGlobalPosition::~AuxGlobalPosition()
   +11%     +16  [ = ]       0    EKF2::~EKF2()
 -33.3%     -16  [ = ]       0    RcvTopicsPubs::~RcvTopicsPubs()
   +50%     +16  [ = ]       0    UxrceddsClient::deinit()
 -50.0%     -32  [ = ]       0    UxrceddsClient::init()
  +0.7%     +80  [ = ]       0    [section .symtab]
   +50%     +16  [ = ]       0    __orb_aux_global_position
 -33.3%     -16  [ = ]       0    estimator::State::quat_nominal
  [NEW]     +16  [ = ]       0    ucdr_deserialize_aux_global_position()
 +49% +2.08Ki  [ = ]       0    [Unmapped]
+0.1% +50.8Ki  +0.1% +1.92Ki    TOTAL

Updated: 2026-01-21T16:40:49

}

ekf.resetAidSourceStatusZeroInnovation(aid_src);
int32_t AuxGlobalPosition::getModeParam(int instance)
Copy link
Member

Choose a reason for hiding this comment

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

From what I see these can be called frequently and thus should be cached (specifically the param_get(param_find calls).

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