Skip to content

Commit 53eed44

Browse files
QoSInitialization::from_rmw does not validate invalid history policy … (backport #2841) (#2844)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]> Co-authored-by: Alejandro Hernández Cordero <[email protected]>
1 parent b6cd839 commit 53eed44

File tree

2 files changed

+15
-1
lines changed

2 files changed

+15
-1
lines changed

rclcpp/src/rclcpp/qos.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,8 +56,10 @@ QoSInitialization::from_rmw(const rmw_qos_profile_t & rmw_qos)
5656
case RMW_QOS_POLICY_HISTORY_KEEP_LAST:
5757
case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT:
5858
case RMW_QOS_POLICY_HISTORY_UNKNOWN:
59-
default:
6059
return KeepLast(rmw_qos.depth);
60+
default:
61+
throw std::invalid_argument(
62+
"Invalid history policy enum value passed to QoSInitialization::from_rmw");
6163
}
6264
}
6365

rclcpp/test/rclcpp/test_qos.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -250,3 +250,15 @@ TEST(TestQoS, qos_check_compatible)
250250
EXPECT_FALSE(ret.reason.empty());
251251
}
252252
}
253+
254+
TEST(TestQoS, from_rmw_validity)
255+
{
256+
rmw_qos_profile_t invalid_qos;
257+
memset(&invalid_qos, 0, sizeof(invalid_qos));
258+
reinterpret_cast<uint32_t &>(invalid_qos.history) = 999;
259+
260+
EXPECT_THROW(
261+
{
262+
rclcpp::QoSInitialization::from_rmw(invalid_qos);
263+
}, std::invalid_argument);
264+
}

0 commit comments

Comments
 (0)