diff --git a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp index 7f748bc..d8d9d49 100644 --- a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp @@ -58,11 +58,11 @@ public: std::vector threads; { std::lock_guard wait_lock(wait_mutex_); - size_t thread_id = 1; + size_t thread_id_ = 1; for (size_t i = number_of_threads_; i > 0; --i) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); - auto func = std::bind(&MultiThreadedExecutor::run, this, thread_id++); + auto func = std::bind(&MultiThreadedExecutor::run, this, thread_id_++); threads.emplace_back(func); } } diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index 72ca557..d4004fd 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -27,21 +27,21 @@ namespace rclcpp { -constexpr std::chrono::seconds operator "" _s(unsigned long long s) +const std::chrono::seconds operator "" _s(unsigned long long s) { return std::chrono::seconds(s); } -constexpr std::chrono::duration operator "" _s(long double s) +const std::chrono::duration operator "" _s(long double s) { return std::chrono::duration(s); } -constexpr std::chrono::nanoseconds +const std::chrono::nanoseconds operator "" _ns(unsigned long long ns) { return std::chrono::nanoseconds(ns); } -constexpr std::chrono::duration +const std::chrono::duration operator "" _ns(long double ns) { return std::chrono::duration(ns);