mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_DDS: make all subscriber QoS best effort reliability
Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
840f4b142d
commit
88926a38cf
@ -207,7 +207,7 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||||||
.type_name = "sensor_msgs::msg::dds_::Joy_",
|
.type_name = "sensor_msgs::msg::dds_::Joy_",
|
||||||
.qos = {
|
.qos = {
|
||||||
.durability = UXR_DURABILITY_VOLATILE,
|
.durability = UXR_DURABILITY_VOLATILE,
|
||||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||||
.history = UXR_HISTORY_KEEP_LAST,
|
.history = UXR_HISTORY_KEEP_LAST,
|
||||||
.depth = 5,
|
.depth = 5,
|
||||||
},
|
},
|
||||||
@ -223,7 +223,7 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||||||
.type_name = "tf2_msgs::msg::dds_::TFMessage_",
|
.type_name = "tf2_msgs::msg::dds_::TFMessage_",
|
||||||
.qos = {
|
.qos = {
|
||||||
.durability = UXR_DURABILITY_VOLATILE,
|
.durability = UXR_DURABILITY_VOLATILE,
|
||||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||||
.history = UXR_HISTORY_KEEP_LAST,
|
.history = UXR_HISTORY_KEEP_LAST,
|
||||||
.depth = 5,
|
.depth = 5,
|
||||||
},
|
},
|
||||||
@ -239,7 +239,7 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||||||
.type_name = "geometry_msgs::msg::dds_::TwistStamped_",
|
.type_name = "geometry_msgs::msg::dds_::TwistStamped_",
|
||||||
.qos = {
|
.qos = {
|
||||||
.durability = UXR_DURABILITY_VOLATILE,
|
.durability = UXR_DURABILITY_VOLATILE,
|
||||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||||
.history = UXR_HISTORY_KEEP_LAST,
|
.history = UXR_HISTORY_KEEP_LAST,
|
||||||
.depth = 5,
|
.depth = 5,
|
||||||
},
|
},
|
||||||
@ -255,7 +255,7 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||||||
.type_name = "ardupilot_msgs::msg::dds_::GlobalPosition_",
|
.type_name = "ardupilot_msgs::msg::dds_::GlobalPosition_",
|
||||||
.qos = {
|
.qos = {
|
||||||
.durability = UXR_DURABILITY_VOLATILE,
|
.durability = UXR_DURABILITY_VOLATILE,
|
||||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||||
.history = UXR_HISTORY_KEEP_LAST,
|
.history = UXR_HISTORY_KEEP_LAST,
|
||||||
.depth = 5,
|
.depth = 5,
|
||||||
},
|
},
|
||||||
|
Loading…
Reference in New Issue
Block a user