Replace feature with cfg based on whether clock message is compiled
This commit is contained in:
parent
62897e2afe
commit
0fd206ca4f
|
|
@ -49,7 +49,6 @@ prettyplease = "0.2.6"
|
||||||
[features]
|
[features]
|
||||||
save-bindgen = ["r2r_rcl/save-bindgen", "r2r_msg_gen/save-bindgen", "r2r_actions/save-bindgen"]
|
save-bindgen = ["r2r_rcl/save-bindgen", "r2r_msg_gen/save-bindgen", "r2r_actions/save-bindgen"]
|
||||||
doc-only = ["r2r_common/doc-only", "r2r_rcl/doc-only", "r2r_msg_gen/doc-only", "r2r_actions/doc-only"]
|
doc-only = ["r2r_common/doc-only", "r2r_rcl/doc-only", "r2r_msg_gen/doc-only", "r2r_actions/doc-only"]
|
||||||
sim-time = []
|
|
||||||
|
|
||||||
[package.metadata.docs.rs]
|
[package.metadata.docs.rs]
|
||||||
features = ["doc-only"]
|
features = ["doc-only"]
|
||||||
|
|
@ -57,7 +56,3 @@ features = ["doc-only"]
|
||||||
[[bench]]
|
[[bench]]
|
||||||
name = "deserialization"
|
name = "deserialization"
|
||||||
harness = false
|
harness = false
|
||||||
|
|
||||||
[[example]]
|
|
||||||
name = "timer_sim_time"
|
|
||||||
required-features = ["sim-time"]
|
|
||||||
|
|
|
||||||
|
|
@ -1,10 +1,11 @@
|
||||||
use r2r::rosgraph_msgs::msg;
|
|
||||||
use r2r::ClockType::SystemTime;
|
use r2r::ClockType::SystemTime;
|
||||||
use r2r::{Clock, QosProfile};
|
use r2r::{Clock, QosProfile};
|
||||||
use std::time::Duration;
|
use std::time::Duration;
|
||||||
|
|
||||||
/// Simple publisher publishing time starting at time 0 every `SENDING_PERIOD`
|
/// Simple publisher publishing time starting at time 0 every `SENDING_PERIOD`
|
||||||
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
fn main() -> Result<(), Box<dyn std::error::Error>> {
|
fn main() -> Result<(), Box<dyn std::error::Error>> {
|
||||||
|
use r2r::rosgraph_msgs::msg;
|
||||||
let ctx = r2r::Context::create()?;
|
let ctx = r2r::Context::create()?;
|
||||||
let mut node = r2r::Node::create(ctx, "clock_publisher", "")?;
|
let mut node = r2r::Node::create(ctx, "clock_publisher", "")?;
|
||||||
let qos = QosProfile::default().keep_last(1);
|
let qos = QosProfile::default().keep_last(1);
|
||||||
|
|
@ -28,3 +29,7 @@ fn main() -> Result<(), Box<dyn std::error::Error>> {
|
||||||
std::thread::sleep(SENDING_PERIOD);
|
std::thread::sleep(SENDING_PERIOD);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#[cfg(not(r2r__rosgraph_msgs__msg__Clock))]
|
||||||
|
fn main() {
|
||||||
|
}
|
||||||
|
|
|
||||||
|
|
@ -43,7 +43,7 @@ fn main() -> Result<(), Box<dyn std::error::Error>> {
|
||||||
// Simulated time can be enabled by registering parameter handler
|
// Simulated time can be enabled by registering parameter handler
|
||||||
// and starting the program this ros param 'use_sim_time:=true'
|
// and starting the program this ros param 'use_sim_time:=true'
|
||||||
// ```shell
|
// ```shell
|
||||||
// cargo run --features=sim-time --example=timer_sim_time -- --ros-args -p use_sim_time:=true
|
// cargo run --example=timer_sim_time -- --ros-args -p use_sim_time:=true
|
||||||
// ```
|
// ```
|
||||||
// this does not work if the parameter is changed during the runtime
|
// this does not work if the parameter is changed during the runtime
|
||||||
let (paramater_handler, _parameter_events) = node.make_parameter_handler()?;
|
let (paramater_handler, _parameter_events) = node.make_parameter_handler()?;
|
||||||
|
|
|
||||||
|
|
@ -85,7 +85,7 @@ impl Clock {
|
||||||
/// The clock must be [`ClockType::RosTime`].
|
/// The clock must be [`ClockType::RosTime`].
|
||||||
///
|
///
|
||||||
/// Wrapper for `rcl_enable_ros_time_override`
|
/// Wrapper for `rcl_enable_ros_time_override`
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
pub(crate) fn enable_ros_time_override(
|
pub(crate) fn enable_ros_time_override(
|
||||||
&mut self, initial_time: rcl_time_point_value_t,
|
&mut self, initial_time: rcl_time_point_value_t,
|
||||||
) -> Result<()> {
|
) -> Result<()> {
|
||||||
|
|
@ -110,7 +110,7 @@ impl Clock {
|
||||||
/// The clock must be [`ClockType::RosTime`].
|
/// The clock must be [`ClockType::RosTime`].
|
||||||
///
|
///
|
||||||
/// Wrapper for `rcl_disable_ros_time_override`
|
/// Wrapper for `rcl_disable_ros_time_override`
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
pub(crate) fn disable_ros_time_override(&mut self) -> Result<()> {
|
pub(crate) fn disable_ros_time_override(&mut self) -> Result<()> {
|
||||||
let valid = unsafe { rcl_clock_valid(&mut *self.clock_handle) };
|
let valid = unsafe { rcl_clock_valid(&mut *self.clock_handle) };
|
||||||
if !valid {
|
if !valid {
|
||||||
|
|
@ -133,7 +133,7 @@ impl Clock {
|
||||||
/// The clock must be [`ClockType::RosTime`].
|
/// The clock must be [`ClockType::RosTime`].
|
||||||
///
|
///
|
||||||
/// Wrapper for `rcl_set_ros_time_override`
|
/// Wrapper for `rcl_set_ros_time_override`
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
pub(crate) fn set_ros_time_override(&mut self, time: rcl_time_point_value_t) -> Result<()> {
|
pub(crate) fn set_ros_time_override(&mut self, time: rcl_time_point_value_t) -> Result<()> {
|
||||||
let valid = unsafe { rcl_clock_valid(&mut *self.clock_handle) };
|
let valid = unsafe { rcl_clock_valid(&mut *self.clock_handle) };
|
||||||
if !valid {
|
if !valid {
|
||||||
|
|
|
||||||
|
|
@ -125,9 +125,9 @@ pub use nodes::{Node, Timer};
|
||||||
|
|
||||||
pub mod qos;
|
pub mod qos;
|
||||||
|
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
mod time_source;
|
mod time_source;
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
pub use time_source::TimeSource;
|
pub use time_source::TimeSource;
|
||||||
|
|
||||||
pub use qos::QosProfile;
|
pub use qos::QosProfile;
|
||||||
|
|
|
||||||
|
|
@ -29,7 +29,7 @@ use crate::publishers::*;
|
||||||
use crate::qos::QosProfile;
|
use crate::qos::QosProfile;
|
||||||
use crate::services::*;
|
use crate::services::*;
|
||||||
use crate::subscribers::*;
|
use crate::subscribers::*;
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
use crate::time_source::TimeSource;
|
use crate::time_source::TimeSource;
|
||||||
|
|
||||||
/// A ROS Node.
|
/// A ROS Node.
|
||||||
|
|
@ -59,7 +59,7 @@ pub struct Node {
|
||||||
// RosTime clock used by all timers created by create_timer()
|
// RosTime clock used by all timers created by create_timer()
|
||||||
ros_clock: Arc<Mutex<Clock>>,
|
ros_clock: Arc<Mutex<Clock>>,
|
||||||
// time source that provides simulated time
|
// time source that provides simulated time
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
time_source: TimeSource,
|
time_source: TimeSource,
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -187,7 +187,7 @@ impl Node {
|
||||||
|
|
||||||
if res == RCL_RET_OK as i32 {
|
if res == RCL_RET_OK as i32 {
|
||||||
let ros_clock = Arc::new(Mutex::new(Clock::create(ClockType::RosTime)?));
|
let ros_clock = Arc::new(Mutex::new(Clock::create(ClockType::RosTime)?));
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
let time_source = {
|
let time_source = {
|
||||||
let time_source = TimeSource::new();
|
let time_source = TimeSource::new();
|
||||||
time_source.attach_ros_clock(Arc::downgrade(&ros_clock))?;
|
time_source.attach_ros_clock(Arc::downgrade(&ros_clock))?;
|
||||||
|
|
@ -206,7 +206,7 @@ impl Node {
|
||||||
timers: Vec::new(),
|
timers: Vec::new(),
|
||||||
pubs: Vec::new(),
|
pubs: Vec::new(),
|
||||||
ros_clock,
|
ros_clock,
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
time_source,
|
time_source,
|
||||||
};
|
};
|
||||||
node.load_params()?;
|
node.load_params()?;
|
||||||
|
|
@ -428,7 +428,7 @@ impl Node {
|
||||||
|
|
||||||
handlers.push(Box::pin(get_param_types_future));
|
handlers.push(Box::pin(get_param_types_future));
|
||||||
|
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
{
|
{
|
||||||
// create TimeSource based on value of use_sim_time parameter
|
// create TimeSource based on value of use_sim_time parameter
|
||||||
let use_sim_time = {
|
let use_sim_time = {
|
||||||
|
|
@ -1337,7 +1337,7 @@ impl Node {
|
||||||
/// Get TimeSource of the node
|
/// Get TimeSource of the node
|
||||||
///
|
///
|
||||||
/// See: [`TimeSource`]
|
/// See: [`TimeSource`]
|
||||||
#[cfg(feature = "sim-time")]
|
#[cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
pub fn get_time_source(&self) -> TimeSource {
|
pub fn get_time_source(&self) -> TimeSource {
|
||||||
self.time_source.clone()
|
self.time_source.clone()
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -1,4 +1,4 @@
|
||||||
#![cfg(feature = "sim-time")]
|
#![cfg(r2r__rosgraph_msgs__msg__Clock)]
|
||||||
|
|
||||||
use crate::builtin_interfaces::msg::Time;
|
use crate::builtin_interfaces::msg::Time;
|
||||||
use crate::error::*;
|
use crate::error::*;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue