Skip to content

Commit 0f58bb8

Browse files
authored
clang-tidy: explicit constructors (#1782)
* mark some single-argument constructors explicit that should have been Signed-off-by: William Woodall <[email protected]> * suppress clang-tidy [google-explicit-constructor] in some cases where it is a false-positive Signed-off-by: William Woodall <[email protected]> * Revert "suppress clang-tidy [google-explicit-constructor] in some cases where it is a false-positive" This reverts commit eb6bf7e. Signed-off-by: William Woodall <[email protected]>
1 parent 8b9cabf commit 0f58bb8

File tree

4 files changed

+6
-6
lines changed

4 files changed

+6
-6
lines changed

rclcpp/include/rclcpp/allocator/allocator_deleter.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ class AllocatorDeleter
4141
}
4242

4343
template<typename T>
44-
AllocatorDeleter(const AllocatorDeleter<T> & a)
44+
explicit AllocatorDeleter(const AllocatorDeleter<T> & a)
4545
{
4646
allocator_ = a.get_allocator();
4747
}

rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ class MultiThreadedExecutor : public rclcpp::Executor
5252
* \param timeout maximum time to wait
5353
*/
5454
RCLCPP_PUBLIC
55-
MultiThreadedExecutor(
55+
explicit MultiThreadedExecutor(
5656
const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions(),
5757
size_t number_of_threads = 0,
5858
bool yield_before_execute = false,

rclcpp/include/rclcpp/parameter_client.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ class AsyncParametersClient
7979
* \param[in] group (optional) The async parameter client will be added to this callback group.
8080
*/
8181
template<typename NodeT>
82-
AsyncParametersClient(
82+
explicit AsyncParametersClient(
8383
const std::shared_ptr<NodeT> node,
8484
const std::string & remote_node_name = "",
8585
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
@@ -102,7 +102,7 @@ class AsyncParametersClient
102102
* \param[in] group (optional) The async parameter client will be added to this callback group.
103103
*/
104104
template<typename NodeT>
105-
AsyncParametersClient(
105+
explicit AsyncParametersClient(
106106
NodeT * node,
107107
const std::string & remote_node_name = "",
108108
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
@@ -333,7 +333,7 @@ class SyncParametersClient
333333
{}
334334

335335
template<typename NodeT>
336-
SyncParametersClient(
336+
explicit SyncParametersClient(
337337
NodeT * node,
338338
const std::string & remote_node_name = "",
339339
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)

rclcpp/include/rclcpp/parameter_event_handler.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -165,7 +165,7 @@ class ParameterEventHandler
165165
* \param[in] qos The QoS settings to use for any subscriptions.
166166
*/
167167
template<typename NodeT>
168-
ParameterEventHandler(
168+
explicit ParameterEventHandler(
169169
NodeT node,
170170
const rclcpp::QoS & qos =
171171
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)))

0 commit comments

Comments
 (0)