Skip to content

Commit

Permalink
Another try at Windows annotations.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <clalancette@gmail.com>
  • Loading branch information
clalancette committed Aug 30, 2023
1 parent 6354c68 commit bff4fd0
Showing 1 changed file with 25 additions and 3 deletions.
28 changes: 25 additions & 3 deletions rclcpp/include/rclcpp/rate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,19 @@ class RateBase
public:
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(RateBase)

RCLCPP_PUBLIC
virtual ~RateBase() {}

RCLCPP_PUBLIC
virtual bool sleep() = 0;

RCLCPP_PUBLIC
[[deprecated("use get_type() instead")]] virtual bool is_steady() const = 0;

RCLCPP_PUBLIC
virtual rcl_clock_type_t get_type() const = 0;

RCLCPP_PUBLIC
virtual void reset() = 0;
};

Expand Down Expand Up @@ -120,32 +129,39 @@ class [[deprecated("use rclcpp::Rate class instead of GenericRate")]] GenericRat
std::chrono::time_point<Clock, ClockDurationNano> last_interval_;
};

class RCLCPP_PUBLIC Rate : public RateBase
class Rate : public RateBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(Rate)

RCLCPP_PUBLIC
explicit Rate(
const double rate,
Clock::SharedPtr clock = std::make_shared<Clock>(RCL_SYSTEM_TIME));

RCLCPP_PUBLIC
explicit Rate(
const Duration & period,
Clock::SharedPtr clock = std::make_shared<Clock>(RCL_SYSTEM_TIME));

RCLCPP_PUBLIC
virtual bool
sleep();

RCLCPP_PUBLIC
[[deprecated("use get_type() instead")]]
virtual bool
is_steady() const;

RCLCPP_PUBLIC
virtual rcl_clock_type_t
get_type() const;

RCLCPP_PUBLIC
virtual void
reset();

RCLCPP_PUBLIC
Duration
period() const;

Expand All @@ -157,17 +173,23 @@ class RCLCPP_PUBLIC Rate : public RateBase
Time last_interval_;
};

class RCLCPP_PUBLIC WallRate : public Rate
class WallRate : public Rate
{
public:
RCLCPP_PUBLIC
explicit WallRate(const double rate);

RCLCPP_PUBLIC
explicit WallRate(const Duration & period);
};

class RCLCPP_PUBLIC ROSRate : public Rate
class ROSRate : public Rate
{
public:
RCLCPP_PUBLIC
explicit ROSRate(const double rate);

RCLCPP_PUBLIC
explicit ROSRate(const Duration & period);
};

Expand Down

0 comments on commit bff4fd0

Please sign in to comment.