time.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 #ifdef ROS2 /**********************************************************************************************************/
6 #include <boost/math/special_functions/round.hpp>
7 #include <rclcpp/create_timer.hpp>
8 #include "rclcpp/rclcpp.hpp"
9 
10 namespace ensenso
11 {
12 namespace ros
13 {
14 using Rate = ::rclcpp::Rate;
15 using Time = ::rclcpp::Time;
16 using Timer = ::rclcpp::TimerBase::SharedPtr;
17 
18 inline ::rclcpp::Duration durationFromSeconds(double d)
19 {
20  return ::rclcpp::Duration(::std::chrono::duration<double>(d));
21 }
22 
23 inline Time now(ensenso::ros::NodeHandle const& nh)
24 {
25  return nh->node()->get_clock()->now();
26 }
27 
28 inline void sleep(double t)
29 {
30  rclcpp::Rate loop_rate(t);
31  loop_rate.sleep();
32 }
33 
34 inline Time timeFromSeconds(double t)
35 {
36  // Implementation source: http://docs.ros.org/en/latest/api/rostime/html/impl_2time_8h_source.html#l00076
37  int64_t sec64 = static_cast<int64_t>(floor(t));
38  if (sec64 < 0 || sec64 > ::std::numeric_limits<uint32_t>::max())
39  throw ::std::runtime_error("Time is out of dual 32-bit range");
40  uint32_t sec = static_cast<uint32_t>(sec64);
41  uint32_t nsec = static_cast<uint32_t>(boost::math::round((t - sec) * 1e9));
42  // avoid rounding errors
43  sec += (nsec / 1000000000ul);
44  nsec %= 1000000000ul;
45  return ::rclcpp::Time(sec, nsec);
46 }
47 } // namespace ros
48 } // namespace ensenso
49 
50 #define TIMER_CALLBACK_DECLARATION_ARGS
51 
52 #define TIMER_CALLBACK_DEFINITION_ARGS
53 
54 #define CREATE_TIMER(nh, duration_in_seconds, callback_ref, object_ptr) \
55  ::rclcpp::create_timer(nh->get_base_interface(), nh->get_timers_interface(), nh->get_clock_interface()->get_clock(), \
56  ensenso::ros::durationFromSeconds(duration_in_seconds), \
57  ensenso::std::bind(callback_ref, object_ptr));
58 
59 #else /***ROS1*********************************************************************************************************/
60 #include <ros/ros.h>
61 
62 namespace ensenso
63 {
64 namespace ros
65 {
66 using Rate = ::ros::Rate;
67 using Time = ::ros::Time;
70 
71 inline ::ros::Duration durationFromSeconds(double d)
72 {
73  return ::ros::Duration(d);
74 }
75 
77 {
78  // (void)nh;
80 }
81 
82 inline void sleep(double t)
83 {
85 }
86 
88 {
90 }
91 } // namespace ros
92 } // namespace ensenso
93 
94 #define TIMER_CALLBACK_DECLARATION_ARGS ensenso::ros::TimerEvent const& timerEvent = ensenso::ros::TimerEvent()
95 
96 #define TIMER_CALLBACK_DEFINITION_ARGS ensenso::ros::TimerEvent const& timerEvent
97 
98 #define CREATE_TIMER(nh, duration_in_seconds, callback_ref, object_ptr) \
99  nh.createTimer(ensenso::ros::durationFromSeconds(duration_in_seconds), callback_ref, object_ptr)
100 #endif
ensenso::ros::timeFromSeconds
inline ::ros::Time timeFromSeconds(double t)
Definition: time.h:87
ros
ros.h
ensenso
Definition: point_cloud_utilities.h:5
ensenso::ros::Timer
::ros::Timer Timer
Definition: time.h:68
ensenso::ros::NodeHandle
::ros::NodeHandle NodeHandle
Definition: node.h:215
ensenso::ros::Time
::ros::Time Time
Definition: time.h:67
d
d
ensenso::ros::TimerEvent
::ros::TimerEvent TimerEvent
Definition: time.h:69
ensenso::ros::now
inline ::ros::Time now(ensenso::ros::NodeHandle const &nh)
Definition: time.h:76
ensenso::ros::Rate
::ros::Rate Rate
Definition: time.h:66
ros::Duration::sleep
bool sleep() const
ensenso::ros::durationFromSeconds
inline ::ros::Duration durationFromSeconds(double d)
Definition: time.h:71
ros::Duration
node_handle.h
t
geometry_msgs::TransformStamped t
ensenso::ros::sleep
void sleep(double t)
Definition: time.h:82
ros::Time::now
static Time now()


ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46