diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 4bf346d7d3..53d58af41c 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -284,7 +284,7 @@ class Executor })); } // Use the number of subscriptions to allocate memory in the handles - unsigned long number_of_subscriptions = subs.size(); + size_t number_of_subscriptions = subs.size(); rmw_subscriptions_t subscriber_handles; subscriber_handles.subscriber_count = number_of_subscriptions; // TODO(wjwwood): Avoid redundant malloc's @@ -303,7 +303,7 @@ class Executor } // Use the number of services to allocate memory in the handles - unsigned long number_of_services = services.size(); + size_t number_of_services = services.size(); rmw_services_t service_handles; service_handles.service_count = number_of_services; service_handles.services = @@ -321,7 +321,7 @@ class Executor } // Use the number of clients to allocate memory in the handles - unsigned long number_of_clients = clients.size(); + size_t number_of_clients = clients.size(); rmw_clients_t client_handles; client_handles.client_count = number_of_clients; client_handles.clients = @@ -341,8 +341,7 @@ class Executor // Use the number of guard conditions to allocate memory in the handles // Add 2 to the number for the ctrl-c guard cond and the executor's size_t start_of_timer_guard_conds = 2; - unsigned long number_of_guard_conds = - timers.size() + start_of_timer_guard_conds; + size_t number_of_guard_conds = timers.size() + start_of_timer_guard_conds; rmw_guard_conditions_t guard_condition_handles; guard_condition_handles.guard_condition_count = number_of_guard_conds; guard_condition_handles.guard_conditions =