@@ -31,14 +31,14 @@ use rosidl_runtime_rs::{Action, Message};
3131
3232use crate :: {
3333 rcl_bindings:: * , ActionClient , ActionClientOptions , ActionClientState , ActionGoalReceiver ,
34- ActionServer , ActionServerOptions , ActionServerState , Client , ClientOptions , ClientState ,
35- Clock , ContextHandle , ExecutorCommands , IntoAsyncServiceCallback ,
34+ ActionServer , ActionServerOptions , ActionServerState , AnyTimerCallback , Client , ClientOptions ,
35+ ClientState , Clock , ContextHandle , ExecutorCommands , IntoAsyncServiceCallback ,
3636 IntoAsyncSubscriptionCallback , IntoNodeServiceCallback , IntoNodeSubscriptionCallback ,
37- LogParams , Logger , ParameterBuilder , ParameterInterface , ParameterVariant , Parameters , Promise ,
38- Publisher , PublisherOptions , PublisherState , RclrsError , RequestedGoal , Service ,
39- ServiceOptions , ServiceState , Subscription , SubscriptionOptions , SubscriptionState ,
40- TerminatedGoal , TimeSource , ToLogParams , Worker , WorkerOptions , WorkerState ,
41- ENTITY_LIFECYCLE_MUTEX ,
37+ IntoNodeTimerOneshotCallback , IntoNodeTimerRepeatingCallback , IntoTimerOptions , LogParams ,
38+ Logger , ParameterBuilder , ParameterInterface , ParameterVariant , Parameters , Promise , Publisher ,
39+ PublisherOptions , PublisherState , RclrsError , RequestedGoal , Service , ServiceOptions ,
40+ ServiceState , Subscription , SubscriptionOptions , SubscriptionState , TerminatedGoal , TimeSource ,
41+ Timer , TimerState , ToLogParams , Worker , WorkerOptions , WorkerState , ENTITY_LIFECYCLE_MUTEX ,
4242} ;
4343
4444/// A processing unit that can communicate with other nodes. See the API of
@@ -946,6 +946,229 @@ impl NodeState {
946946 )
947947 }
948948
949+ /// Create a [`Timer`] with a repeating callback.
950+ ///
951+ /// This has similar behavior to `rclcpp::Node::create_timer` by periodically
952+ /// triggering the callback of the timer. For a one-shot timer alternative,
953+ /// see [`NodeState::create_timer_oneshot`].
954+ ///
955+ /// See also:
956+ /// * [`Self::create_timer_oneshot`]
957+ /// * [`Self::create_timer_inert`]
958+ ///
959+ /// # Behavior
960+ ///
961+ /// While the callback of this timer is running, no other callbacks associated
962+ /// with this node will be able to run. This is in contrast to callbacks given
963+ /// to [`Self::create_subscription`] which can run multiple times in parallel.
964+ ///
965+ /// Since the callback of this timer may block other callbacks from being able
966+ /// to run, it is strongly recommended to ensure that the callback returns
967+ /// quickly. If the callback needs to trigger long-running behavior then you
968+ /// can consider using [`std::thread::spawn`], or for async behaviors you can
969+ /// capture an [`ExecutorCommands`] in your callback and use [`ExecutorCommands::run`]
970+ /// to issue a task for the executor to run in its async task pool.
971+ ///
972+ /// Since these callbacks are blocking, you may use [`FnMut`] here instead of
973+ /// being limited to [`Fn`].
974+ ///
975+ /// # Timer Options
976+ ///
977+ /// You can choose both
978+ /// 1. a timer period (duration) which determines how often the callback is triggered
979+ /// 2. a clock to measure the passage of time
980+ ///
981+ /// Both of these choices are expressed by [`TimerOptions`][1].
982+ ///
983+ /// By default the steady clock time will be used, but you could choose
984+ /// node time instead if you want the timer to automatically use simulated
985+ /// time when running as part of a simulation:
986+ /// ```
987+ /// # use rclrs::*;
988+ /// # let executor = Context::default().create_basic_executor();
989+ /// # let node = executor.create_node("my_node").unwrap();
990+ /// use std::time::Duration;
991+ ///
992+ /// let timer = node.create_timer_repeating(
993+ /// TimerOptions::new(Duration::from_secs(1))
994+ /// .node_time(),
995+ /// || {
996+ /// println!("Triggering once each simulated second");
997+ /// },
998+ /// )?;
999+ /// # Ok::<(), RclrsError>(())
1000+ /// ```
1001+ ///
1002+ /// If there is a specific manually-driven clock you want to use, you can
1003+ /// also select that:
1004+ /// ```
1005+ /// # use rclrs::*;
1006+ /// # let executor = Context::default().create_basic_executor();
1007+ /// # let node = executor.create_node("my_node").unwrap();
1008+ /// use std::time::Duration;
1009+ ///
1010+ /// let (my_clock, my_source) = Clock::with_source();
1011+ ///
1012+ /// let timer = node.create_timer_repeating(
1013+ /// TimerOptions::new(Duration::from_secs(1))
1014+ /// .clock(&my_clock),
1015+ /// || {
1016+ /// println!("Triggering once each simulated second");
1017+ /// },
1018+ /// )?;
1019+ ///
1020+ /// my_source.set_ros_time_override(1_500_000_000);
1021+ /// # Ok::<(), RclrsError>(())
1022+ /// ```
1023+ ///
1024+ /// If you are okay with the default choice of clock (steady clock) then you
1025+ /// can choose to simply pass a duration in as the options:
1026+ /// ```
1027+ /// # use rclrs::*;
1028+ /// # let executor = Context::default().create_basic_executor();
1029+ /// # let node = executor.create_node("my_node").unwrap();
1030+ /// use std::time::Duration;
1031+ ///
1032+ /// let timer = node.create_timer_repeating(
1033+ /// Duration::from_secs(1),
1034+ /// || {
1035+ /// println!("Triggering per steady clock second");
1036+ /// },
1037+ /// )?;
1038+ /// # Ok::<(), RclrsError>(())
1039+ /// ```
1040+ ///
1041+ /// # Node Timer Repeating Callbacks
1042+ ///
1043+ /// Node Timer repeating callbacks support three signatures:
1044+ /// - <code>[FnMut] ()</code>
1045+ /// - <code>[FnMut] ([Time][2])</code>
1046+ /// - <code>[FnMut] (&[Timer])</code>
1047+ ///
1048+ /// You can choose to receive the current time when the callback is being
1049+ /// triggered.
1050+ ///
1051+ /// Or instead of the current time, you can get a borrow of the [`Timer`]
1052+ /// itself, that way if you need to access it from inside the callback, you
1053+ /// do not need to worry about capturing a [`Weak`][3] and then locking it.
1054+ /// This is useful if you need to change the callback of the timer from inside
1055+ /// the callback of the timer.
1056+ ///
1057+ /// For an [`FnOnce`] instead of [`FnMut`], use [`Self::create_timer_oneshot`].
1058+ ///
1059+ /// [1]: crate::TimerOptions
1060+ /// [2]: crate::Time
1061+ /// [3]: std::sync::Weak
1062+ pub fn create_timer_repeating < ' a , Args > (
1063+ self : & Arc < Self > ,
1064+ options : impl IntoTimerOptions < ' a > ,
1065+ callback : impl IntoNodeTimerRepeatingCallback < Args > ,
1066+ ) -> Result < Timer , RclrsError > {
1067+ self . create_timer_internal ( options, callback. into_node_timer_repeating_callback ( ) )
1068+ }
1069+
1070+ /// Create a [`Timer`] whose callback will be triggered once after the period
1071+ /// of the timer has elapsed. After that you will need to use
1072+ /// [`TimerState::set_repeating`] or [`TimerState::set_oneshot`] or else
1073+ /// nothing will happen the following times that the `Timer` elapses.
1074+ ///
1075+ /// This does not have an equivalent in `rclcpp`.
1076+ ///
1077+ /// See also:
1078+ /// * [`Self::create_timer_repeating`]
1079+ /// * [`Self::create_timer_inert`]
1080+ ///
1081+ /// # Behavior
1082+ ///
1083+ /// While the callback of this timer is running, no other callbacks associated
1084+ /// with this node will be able to run. This is in contrast to callbacks given
1085+ /// to [`Self::create_subscription`] which can run multiple times in parallel.
1086+ ///
1087+ /// Since the callback of this timer may block other callbacks from being able
1088+ /// to run, it is strongly recommended to ensure that the callback returns
1089+ /// quickly. If the callback needs to trigger long-running behavior then you
1090+ /// can consider using [`std::thread::spawn`], or for async behaviors you can
1091+ /// capture an [`ExecutorCommands`] in your callback and use [`ExecutorCommands::run`]
1092+ /// to issue a task for the executor to run in its async task pool.
1093+ ///
1094+ /// Since these callbacks will only be triggered once, you may use [`FnOnce`] here.
1095+ ///
1096+ /// # Timer Options
1097+ ///
1098+ /// See [`NodeSate::create_timer_repeating`][3] for examples of setting the
1099+ /// timer options.
1100+ ///
1101+ /// # Node Timer Oneshot Callbacks
1102+ ///
1103+ /// Node Timer OneShot callbacks support three signatures:
1104+ /// - <code>[FnOnce] ()</code>
1105+ /// - <code>[FnOnce] ([Time][2])</code>
1106+ /// - <code>[FnOnce] (&[Timer])</code>
1107+ ///
1108+ /// You can choose to receive the current time when the callback is being
1109+ /// triggered.
1110+ ///
1111+ /// Or instead of the current time, you can get a borrow of the [`Timer`]
1112+ /// itself, that way if you need to access it from inside the callback, you
1113+ /// do not need to worry about capturing a [`Weak`][3] and then locking it.
1114+ /// This is useful if you need to change the callback of the timer from inside
1115+ /// the callback of the timer.
1116+ ///
1117+ /// [2]: crate::Time
1118+ /// [3]: std::sync::Weak
1119+ pub fn create_timer_oneshot < ' a , Args > (
1120+ self : & Arc < Self > ,
1121+ options : impl IntoTimerOptions < ' a > ,
1122+ callback : impl IntoNodeTimerOneshotCallback < Args > ,
1123+ ) -> Result < Timer , RclrsError > {
1124+ self . create_timer_internal ( options, callback. into_node_timer_oneshot_callback ( ) )
1125+ }
1126+
1127+ /// Create a [`Timer`] without a callback. Nothing will happen when this
1128+ /// `Timer` elapses until you use [`TimerState::set_repeating`] or
1129+ /// [`TimerState::set_oneshot`].
1130+ ///
1131+ /// This function is not usually what you want. An inert timer is usually
1132+ /// just a follow-up state to a oneshot timer which is waiting to be given
1133+ /// a new callback to run. However, you could use this method to declare a
1134+ /// timer whose callbacks you will start to feed in at a later.
1135+ ///
1136+ /// There is no equivalent to this function in `rclcpp`.
1137+ ///
1138+ /// See also:
1139+ /// * [`Self::create_timer_repeating`]
1140+ /// * [`Self::create_timer_oneshot`]
1141+ pub fn create_timer_inert < ' a > (
1142+ self : & Arc < Self > ,
1143+ options : impl IntoTimerOptions < ' a > ,
1144+ ) -> Result < Timer , RclrsError > {
1145+ self . create_timer_internal ( options, AnyTimerCallback :: Inert )
1146+ }
1147+
1148+ /// Used internally to create any kind of [`Timer`].
1149+ ///
1150+ /// Downstream users should instead use:
1151+ /// * [`Self::create_timer_repeating`]
1152+ /// * [`Self::create_timer_oneshot`]
1153+ /// * [`Self::create_timer_inert`]
1154+ fn create_timer_internal < ' a > (
1155+ self : & Arc < Self > ,
1156+ options : impl IntoTimerOptions < ' a > ,
1157+ callback : AnyTimerCallback < Node > ,
1158+ ) -> Result < Timer , RclrsError > {
1159+ let options = options. into_timer_options ( ) ;
1160+ let clock = options. clock . as_clock ( self ) ;
1161+ let node = options. clock . is_node_time ( ) . then ( || Arc :: clone ( self ) ) ;
1162+ TimerState :: create (
1163+ options. period ,
1164+ clock,
1165+ callback,
1166+ self . commands . async_worker_commands ( ) ,
1167+ & self . handle . context_handle ,
1168+ node,
1169+ )
1170+ }
1171+
9491172 /// Returns the ROS domain ID that the node is using.
9501173 ///
9511174 /// The domain ID controls which nodes can send messages to each other, see the [ROS 2 concept article][1].
0 commit comments