diff --git a/common/component_interface_specs/include/component_interface_specs/vehicle.hpp b/common/component_interface_specs/include/component_interface_specs/vehicle.hpp index e7ce2c5212a25..68c7c9c2cd606 100644 --- a/common/component_interface_specs/include/component_interface_specs/vehicle.hpp +++ b/common/component_interface_specs/include/component_interface_specs/vehicle.hpp @@ -92,7 +92,7 @@ struct DoorStatus static constexpr char name[] = "/vehicle/doors/status"; static constexpr size_t depth = 1; static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; - static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; } // namespace vehicle_interface diff --git a/simulator/vehicle_door_simulator/src/dummy_doors.cpp b/simulator/vehicle_door_simulator/src/dummy_doors.cpp index b78ca9973e7e1..cad0aa721dc73 100644 --- a/simulator/vehicle_door_simulator/src/dummy_doors.cpp +++ b/simulator/vehicle_door_simulator/src/dummy_doors.cpp @@ -29,7 +29,8 @@ DummyDoors::DummyDoors() : Node("dummy_doors") srv_layout_ = create_service( "~/doors/layout", std::bind(&DummyDoors::on_layout, this, _1, _2)); - pub_status_ = create_publisher("~/doors/status", rclcpp::QoS(1)); + pub_status_ = + create_publisher("~/doors/status", rclcpp::QoS(1).transient_local()); const auto period = rclcpp::Rate(5.0).period(); timer_ = rclcpp::create_timer(this, get_clock(), period, [this]() { on_timer(); });