mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_DDS: Switch NavSatFix topic to sensor data QOS
* Change Reliability to BEST_EFFORT * Change Durability to VOLATILE * Change to smaller queue size on NavSatFix QOS
This commit is contained in:
parent
caa77ccba8
commit
ffed6e0f26
@ -35,15 +35,18 @@
|
||||
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>20</depth>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="navsatfix0__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>RELIABLE</kind>
|
||||
<kind>BEST_EFFORT</kind>
|
||||
</reliability>
|
||||
<durability>
|
||||
<kind>VOLATILE</kind>
|
||||
</durability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
@ -51,7 +54,7 @@
|
||||
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>20</depth>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
|
Loading…
Reference in New Issue
Block a user