Skip to content

Commit 73e9bfb

Browse files
authored
QoSInitialization::from_rmw does not validate invalid history policy values, leading to silent failures (#2841)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]>
1 parent 1aaade8 commit 73e9bfb

File tree

2 files changed

+14
-1
lines changed

2 files changed

+14
-1
lines changed

rclcpp/src/rclcpp/qos.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,8 +69,10 @@ QoSInitialization::from_rmw(const rmw_qos_profile_t & rmw_qos)
6969
return KeepLast(rmw_qos.depth, false);
7070
case RMW_QOS_POLICY_HISTORY_KEEP_LAST:
7171
case RMW_QOS_POLICY_HISTORY_UNKNOWN:
72-
default:
7372
return KeepLast(rmw_qos.depth);
73+
default:
74+
throw std::invalid_argument(
75+
"Invalid history policy enum value passed to QoSInitialization::from_rmw");
7476
}
7577
}
7678

rclcpp/test/rclcpp/test_qos.cpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -272,3 +272,14 @@ TEST(TestQoS, qos_check_compatible)
272272
}
273273
}
274274
}
275+
276+
TEST(TestQoS, from_rmw_validity)
277+
{
278+
rmw_qos_profile_t invalid_qos;
279+
memset(&invalid_qos, 0, sizeof(invalid_qos));
280+
reinterpret_cast<uint32_t &>(invalid_qos.history) = 999;
281+
282+
EXPECT_THROW({
283+
rclcpp::QoSInitialization::from_rmw(invalid_qos);
284+
}, std::invalid_argument);
285+
}

0 commit comments

Comments
 (0)