From 340818e5f36bc6f43fe078e318519d15b202714c Mon Sep 17 00:00:00 2001 From: carter Date: Mon, 9 Dec 2024 18:14:59 -0700 Subject: [PATCH 01/14] Major re-org to split out roslibrust_common and ros1 --- Cargo.lock | 50 +- Cargo.toml | 2 +- example_package/Cargo.toml | 2 + example_package_macro/Cargo.toml | 5 +- roslibrust/Cargo.toml | 30 +- roslibrust/examples/generic_client.rs | 1 + .../examples/generic_client_services.rs | 1 + roslibrust/examples/generic_message.rs | 2 +- roslibrust/src/lib.rs | 65 +-- roslibrust/src/rosbridge/client.rs | 5 +- roslibrust/src/rosbridge/comm.rs | 2 +- roslibrust/src/rosbridge/integration_tests.rs | 1 + roslibrust/src/rosbridge/mod.rs | 5 +- roslibrust/src/rosbridge/publisher.rs | 2 +- roslibrust/src/rosbridge/subscriber.rs | 2 +- roslibrust/src/topic_provider.rs | 4 +- roslibrust_codegen/Cargo.toml | 1 + roslibrust_codegen/src/gen.rs | 4 +- roslibrust_codegen/src/integral_types.rs | 12 +- roslibrust_codegen/src/lib.rs | 39 +- roslibrust_common/Cargo.toml | 16 + roslibrust_common/src/lib.rs | 107 ++++ roslibrust_mock/Cargo.toml | 3 + roslibrust_ros1/Cargo.toml | 33 ++ .../ros1/mod.rs => roslibrust_ros1/src/lib.rs | 0 roslibrust_ros1/src/main.rs | 3 + .../src}/master_client.rs | 0 .../src/ros1 => roslibrust_ros1/src}/names.rs | 0 .../src}/node/actor.rs | 19 +- .../src}/node/handle.rs | 18 +- .../ros1 => roslibrust_ros1/src}/node/mod.rs | 2 +- .../src}/node/xmlrpc.rs | 0 .../ros1 => roslibrust_ros1/src}/publisher.rs | 4 +- .../src}/service_client.rs | 9 +- .../src}/service_server.rs | 2 +- .../src}/subscriber.rs | 4 +- .../ros1 => roslibrust_ros1/src}/tcpros.rs | 0 .../tests/ros1_native_integration_tests.rs | 0 .../tests/ros1_xmlrpc.rs | 2 +- roslibrust_test/Cargo.toml | 2 + roslibrust_test/src/ros1.rs | 492 +++++++++--------- roslibrust_test/src/ros2.rs | 304 +++++------ roslibrust_zenoh/Cargo.toml | 2 + 43 files changed, 672 insertions(+), 585 deletions(-) create mode 100644 roslibrust_common/Cargo.toml create mode 100644 roslibrust_common/src/lib.rs create mode 100644 roslibrust_ros1/Cargo.toml rename roslibrust/src/ros1/mod.rs => roslibrust_ros1/src/lib.rs (100%) create mode 100644 roslibrust_ros1/src/main.rs rename {roslibrust/src/ros1 => roslibrust_ros1/src}/master_client.rs (100%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/names.rs (100%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/node/actor.rs (98%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/node/handle.rs (92%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/node/mod.rs (99%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/node/xmlrpc.rs (100%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/publisher.rs (99%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/service_client.rs (97%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/service_server.rs (99%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/subscriber.rs (98%) rename {roslibrust/src/ros1 => roslibrust_ros1/src}/tcpros.rs (100%) rename {roslibrust => roslibrust_ros1}/tests/ros1_native_integration_tests.rs (100%) rename {roslibrust => roslibrust_ros1}/tests/ros1_xmlrpc.rs (98%) diff --git a/Cargo.lock b/Cargo.lock index e2a6fbef..da2b0f48 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -852,6 +852,7 @@ version = "0.1.0" dependencies = [ "cargo-emit", "roslibrust_codegen", + "roslibrust_common", ] [[package]] @@ -860,6 +861,7 @@ version = "0.1.0" dependencies = [ "roslibrust_codegen", "roslibrust_codegen_macro", + "roslibrust_common", ] [[package]] @@ -2571,27 +2573,22 @@ version = "0.11.1" dependencies = [ "abort-on-drop", "anyhow", - "byteorder", "dashmap", "deadqueue", "env_logger 0.10.2", "futures", "futures-util", - "gethostname", - "hyper", "lazy_static", "log", "proc-macro2", "rand", - "regex", - "reqwest", "roslibrust_codegen", "roslibrust_codegen_macro", - "roslibrust_serde_rosmsg", + "roslibrust_common", + "roslibrust_ros1", "serde", "serde-big-array", "serde_json", - "serde_xmlrpc", "simple_logger", "smart-default 0.6.0", "test-log", @@ -2611,6 +2608,7 @@ dependencies = [ "md5", "proc-macro2", "quote", + "roslibrust_common", "serde", "serde-big-array", "serde_bytes", @@ -2634,6 +2632,18 @@ dependencies = [ "syn 1.0.109", ] +[[package]] +name = "roslibrust_common" +version = "0.1.0" +dependencies = [ + "anyhow", + "serde", + "serde_json", + "thiserror 2.0.6", + "tokio", + "tokio-tungstenite 0.17.2", +] + [[package]] name = "roslibrust_genmsg" version = "0.9.0" @@ -2659,6 +2669,30 @@ dependencies = [ "roslibrust", "roslibrust_codegen", "roslibrust_codegen_macro", + "roslibrust_common", + "tokio", +] + +[[package]] +name = "roslibrust_ros1" +version = "0.1.0" +dependencies = [ + "abort-on-drop", + "anyhow", + "byteorder", + "gethostname", + "hyper", + "lazy_static", + "log", + "regex", + "reqwest", + "roslibrust_codegen", + "roslibrust_common", + "roslibrust_serde_rosmsg", + "serde", + "serde_xmlrpc", + "test-log", + "thiserror 2.0.6", "tokio", ] @@ -2685,6 +2719,7 @@ dependencies = [ "pprof", "roslibrust", "roslibrust_codegen", + "roslibrust_common", "tokio", ] @@ -2699,6 +2734,7 @@ dependencies = [ "roslibrust", "roslibrust_codegen", "roslibrust_codegen_macro", + "roslibrust_common", "roslibrust_serde_rosmsg", "tokio", "zenoh", diff --git a/Cargo.toml b/Cargo.toml index 3990f2b1..03ceda15 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -9,6 +9,6 @@ members = [ "roslibrust_genmsg", "roslibrust_test", "roslibrust_mock", - "roslibrust_zenoh", + "roslibrust_zenoh", "roslibrust_ros1", "roslibrust_common", ] resolver = "2" diff --git a/example_package/Cargo.toml b/example_package/Cargo.toml index f8ae9618..64cddbff 100644 --- a/example_package/Cargo.toml +++ b/example_package/Cargo.toml @@ -6,6 +6,8 @@ edition = "2021" [dependencies] # The code generated by roslibrust_codegen has dependendencies # We need to depend on the crate at build time so that the generate code has access to these dependencies +roslibrust_common = { path = "../roslibrust_common" } +# THIS SHOULDN'T BE NEEDED, BUT IS FOR NOW GOTTA FIX LEAKING DEPENDENCIES roslibrust_codegen = { path = "../roslibrust_codegen" } [build-dependencies] diff --git a/example_package_macro/Cargo.toml b/example_package_macro/Cargo.toml index edb0c4c1..1b0e89ae 100644 --- a/example_package_macro/Cargo.toml +++ b/example_package_macro/Cargo.toml @@ -6,6 +6,9 @@ edition = "2021" [dependencies] # The code generated by roslibrust_codegen has dependendencies # We need to depend on the crate at build time so that the generate code has access to these dependencies -roslibrust_codegen = { path = "../roslibrust_codegen" } +# TODO figure out how to rexport these types through the macro +roslibrust_common = { path = "../roslibrust_common" } # This crate contains the actual macro we will invoke roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } +# THIS SHOULDN'T BE NEEDED, BUT IS FOR NOW GOTTA FIX LEAKING DEPENDENCIES +roslibrust_codegen = { path = "../roslibrust_codegen" } \ No newline at end of file diff --git a/roslibrust/Cargo.toml b/roslibrust/Cargo.toml index 7bc8db04..61cdc8a2 100644 --- a/roslibrust/Cargo.toml +++ b/roslibrust/Cargo.toml @@ -13,7 +13,6 @@ categories = ["science::robotics"] [dependencies] abort-on-drop = "0.2" anyhow = "1.0" -byteorder = "1.4" dashmap = "5.3" deadqueue = "0.2.4" # .4+ is required to fix bug with missing tokio dep futures = "0.3" @@ -34,18 +33,16 @@ tokio = { version = "1.20", features = [ ] } tokio-tungstenite = { version = "0.17" } uuid = { version = "1.1", features = ["v4"] } +# TODO this crate shouldn't depend on codegen or codege_macro directly roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro", version = "0.11.1" } roslibrust_codegen = { path = "../roslibrust_codegen", version = "0.11.1" } -reqwest = { version = "0.11", optional = true } # Only used with native ros1 -serde_xmlrpc = { version = "0.2", optional = true } # Only used with native ros1 -roslibrust_serde_rosmsg = { version = "0.4", optional = true } # Only used with native ros1 -hyper = { version = "0.14", features = [ - "server", -], optional = true } # Only used with native ros1 -gethostname = { version = "0.4", optional = true } # Only used with native ros1 -regex = { version = "1.9", optional = true } # Only used with native ros1 + +# TODO version here +roslibrust_common = { path = "../roslibrust_common" } # TODO I think we should move rosapi into its own crate... serde-big-array = { version = "0.5", optional = true } # Only used with rosapi +# TODO REAL VERSION HERE +roslibrust_ros1 = { path = "../roslibrust_ros1", optional = true } [dev-dependencies] env_logger = "0.10" @@ -68,20 +65,7 @@ ros2_test = ["running_bridge"] # Provides access to experimental abstract trait topic_provider topic_provider = [] # Provides a ros1 xmlrpc / TCPROS client -ros1 = [ - "dep:serde_xmlrpc", - "dep:reqwest", - "dep:hyper", - "dep:gethostname", - "dep:regex", - "dep:roslibrust_serde_rosmsg", -] - - -[[test]] -name = "ros1_xmlrpc" -path = "tests/ros1_xmlrpc.rs" -required-features = ["ros1_test", "ros1"] +ros1 = ["roslibrust_ros1"] [package.metadata.docs.rs] features = ["ros1"] diff --git a/roslibrust/examples/generic_client.rs b/roslibrust/examples/generic_client.rs index 50b4081e..c3c79d78 100644 --- a/roslibrust/examples/generic_client.rs +++ b/roslibrust/examples/generic_client.rs @@ -1,5 +1,6 @@ //! Purpose of this example is to show how the TopicProvider trait can be use //! to create code that is generic of which communication backend it will use. +#[cfg(feature = "topic_provider")] use roslibrust::topic_provider::*; roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces/std_msgs"); diff --git a/roslibrust/examples/generic_client_services.rs b/roslibrust/examples/generic_client_services.rs index 28fec204..a4d57f11 100644 --- a/roslibrust/examples/generic_client_services.rs +++ b/roslibrust/examples/generic_client_services.rs @@ -1,5 +1,6 @@ //! Purpose of this example is to show how the ServiceProvider trait can be use //! to create code that is generic of which communication backend it will use. +#[cfg(feature = "topic_provider")] use roslibrust::topic_provider::*; roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); diff --git a/roslibrust/examples/generic_message.rs b/roslibrust/examples/generic_message.rs index 1a1ba67a..14b88ce6 100644 --- a/roslibrust/examples/generic_message.rs +++ b/roslibrust/examples/generic_message.rs @@ -2,7 +2,7 @@ //! to decode to the right type. use log::*; use roslibrust::ClientHandle; -use roslibrust_codegen::RosMessageType; +use roslibrust_common::RosMessageType; /// We place the ros1 generate code into a module to prevent name collisions with the identically /// named ros2 types. diff --git a/roslibrust/src/lib.rs b/roslibrust/src/lib.rs index 21423a37..b29b46f6 100644 --- a/roslibrust/src/lib.rs +++ b/roslibrust/src/lib.rs @@ -101,16 +101,15 @@ mod rosbridge; pub use rosbridge::*; -// Re export the codegen traits so that crates that only interact with abstract messages -// don't need to depend on the codegen crate -pub use roslibrust_codegen::RosMessageType; -pub use roslibrust_codegen::RosServiceType; +// Re-export common types and traits under the roslibrust namespace +pub use roslibrust_common::*; #[cfg(feature = "rosapi")] pub mod rosapi; +// If the ros1 feature is enabled, export the roslibrust_ros1 crate under ros1 #[cfg(feature = "ros1")] -pub mod ros1; +pub use roslibrust_ros1 as ros1; // Topic provider is locked behind a feature until it is stabalized // additionally because of its use of generic associated types, it requires rust >1.65 @@ -118,59 +117,3 @@ pub mod ros1; /// Provides a generic trait for building clients / against either the rosbridge, /// ros1, or a mock backend pub mod topic_provider; - -/// For now starting with a central error type, may break this up more in future -#[derive(thiserror::Error, Debug)] -pub enum RosLibRustError { - #[error("Not currently connected to ros master / bridge")] - Disconnected, - // TODO we probably want to eliminate tungstenite from this and hide our - // underlying websocket implementation from the API - // currently we "technically" break the API when we change tungstenite verisons - #[error("Websocket communication error: {0}")] - CommFailure(#[from] tokio_tungstenite::tungstenite::Error), - #[error("Operation timed out: {0}")] - Timeout(#[from] tokio::time::error::Elapsed), - #[error("Failed to parse message from JSON: {0}")] - InvalidMessage(#[from] serde_json::Error), - #[error("TCPROS serialization error: {0}")] - SerializationError(String), - #[error("Rosbridge server reported an error: {0}")] - ServerError(String), - #[error("IO error: {0}")] - IoError(#[from] std::io::Error), - #[error("Name does not meet ROS requirements: {0}")] - InvalidName(String), - // Generic catch-all error type for not-yet-handled errors - // TODO ultimately this type will be removed from API of library - #[error(transparent)] - Unexpected(#[from] anyhow::Error), -} - -/// Generic result type used as standard throughout library. -/// Note: many functions which currently return this will be updated to provide specific error -/// types in the future instead of the generic error here. -pub type RosLibRustResult = Result; - -// Note: service Fn is currently defined here as it used by ros1 and roslibrust impls -/// This trait describes a function which can validly act as a ROS service -/// server with roslibrust. We're really just using this as a trait alias -/// as the full definition is overly verbose and trait aliases are unstable. -pub trait ServiceFn: - Fn(T::Request) -> Result> - + Send - + Sync - + 'static -{ -} - -/// Automatic implementation of ServiceFn for Fn -impl ServiceFn for F -where - T: RosServiceType, - F: Fn(T::Request) -> Result> - + Send - + Sync - + 'static, -{ -} diff --git a/roslibrust/src/rosbridge/client.rs b/roslibrust/src/rosbridge/client.rs index 337534c0..a4e4b43e 100644 --- a/roslibrust/src/rosbridge/client.rs +++ b/roslibrust/src/rosbridge/client.rs @@ -1,12 +1,13 @@ use crate::{ rosbridge::comm::{self, RosBridgeComm}, - Publisher, RosLibRustError, RosLibRustResult, ServiceFn, ServiceHandle, Subscriber, + Publisher, RosLibRustError, RosLibRustResult, ServiceHandle, Subscriber, }; use anyhow::anyhow; use dashmap::DashMap; use futures::StreamExt; use log::*; -use roslibrust_codegen::{RosMessageType, RosServiceType}; +use roslibrust_common::ServiceFn; +use roslibrust_common::{RosMessageType, RosServiceType}; use serde_json::Value; use std::collections::HashMap; use std::str::FromStr; diff --git a/roslibrust/src/rosbridge/comm.rs b/roslibrust/src/rosbridge/comm.rs index c7685654..8a52c470 100644 --- a/roslibrust/src/rosbridge/comm.rs +++ b/roslibrust/src/rosbridge/comm.rs @@ -2,7 +2,7 @@ use crate::{rosbridge::Writer, RosLibRustResult}; use anyhow::bail; use futures_util::SinkExt; use log::debug; -use roslibrust_codegen::RosMessageType; +use roslibrust_common::RosMessageType; use serde_json::json; use std::{fmt::Display, str::FromStr, string::ToString}; use tokio_tungstenite::tungstenite::Message; diff --git a/roslibrust/src/rosbridge/integration_tests.rs b/roslibrust/src/rosbridge/integration_tests.rs index de7e612b..df06d94c 100644 --- a/roslibrust/src/rosbridge/integration_tests.rs +++ b/roslibrust/src/rosbridge/integration_tests.rs @@ -386,6 +386,7 @@ mod integration_tests { #[test_log::test(tokio::test)] // Note: only have a ros1 version of this test for now, as this is specialized in how we launch rosbridge #[cfg(feature = "ros1_test")] + #[ignore] async fn pub_and_sub_reconnect_through_dead_bridge() { // Have to do a timeout to confirm the bridge is up / down const WAIT_FOR_ROSBRIDGE: tokio::time::Duration = tokio::time::Duration::from_millis(2000); diff --git a/roslibrust/src/rosbridge/mod.rs b/roslibrust/src/rosbridge/mod.rs index c6ad3a5e..17646064 100644 --- a/roslibrust/src/rosbridge/mod.rs +++ b/roslibrust/src/rosbridge/mod.rs @@ -1,7 +1,8 @@ +use roslibrust_common::RosServiceType; + // Subscriber is a transparent module, we directly expose internal types // Module exists only to organize source code. mod subscriber; -use roslibrust_codegen::RosServiceType; pub use subscriber::*; // Publisher is a transparent module, we directly expose internal types @@ -33,7 +34,7 @@ use tungstenite::Message; // Doing this to maintain backwards compatibilities like `use roslibrust::rosbridge::RosLibRustError` #[allow(unused)] -pub use super::{RosLibRustError, RosLibRustResult}; +pub use roslibrust_common::{RosLibRustError, RosLibRustResult}; /// Used for type erasure of message type so that we can store arbitrary handles type Callback = Box; diff --git a/roslibrust/src/rosbridge/publisher.rs b/roslibrust/src/rosbridge/publisher.rs index afbaa8f5..05cd56e4 100644 --- a/roslibrust/src/rosbridge/publisher.rs +++ b/roslibrust/src/rosbridge/publisher.rs @@ -1,5 +1,5 @@ use crate::{ClientHandle, RosLibRustResult}; -use roslibrust_codegen::RosMessageType; +use roslibrust_common::RosMessageType; /// A handle given to the caller when they advertise a topic /// diff --git a/roslibrust/src/rosbridge/subscriber.rs b/roslibrust/src/rosbridge/subscriber.rs index fea1b570..791b6b54 100644 --- a/roslibrust/src/rosbridge/subscriber.rs +++ b/roslibrust/src/rosbridge/subscriber.rs @@ -6,7 +6,7 @@ use log::error; use std::sync::Arc; use crate::{rosbridge::MessageQueue, ClientHandle}; -use roslibrust_codegen::RosMessageType; +use roslibrust_common::RosMessageType; /// Represents a single instance of listening to a topic, and provides the ability to extract messages /// diff --git a/roslibrust/src/topic_provider.rs b/roslibrust/src/topic_provider.rs index 98ee253d..b5b1ae63 100644 --- a/roslibrust/src/topic_provider.rs +++ b/roslibrust/src/topic_provider.rs @@ -1,6 +1,6 @@ -use roslibrust_codegen::{RosMessageType, RosServiceType}; +use roslibrust_common::{RosMessageType, RosServiceType, ServiceFn}; -use crate::{RosLibRustResult, ServiceClient, ServiceFn}; +use crate::{RosLibRustResult, ServiceClient}; /// Indicates that something is a publisher and has our expected publish /// Implementors of this trait are expected to auto-cleanup the publisher when dropped diff --git a/roslibrust_codegen/Cargo.toml b/roslibrust_codegen/Cargo.toml index 52364561..0851e3c8 100644 --- a/roslibrust_codegen/Cargo.toml +++ b/roslibrust_codegen/Cargo.toml @@ -13,6 +13,7 @@ categories = ["science::robotics"] # See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html [dependencies] +roslibrust_common = { path = "../roslibrust_common" } lazy_static = "1.4" log = "0.4" md5 = "0.7" diff --git a/roslibrust_codegen/src/gen.rs b/roslibrust_codegen/src/gen.rs index 1f4de44f..c5b9ae03 100644 --- a/roslibrust_codegen/src/gen.rs +++ b/roslibrust_codegen/src/gen.rs @@ -42,7 +42,7 @@ pub fn generate_service(service: ServiceFile) -> Result { pub struct #struct_name { } - impl ::roslibrust_codegen::RosServiceType for #struct_name { + impl ::roslibrust_common::RosServiceType for #struct_name { const ROS_SERVICE_NAME: &'static str = #service_type_name; const MD5SUM: &'static str = #service_md5sum; type Request = #request_name; @@ -99,7 +99,7 @@ pub fn generate_struct(msg: MessageFile) -> Result { #(#fields )* } - impl ::roslibrust_codegen::RosMessageType for #struct_name { + impl ::roslibrust_common::RosMessageType for #struct_name { const ROS_TYPE_NAME: &'static str = #ros_type_name; const MD5SUM: &'static str = #md5sum; const DEFINITION: &'static str = #raw_message_definition; diff --git a/roslibrust_codegen/src/integral_types.rs b/roslibrust_codegen/src/integral_types.rs index 9a984005..7480073b 100644 --- a/roslibrust_codegen/src/integral_types.rs +++ b/roslibrust_codegen/src/integral_types.rs @@ -1,6 +1,6 @@ use simple_error::{bail, SimpleError}; -use crate::RosMessageType; +use roslibrust_common::RosMessageType; /// Matches the integral ros1 type time, with extensions for ease of use /// NOTE: in ROS1 "Time" is not a message in and of itself and std_msgs/Time should be used. @@ -78,16 +78,6 @@ impl RosMessageType for Time { const DEFINITION: &'static str = ""; } -#[derive(:: serde :: Deserialize, :: serde :: Serialize, Debug, Default, Clone, PartialEq)] -pub struct ShapeShifter(Vec); - -// The equivalent of rospy AnyMsg or C++ ShapeShifter, subscribe_any() uses this type -impl RosMessageType for ShapeShifter { - const ROS_TYPE_NAME: &'static str = "*"; - const MD5SUM: &'static str = "*"; - const DEFINITION: &'static str = ""; -} - // TODO provide chrono conversions here behind a cfg flag /// Matches the integral ros1 duration type, with extensions for ease of use diff --git a/roslibrust_codegen/src/lib.rs b/roslibrust_codegen/src/lib.rs index d1ae5adb..94d5698c 100644 --- a/roslibrust_codegen/src/lib.rs +++ b/roslibrust_codegen/src/lib.rs @@ -27,43 +27,8 @@ pub use serde_big_array::BigArray; // Used in generated code for large fixed siz pub use serde_bytes; pub use smart_default::SmartDefault; // Used in generated code for default values // Used in generated code for faster Vec serialization -/// Fundamental traits for message types this crate works with -/// This trait will be satisfied for any types generated with this crate's message_gen functionality -pub trait RosMessageType: - 'static + DeserializeOwned + Send + Serialize + Sync + Clone + Debug -{ - /// Expected to be the combination pkg_name/type_name string describing the type to ros - /// Example: std_msgs/Header - const ROS_TYPE_NAME: &'static str; - - /// The computed md5sum of the message file and its dependencies - /// This field is optional, and only needed when using ros1 native communication - const MD5SUM: &'static str = ""; - - /// The definition from the msg, srv, or action file - /// This field is optional, and only needed when using ros1 native communication - const DEFINITION: &'static str = ""; -} - -// This special impl allows for services with no args / returns -impl RosMessageType for () { - const ROS_TYPE_NAME: &'static str = ""; - const MD5SUM: &'static str = ""; - const DEFINITION: &'static str = ""; -} - -/// Fundamental traits for service types this crate works with -/// This trait will be satisfied for any services definitions generated with this crate's message_gen functionality -pub trait RosServiceType: 'static + Send + Sync { - /// Name of the ros service e.g. `rospy_tutorials/AddTwoInts` - const ROS_SERVICE_NAME: &'static str; - /// The computed md5sum of the message file and its dependencies - const MD5SUM: &'static str; - /// The type of data being sent in the request - type Request: RosMessageType; - /// The type of the data - type Response: RosMessageType; -} +// Export the common types so they can be found under this namespace for backwards compatibility reasons +pub use roslibrust_common::*; /// Taking in a message definition /// reformat it according to the md5sum algorithm: diff --git a/roslibrust_common/Cargo.toml b/roslibrust_common/Cargo.toml new file mode 100644 index 00000000..89c461ca --- /dev/null +++ b/roslibrust_common/Cargo.toml @@ -0,0 +1,16 @@ +[package] +name = "roslibrust_common" +version = "0.1.0" +edition = "2021" + +[dependencies] +thiserror = "2.0" +anyhow = "1.0" +serde = { version = "1.0", features = ["derive"] } + +# THESE DEPENDENCIES WILL BE REMOVED +# We're currently leaking these error types in the "generic error type" +# We'll clean this up +tokio = { version = "1.41", features = ["time"] } +tokio-tungstenite = { version = "0.17" } +serde_json = "1.0" diff --git a/roslibrust_common/src/lib.rs b/roslibrust_common/src/lib.rs new file mode 100644 index 00000000..4a3dc7ab --- /dev/null +++ b/roslibrust_common/src/lib.rs @@ -0,0 +1,107 @@ +//! # roslibrust_common +//! This crate provides common types and traits used throughout the roslibrust ecosystem. + +/// For now starting with a central error type, may break this up more in future +#[derive(thiserror::Error, Debug)] +pub enum RosLibRustError { + #[error("Not currently connected to ros master / bridge")] + Disconnected, + // TODO we probably want to eliminate tungstenite from this and hide our + // underlying websocket implementation from the API + // currently we "technically" break the API when we change tungstenite verisons + #[error("Websocket communication error: {0}")] + CommFailure(#[from] tokio_tungstenite::tungstenite::Error), + #[error("Operation timed out: {0}")] + Timeout(#[from] tokio::time::error::Elapsed), + #[error("Failed to parse message from JSON: {0}")] + InvalidMessage(#[from] serde_json::Error), + #[error("TCPROS serialization error: {0}")] + SerializationError(String), + #[error("Rosbridge server reported an error: {0}")] + ServerError(String), + #[error("IO error: {0}")] + IoError(#[from] std::io::Error), + #[error("Name does not meet ROS requirements: {0}")] + InvalidName(String), + // Generic catch-all error type for not-yet-handled errors + // TODO ultimately this type will be removed from API of library + #[error(transparent)] + Unexpected(#[from] anyhow::Error), +} + +/// Generic result type used as standard throughout library. +/// Note: many functions which currently return this will be updated to provide specific error +/// types in the future instead of the generic error here. +pub type RosLibRustResult = Result; + +/// Fundamental traits for message types this crate works with +/// This trait will be satisfied for any types generated with this crate's message_gen functionality +pub trait RosMessageType: + 'static + serde::de::DeserializeOwned + Send + serde::Serialize + Sync + Clone + std::fmt::Debug +{ + /// Expected to be the combination pkg_name/type_name string describing the type to ros + /// Example: std_msgs/Header + const ROS_TYPE_NAME: &'static str; + + /// The computed md5sum of the message file and its dependencies + /// This field is optional, and only needed when using ros1 native communication + const MD5SUM: &'static str = ""; + + /// The definition from the msg, srv, or action file + /// This field is optional, and only needed when using ros1 native communication + const DEFINITION: &'static str = ""; +} + +// This special impl allows for services with no args / returns +impl RosMessageType for () { + const ROS_TYPE_NAME: &'static str = ""; + const MD5SUM: &'static str = ""; + const DEFINITION: &'static str = ""; +} + +/// Fundamental traits for service types this crate works with +/// This trait will be satisfied for any services definitions generated with this crate's message_gen functionality +pub trait RosServiceType: 'static + Send + Sync { + /// Name of the ros service e.g. `rospy_tutorials/AddTwoInts` + const ROS_SERVICE_NAME: &'static str; + /// The computed md5sum of the message file and its dependencies + const MD5SUM: &'static str; + /// The type of data being sent in the request + type Request: RosMessageType; + /// The type of the data + type Response: RosMessageType; +} + +// Note: service Fn is currently defined here as it used by ros1 and roslibrust impls +/// This trait describes a function which can validly act as a ROS service +/// server with roslibrust. We're really just using this as a trait alias +/// as the full definition is overly verbose and trait aliases are unstable. +pub trait ServiceFn: + Fn(T::Request) -> Result> + + Send + + Sync + + 'static +{ +} + +/// Automatic implementation of ServiceFn for Fn +impl ServiceFn for F +where + T: RosServiceType, + F: Fn(T::Request) -> Result> + + Send + + Sync + + 'static, +{ +} + +/// A generic message type used by some implementations to provide a generic subscriber / publisher without serialization +#[derive(:: serde :: Deserialize, :: serde :: Serialize, Debug, Default, Clone, PartialEq)] +pub struct ShapeShifter(Vec); + +// The equivalent of rospy AnyMsg or C++ ShapeShifter, subscribe_any() uses this type +impl RosMessageType for ShapeShifter { + const ROS_TYPE_NAME: &'static str = "*"; + const MD5SUM: &'static str = "*"; + const DEFINITION: &'static str = ""; +} diff --git a/roslibrust_mock/Cargo.toml b/roslibrust_mock/Cargo.toml index beba67ca..61b241d7 100644 --- a/roslibrust_mock/Cargo.toml +++ b/roslibrust_mock/Cargo.toml @@ -12,5 +12,8 @@ bincode = "1.3" log = "0.4" [dev-dependencies] +# Ideally this shouldn't need to be here +roslibrust_common = { path = "../roslibrust_common" } +# Neither should this... roslibrust_codegen = { path = "../roslibrust_codegen" } roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } diff --git a/roslibrust_ros1/Cargo.toml b/roslibrust_ros1/Cargo.toml new file mode 100644 index 00000000..5693a9df --- /dev/null +++ b/roslibrust_ros1/Cargo.toml @@ -0,0 +1,33 @@ +[package] +name = "roslibrust_ros1" +version = "0.1.0" +edition = "2021" + +[dependencies] +# Provides common types and traits used throughout the roslibrust ecosystem. +roslibrust_common = { path = "../roslibrust_common" } +# TODO we'd like to remove this dependency? Don't love these are crosslinked +roslibrust_codegen = { path = "../roslibrust_codegen" } + +# Should probably become workspace members: +tokio = { version = "1.41", features = ["rt-multi-thread", "sync", "macros"] } +log = "0.4" +lazy_static = "1.4" +abort-on-drop = "0.2" +test-log = "0.2" +serde = { version = "1.0" } + +# These are definitely needed by this crate: +reqwest = { version = "0.11" } +serde_xmlrpc = { version = "0.2" } +roslibrust_serde_rosmsg = { version = "0.4" } +hyper = { version = "0.14", features = ["server"] } +gethostname = { version = "0.4" } +regex = { version = "1.9" } +byteorder = "1.4" +thiserror = "2.0" +anyhow = "1.0" + +[features] +# Used for enabling tests that rely on a running ros1 master +ros1_test = [] diff --git a/roslibrust/src/ros1/mod.rs b/roslibrust_ros1/src/lib.rs similarity index 100% rename from roslibrust/src/ros1/mod.rs rename to roslibrust_ros1/src/lib.rs diff --git a/roslibrust_ros1/src/main.rs b/roslibrust_ros1/src/main.rs new file mode 100644 index 00000000..e7a11a96 --- /dev/null +++ b/roslibrust_ros1/src/main.rs @@ -0,0 +1,3 @@ +fn main() { + println!("Hello, world!"); +} diff --git a/roslibrust/src/ros1/master_client.rs b/roslibrust_ros1/src/master_client.rs similarity index 100% rename from roslibrust/src/ros1/master_client.rs rename to roslibrust_ros1/src/master_client.rs diff --git a/roslibrust/src/ros1/names.rs b/roslibrust_ros1/src/names.rs similarity index 100% rename from roslibrust/src/ros1/names.rs rename to roslibrust_ros1/src/names.rs diff --git a/roslibrust/src/ros1/node/actor.rs b/roslibrust_ros1/src/node/actor.rs similarity index 98% rename from roslibrust/src/ros1/node/actor.rs rename to roslibrust_ros1/src/node/actor.rs index 4ec61e7c..f009855a 100644 --- a/roslibrust/src/ros1/node/actor.rs +++ b/roslibrust_ros1/src/node/actor.rs @@ -1,18 +1,15 @@ use crate::{ - ros1::{ - names::Name, - node::{XmlRpcServer, XmlRpcServerHandle}, - publisher::Publication, - service_client::ServiceClientLink, - service_server::ServiceServerLink, - subscriber::Subscription, - MasterClient, NodeError, ProtocolParams, ServiceClient, TypeErasedCallback, - }, - RosLibRustError, ServiceFn, + names::Name, + node::{XmlRpcServer, XmlRpcServerHandle}, + publisher::Publication, + service_client::ServiceClientLink, + service_server::ServiceServerLink, + subscriber::Subscription, + MasterClient, NodeError, ProtocolParams, ServiceClient, TypeErasedCallback, }; use abort_on_drop::ChildTask; use log::*; -use roslibrust_codegen::{RosMessageType, RosServiceType}; +use roslibrust_common::{RosLibRustError, RosMessageType, RosServiceType, ServiceFn}; use std::{collections::HashMap, io, net::Ipv4Addr, sync::Arc}; use tokio::sync::{broadcast, mpsc, oneshot}; diff --git a/roslibrust/src/ros1/node/handle.rs b/roslibrust_ros1/src/node/handle.rs similarity index 92% rename from roslibrust/src/ros1/node/handle.rs rename to roslibrust_ros1/src/node/handle.rs index f58d1352..edfe5fd8 100644 --- a/roslibrust/src/ros1/node/handle.rs +++ b/roslibrust_ros1/src/node/handle.rs @@ -1,11 +1,9 @@ use super::actor::{Node, NodeServerHandle}; use crate::{ - ros1::{ - names::Name, publisher::Publisher, publisher::PublisherAny, service_client::ServiceClient, - subscriber::Subscriber, subscriber::SubscriberAny, NodeError, ServiceServer, - }, - ServiceFn, + names::Name, publisher::Publisher, publisher::PublisherAny, service_client::ServiceClient, + subscriber::Subscriber, subscriber::SubscriberAny, NodeError, ServiceServer, }; +use roslibrust_common::ServiceFn; /// Represents a handle to an underlying Node. NodeHandle's can be freely cloned, moved, copied, etc. /// This class provides the user facing API for interacting with ROS. @@ -97,7 +95,7 @@ impl NodeHandle { /// Subsequent calls will simply be given additional handles to the underlying publication. /// This behavior was chosen to mirror ROS1's API, however it is recommended to .clone() the returned publisher /// instead of calling this function multiple times. - pub async fn advertise( + pub async fn advertise( &self, topic_name: &str, queue_size: usize, @@ -117,12 +115,12 @@ impl NodeHandle { ) -> Result { let receiver = self .inner - .register_subscriber::(topic_name, queue_size) + .register_subscriber::(topic_name, queue_size) .await?; Ok(SubscriberAny::new(receiver)) } - pub async fn subscribe( + pub async fn subscribe( &self, topic_name: &str, queue_size: usize, @@ -134,7 +132,7 @@ impl NodeHandle { Ok(Subscriber::new(receiver)) } - pub async fn service_client( + pub async fn service_client( &self, service_name: &str, ) -> Result, NodeError> { @@ -152,7 +150,7 @@ impl NodeHandle { server: F, ) -> Result where - T: roslibrust_codegen::RosServiceType, + T: roslibrust_common::RosServiceType, F: ServiceFn, { let service_name = Name::new(service_name)?; diff --git a/roslibrust/src/ros1/node/mod.rs b/roslibrust_ros1/src/node/mod.rs similarity index 99% rename from roslibrust/src/ros1/node/mod.rs rename to roslibrust_ros1/src/node/mod.rs index 95719365..aa0d0535 100644 --- a/roslibrust/src/ros1/node/mod.rs +++ b/roslibrust_ros1/src/node/mod.rs @@ -1,7 +1,7 @@ //! This module contains the top level Node and NodeHandle classes. //! These wrap the lower level management of a ROS Node connection into a higher level and thread safe API. -use crate::RosLibRustError; +use roslibrust_common::RosLibRustError; use super::{names::InvalidNameError, RosMasterError}; use std::{ diff --git a/roslibrust/src/ros1/node/xmlrpc.rs b/roslibrust_ros1/src/node/xmlrpc.rs similarity index 100% rename from roslibrust/src/ros1/node/xmlrpc.rs rename to roslibrust_ros1/src/node/xmlrpc.rs diff --git a/roslibrust/src/ros1/publisher.rs b/roslibrust_ros1/src/publisher.rs similarity index 99% rename from roslibrust/src/ros1/publisher.rs rename to roslibrust_ros1/src/publisher.rs index 4bb11e9b..1f35af2c 100644 --- a/roslibrust/src/ros1/publisher.rs +++ b/roslibrust_ros1/src/publisher.rs @@ -1,10 +1,10 @@ -use crate::ros1::{ +use crate::{ names::Name, tcpros::{self, ConnectionHeader}, }; use abort_on_drop::ChildTask; use log::*; -use roslibrust_codegen::RosMessageType; +use roslibrust_common::RosMessageType; use std::{ marker::PhantomData, net::{Ipv4Addr, SocketAddr}, diff --git a/roslibrust/src/ros1/service_client.rs b/roslibrust_ros1/src/service_client.rs similarity index 97% rename from roslibrust/src/ros1/service_client.rs rename to roslibrust_ros1/src/service_client.rs index 3efa9f18..2d3aa30d 100644 --- a/roslibrust/src/ros1/service_client.rs +++ b/roslibrust_ros1/src/service_client.rs @@ -1,12 +1,9 @@ use crate::{ - ros1::{ - names::Name, - tcpros::{establish_connection, ConnectionHeader}, - }, - RosLibRustError, RosLibRustResult, + names::Name, + tcpros::{establish_connection, ConnectionHeader}, }; use abort_on_drop::ChildTask; -use roslibrust_codegen::RosServiceType; +use roslibrust_common::{RosLibRustError, RosLibRustResult, RosServiceType}; use std::{marker::PhantomData, sync::Arc}; use tokio::{ io::{AsyncReadExt, AsyncWriteExt}, diff --git a/roslibrust/src/ros1/service_server.rs b/roslibrust_ros1/src/service_server.rs similarity index 99% rename from roslibrust/src/ros1/service_server.rs rename to roslibrust_ros1/src/service_server.rs index affa6394..208b0cdb 100644 --- a/roslibrust/src/ros1/service_server.rs +++ b/roslibrust_ros1/src/service_server.rs @@ -7,7 +7,7 @@ use abort_on_drop::ChildTask; use log::*; use tokio::io::AsyncWriteExt; -use crate::ros1::tcpros::{self, ConnectionHeader}; +use crate::tcpros::{self, ConnectionHeader}; use super::{names::Name, NodeHandle, TypeErasedCallback}; diff --git a/roslibrust/src/ros1/subscriber.rs b/roslibrust_ros1/src/subscriber.rs similarity index 98% rename from roslibrust/src/ros1/subscriber.rs rename to roslibrust_ros1/src/subscriber.rs index b352d9ff..bbf10680 100644 --- a/roslibrust/src/ros1/subscriber.rs +++ b/roslibrust_ros1/src/subscriber.rs @@ -1,7 +1,7 @@ -use crate::ros1::{names::Name, tcpros::ConnectionHeader}; +use crate::{names::Name, tcpros::ConnectionHeader}; use abort_on_drop::ChildTask; use log::*; -use roslibrust_codegen::{RosMessageType, ShapeShifter}; +use roslibrust_common::{RosMessageType, ShapeShifter}; use std::{marker::PhantomData, sync::Arc}; use tokio::{ io::AsyncWriteExt, diff --git a/roslibrust/src/ros1/tcpros.rs b/roslibrust_ros1/src/tcpros.rs similarity index 100% rename from roslibrust/src/ros1/tcpros.rs rename to roslibrust_ros1/src/tcpros.rs diff --git a/roslibrust/tests/ros1_native_integration_tests.rs b/roslibrust_ros1/tests/ros1_native_integration_tests.rs similarity index 100% rename from roslibrust/tests/ros1_native_integration_tests.rs rename to roslibrust_ros1/tests/ros1_native_integration_tests.rs diff --git a/roslibrust/tests/ros1_xmlrpc.rs b/roslibrust_ros1/tests/ros1_xmlrpc.rs similarity index 98% rename from roslibrust/tests/ros1_xmlrpc.rs rename to roslibrust_ros1/tests/ros1_xmlrpc.rs index 4b2f2eac..f26046ec 100644 --- a/roslibrust/tests/ros1_xmlrpc.rs +++ b/roslibrust_ros1/tests/ros1_xmlrpc.rs @@ -1,4 +1,4 @@ -#[cfg(all(feature = "ros1", feature = "ros1_test"))] +#[cfg(feature = "ros1_test")] mod tests { use roslibrust::ros1::NodeHandle; use roslibrust_codegen::RosMessageType; diff --git a/roslibrust_test/Cargo.toml b/roslibrust_test/Cargo.toml index 5bbf04ea..7f2a5943 100644 --- a/roslibrust_test/Cargo.toml +++ b/roslibrust_test/Cargo.toml @@ -6,6 +6,8 @@ edition = "2021" [dependencies] env_logger = "0.10" roslibrust = { path = "../roslibrust", features = ["ros1"] } +roslibrust_common = { path = "../roslibrust_common" } +# TODO this shouldn't need to be here! roslibrust_codegen = { path = "../roslibrust_codegen" } lazy_static = "1.4" tokio = { version = "1.20", features = ["net", "sync"] } diff --git a/roslibrust_test/src/ros1.rs b/roslibrust_test/src/ros1.rs index 28bf3530..3756ce18 100644 --- a/roslibrust_test/src/ros1.rs +++ b/roslibrust_test/src/ros1.rs @@ -27,7 +27,7 @@ pub mod actionlib_msgs { pub r#stamp: ::roslibrust_codegen::integral_types::Time, pub r#id: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for GoalID { + impl ::roslibrust_common::RosMessageType for GoalID { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalID"; const MD5SUM: &'static str = "302881f31927c1df708a2dbab0e80ee8"; const DEFINITION: &'static str = r#"# The stamp should store the time at which this goal was requested. @@ -55,7 +55,7 @@ string id"#; pub r#status: u8, pub r#text: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for GoalStatus { + impl ::roslibrust_common::RosMessageType for GoalStatus { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalStatus"; const MD5SUM: &'static str = "d388f9b87b3c471f784434d671988d4a"; const DEFINITION: &'static str = r#"GoalID goal_id @@ -119,7 +119,7 @@ string id"#; pub r#header: std_msgs::Header, pub r#status_list: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for GoalStatusArray { + impl ::roslibrust_common::RosMessageType for GoalStatusArray { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalStatusArray"; const MD5SUM: &'static str = "8b2b82f13216d0a8ea88bd3af735e619"; const DEFINITION: &'static str = r#"# Stores the statuses for goals that are currently being tracked @@ -218,7 +218,7 @@ pub mod diagnostic_msgs { pub r#header: std_msgs::Header, pub r#status: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for DiagnosticArray { + impl ::roslibrust_common::RosMessageType for DiagnosticArray { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/DiagnosticArray"; const MD5SUM: &'static str = "60810da900de1dd6ddd437c3503511da"; const DEFINITION: &'static str = r#"# This message is used to send diagnostic information about the state of the robot @@ -281,7 +281,7 @@ string frame_id"#; pub r#hardware_id: ::std::string::String, pub r#values: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for DiagnosticStatus { + impl ::roslibrust_common::RosMessageType for DiagnosticStatus { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/DiagnosticStatus"; const MD5SUM: &'static str = "d0ce08bc6e5ba34c7754f563a9cabaf1"; const DEFINITION: &'static str = r#"# This message holds the status of an individual component of the robot. @@ -324,7 +324,7 @@ string value # a value to track over time"#; pub r#key: ::std::string::String, pub r#value: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for KeyValue { + impl ::roslibrust_common::RosMessageType for KeyValue { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/KeyValue"; const MD5SUM: &'static str = "cf57fdc6617a881a88c16e768132149c"; const DEFINITION: &'static str = r#"string key # what to label this value when viewing @@ -343,7 +343,7 @@ string value # a value to track over time"#; pub struct AddDiagnosticsRequest { pub r#load_namespace: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for AddDiagnosticsRequest { + impl ::roslibrust_common::RosMessageType for AddDiagnosticsRequest { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/AddDiagnosticsRequest"; const MD5SUM: &'static str = "c26cf6e164288fbc6050d74f838bcdf0"; const DEFINITION: &'static str = r#"# This service is used as part of the process for loading analyzers at runtime, @@ -378,7 +378,7 @@ string load_namespace"#; pub r#success: bool, pub r#message: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for AddDiagnosticsResponse { + impl ::roslibrust_common::RosMessageType for AddDiagnosticsResponse { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/AddDiagnosticsResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; const DEFINITION: &'static str = r#"# True if diagnostic aggregator was updated with new diagnostics, False @@ -392,7 +392,7 @@ string message"#; } #[allow(dead_code)] pub struct AddDiagnostics {} - impl ::roslibrust_codegen::RosServiceType for AddDiagnostics { + impl ::roslibrust_common::RosServiceType for AddDiagnostics { const ROS_SERVICE_NAME: &'static str = "diagnostic_msgs/AddDiagnostics"; const MD5SUM: &'static str = "e6ac9bbde83d0d3186523c3687aecaee"; type Request = AddDiagnosticsRequest; @@ -409,7 +409,7 @@ string message"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct SelfTestRequest {} - impl ::roslibrust_codegen::RosMessageType for SelfTestRequest { + impl ::roslibrust_common::RosMessageType for SelfTestRequest { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/SelfTestRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -429,7 +429,7 @@ string message"#; pub r#passed: u8, pub r#status: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for SelfTestResponse { + impl ::roslibrust_common::RosMessageType for SelfTestResponse { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/SelfTestResponse"; const MD5SUM: &'static str = "ac21b1bab7ab17546986536c22eb34e9"; const DEFINITION: &'static str = r#"string id @@ -462,7 +462,7 @@ string value # a value to track over time"#; } #[allow(dead_code)] pub struct SelfTest {} - impl ::roslibrust_codegen::RosServiceType for SelfTest { + impl ::roslibrust_common::RosServiceType for SelfTest { const ROS_SERVICE_NAME: &'static str = "diagnostic_msgs/SelfTest"; const MD5SUM: &'static str = "ac21b1bab7ab17546986536c22eb34e9"; type Request = SelfTestRequest; @@ -498,7 +498,7 @@ pub mod geometry_msgs { pub r#linear: self::Vector3, pub r#angular: self::Vector3, } - impl ::roslibrust_codegen::RosMessageType for Accel { + impl ::roslibrust_common::RosMessageType for Accel { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Accel"; const MD5SUM: &'static str = "9f195f881246fdfa2798d1d3eebca84a"; const DEFINITION: &'static str = r#"# This expresses acceleration in free space broken into its linear and angular parts. @@ -531,7 +531,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#accel: self::Accel, } - impl ::roslibrust_codegen::RosMessageType for AccelStamped { + impl ::roslibrust_common::RosMessageType for AccelStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelStamped"; const MD5SUM: &'static str = "d8a98a5d81351b6eb0578c78557e7659"; const DEFINITION: &'static str = r#"# An accel with reference coordinate frame and timestamp @@ -598,7 +598,7 @@ string frame_id"#; #[serde(with = "::roslibrust_codegen::BigArray")] pub r#covariance: [f64; 36], } - impl ::roslibrust_codegen::RosMessageType for AccelWithCovariance { + impl ::roslibrust_common::RosMessageType for AccelWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovariance"; const MD5SUM: &'static str = "ad5a718d699c6be72a02b8d6a139f334"; const DEFINITION: &'static str = r#"# This expresses acceleration in free space with uncertainty. @@ -654,7 +654,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#accel: self::AccelWithCovariance, } - impl ::roslibrust_codegen::RosMessageType for AccelWithCovarianceStamped { + impl ::roslibrust_common::RosMessageType for AccelWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovarianceStamped"; const MD5SUM: &'static str = "96adb295225031ec8d57fb4251b0a886"; const DEFINITION: &'static str = r#"# This represents an estimated accel with reference coordinate frame and timestamp. @@ -765,7 +765,7 @@ string frame_id"#; pub r#iyz: f64, pub r#izz: f64, } - impl ::roslibrust_codegen::RosMessageType for Inertia { + impl ::roslibrust_common::RosMessageType for Inertia { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Inertia"; const MD5SUM: &'static str = "1d26e4bb6c83ff141c5cf0d883c2b0fe"; const DEFINITION: &'static str = r#"# Mass [kg] @@ -811,7 +811,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#inertia: self::Inertia, } - impl ::roslibrust_codegen::RosMessageType for InertiaStamped { + impl ::roslibrust_common::RosMessageType for InertiaStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/InertiaStamped"; const MD5SUM: &'static str = "ddee48caeab5a966c5e8d166654a9ac7"; const DEFINITION: &'static str = r#"Header header @@ -889,7 +889,7 @@ string frame_id"#; pub r#y: f64, pub r#z: f64, } - impl ::roslibrust_codegen::RosMessageType for Point { + impl ::roslibrust_common::RosMessageType for Point { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Point"; const MD5SUM: &'static str = "4a842b65f413084dc2b10fb484ea7f17"; const DEFINITION: &'static str = r#"# This contains the position of a point in free space @@ -912,7 +912,7 @@ float64 z"#; pub r#y: f32, pub r#z: f32, } - impl ::roslibrust_codegen::RosMessageType for Point32 { + impl ::roslibrust_common::RosMessageType for Point32 { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Point32"; const MD5SUM: &'static str = "cc153912f1453b708d221682bc23d9ac"; const DEFINITION: &'static str = r#"# This contains the position of a point in free space(with 32 bits of precision). @@ -941,7 +941,7 @@ float32 z"#; pub r#header: std_msgs::Header, pub r#point: self::Point, } - impl ::roslibrust_codegen::RosMessageType for PointStamped { + impl ::roslibrust_common::RosMessageType for PointStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PointStamped"; const MD5SUM: &'static str = "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; const DEFINITION: &'static str = r#"# This represents a Point with reference coordinate frame and timestamp @@ -982,7 +982,7 @@ string frame_id"#; pub struct Polygon { pub r#points: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Polygon { + impl ::roslibrust_common::RosMessageType for Polygon { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Polygon"; const MD5SUM: &'static str = "cd60a26494a087f577976f0329fa120e"; const DEFINITION: &'static str = r#"#A specification of a polygon where the first and last points are assumed to be connected @@ -1015,7 +1015,7 @@ float32 z"#; pub r#header: std_msgs::Header, pub r#polygon: self::Polygon, } - impl ::roslibrust_codegen::RosMessageType for PolygonStamped { + impl ::roslibrust_common::RosMessageType for PolygonStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PolygonStamped"; const MD5SUM: &'static str = "c6be8f7dc3bee7fe9e8d296070f53340"; const DEFINITION: &'static str = r#"# This represents a Polygon with reference coordinate frame and timestamp @@ -1081,7 +1081,7 @@ string frame_id"#; pub r#position: self::Point, pub r#orientation: self::Quaternion, } - impl ::roslibrust_codegen::RosMessageType for Pose { + impl ::roslibrust_common::RosMessageType for Pose { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Pose"; const MD5SUM: &'static str = "e45d45a5a1ce597b249e23fb30fc871f"; const DEFINITION: &'static str = r#"# A representation of pose in free space, composed of position and orientation. @@ -1117,7 +1117,7 @@ float64 w"#; pub r#y: f64, pub r#theta: f64, } - impl ::roslibrust_codegen::RosMessageType for Pose2D { + impl ::roslibrust_common::RosMessageType for Pose2D { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Pose2D"; const MD5SUM: &'static str = "938fa65709584ad8e77d238529be13b8"; const DEFINITION: &'static str = r#"# Deprecated @@ -1148,7 +1148,7 @@ float64 theta"#; pub r#header: std_msgs::Header, pub r#poses: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for PoseArray { + impl ::roslibrust_common::RosMessageType for PoseArray { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseArray"; const MD5SUM: &'static str = "916c28c5764443f268b296bb671b9d97"; const DEFINITION: &'static str = r#"# An array of poses with a header for global reference. @@ -1219,7 +1219,7 @@ string frame_id"#; pub r#header: std_msgs::Header, pub r#pose: self::Pose, } - impl ::roslibrust_codegen::RosMessageType for PoseStamped { + impl ::roslibrust_common::RosMessageType for PoseStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseStamped"; const MD5SUM: &'static str = "d3812c3cbc69362b77dc0b19b345f8f5"; const DEFINITION: &'static str = r#"# A Pose with reference coordinate frame and timestamp @@ -1290,7 +1290,7 @@ string frame_id"#; #[serde(with = "::roslibrust_codegen::BigArray")] pub r#covariance: [f64; 36], } - impl ::roslibrust_codegen::RosMessageType for PoseWithCovariance { + impl ::roslibrust_common::RosMessageType for PoseWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovariance"; const MD5SUM: &'static str = "c23e848cf1b7533a8d7c259073a97e6f"; const DEFINITION: &'static str = r#"# This represents a pose in free space with uncertainty. @@ -1350,7 +1350,7 @@ float64 w"#; pub r#header: std_msgs::Header, pub r#pose: self::PoseWithCovariance, } - impl ::roslibrust_codegen::RosMessageType for PoseWithCovarianceStamped { + impl ::roslibrust_common::RosMessageType for PoseWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovarianceStamped"; const MD5SUM: &'static str = "953b798c0f514ff060a53a3498ce6246"; const DEFINITION: &'static str = r#"# This expresses an estimated pose with a reference coordinate frame and timestamp @@ -1466,7 +1466,7 @@ string frame_id"#; pub r#z: f64, pub r#w: f64, } - impl ::roslibrust_codegen::RosMessageType for Quaternion { + impl ::roslibrust_common::RosMessageType for Quaternion { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Quaternion"; const MD5SUM: &'static str = "a779879fadf0160734f906b8c19c7004"; const DEFINITION: &'static str = r#"# This represents an orientation in free space in quaternion form. @@ -1490,7 +1490,7 @@ float64 w"#; pub r#header: std_msgs::Header, pub r#quaternion: self::Quaternion, } - impl ::roslibrust_codegen::RosMessageType for QuaternionStamped { + impl ::roslibrust_common::RosMessageType for QuaternionStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/QuaternionStamped"; const MD5SUM: &'static str = "e57f1e547e0e1fd13504588ffc8334e2"; const DEFINITION: &'static str = r#"# This represents an orientation with reference coordinate frame and timestamp. @@ -1535,7 +1535,7 @@ string frame_id"#; pub r#translation: self::Vector3, pub r#rotation: self::Quaternion, } - impl ::roslibrust_codegen::RosMessageType for Transform { + impl ::roslibrust_common::RosMessageType for Transform { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Transform"; const MD5SUM: &'static str = "ac9eff44abf714214112b05d54a3cf9b"; const DEFINITION: &'static str = r#"# This represents the transform between two coordinate frames in free space. @@ -1578,7 +1578,7 @@ float64 z"#; pub r#child_frame_id: ::std::string::String, pub r#transform: self::Transform, } - impl ::roslibrust_codegen::RosMessageType for TransformStamped { + impl ::roslibrust_common::RosMessageType for TransformStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TransformStamped"; const MD5SUM: &'static str = "b5764a33bfeb3588febc2682852579b0"; const DEFINITION: &'static str = r#"# This expresses a transform from coordinate frame header.frame_id @@ -1667,7 +1667,7 @@ string frame_id"#; pub r#linear: self::Vector3, pub r#angular: self::Vector3, } - impl ::roslibrust_codegen::RosMessageType for Twist { + impl ::roslibrust_common::RosMessageType for Twist { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Twist"; const MD5SUM: &'static str = "9f195f881246fdfa2798d1d3eebca84a"; const DEFINITION: &'static str = r#"# This expresses velocity in free space broken into its linear and angular parts. @@ -1700,7 +1700,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#twist: self::Twist, } - impl ::roslibrust_codegen::RosMessageType for TwistStamped { + impl ::roslibrust_common::RosMessageType for TwistStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistStamped"; const MD5SUM: &'static str = "98d34b0043a2093cf9d9345ab6eef12e"; const DEFINITION: &'static str = r#"# A twist with reference coordinate frame and timestamp @@ -1767,7 +1767,7 @@ string frame_id"#; #[serde(with = "::roslibrust_codegen::BigArray")] pub r#covariance: [f64; 36], } - impl ::roslibrust_codegen::RosMessageType for TwistWithCovariance { + impl ::roslibrust_common::RosMessageType for TwistWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovariance"; const MD5SUM: &'static str = "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; const DEFINITION: &'static str = r#"# This expresses velocity in free space with uncertainty. @@ -1823,7 +1823,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#twist: self::TwistWithCovariance, } - impl ::roslibrust_codegen::RosMessageType for TwistWithCovarianceStamped { + impl ::roslibrust_common::RosMessageType for TwistWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovarianceStamped"; const MD5SUM: &'static str = "8927a1a12fb2607ceea095b2dc440a96"; const DEFINITION: &'static str = r#"# This represents an estimated twist with reference coordinate frame and timestamp. @@ -1929,7 +1929,7 @@ string frame_id"#; pub r#y: f64, pub r#z: f64, } - impl ::roslibrust_codegen::RosMessageType for Vector3 { + impl ::roslibrust_common::RosMessageType for Vector3 { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Vector3"; const MD5SUM: &'static str = "4a842b65f413084dc2b10fb484ea7f17"; const DEFINITION: &'static str = r#"# This represents a vector in free space. @@ -1957,7 +1957,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#vector: self::Vector3, } - impl ::roslibrust_codegen::RosMessageType for Vector3Stamped { + impl ::roslibrust_common::RosMessageType for Vector3Stamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Vector3Stamped"; const MD5SUM: &'static str = "7b324c7325e683bf02a9b14b01090ec7"; const DEFINITION: &'static str = r#"# This represents a Vector3 with reference coordinate frame and timestamp @@ -2005,7 +2005,7 @@ string frame_id"#; pub r#force: self::Vector3, pub r#torque: self::Vector3, } - impl ::roslibrust_codegen::RosMessageType for Wrench { + impl ::roslibrust_common::RosMessageType for Wrench { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Wrench"; const MD5SUM: &'static str = "4f539cf138b23283b520fd271b567936"; const DEFINITION: &'static str = r#"# This represents force in free space, separated into @@ -2039,7 +2039,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#wrench: self::Wrench, } - impl ::roslibrust_codegen::RosMessageType for WrenchStamped { + impl ::roslibrust_common::RosMessageType for WrenchStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/WrenchStamped"; const MD5SUM: &'static str = "d78d3cb249ce23087ade7e7d0c40cfa7"; const DEFINITION: &'static str = r#"# A wrench with reference coordinate frame and timestamp @@ -2122,7 +2122,7 @@ pub mod nav_msgs { pub r#action_result: self::GetMapActionResult, pub r#action_feedback: self::GetMapActionFeedback, } - impl ::roslibrust_codegen::RosMessageType for GetMapAction { + impl ::roslibrust_common::RosMessageType for GetMapAction { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapAction"; const MD5SUM: &'static str = "e611ad23fbf237c031b7536416dc7cd7"; const DEFINITION: &'static str = r#"GetMapActionGoal action_goal @@ -3176,7 +3176,7 @@ string frame_id"#; pub r#status: actionlib_msgs::GoalStatus, pub r#feedback: self::GetMapFeedback, } - impl ::roslibrust_codegen::RosMessageType for GetMapActionFeedback { + impl ::roslibrust_common::RosMessageType for GetMapActionFeedback { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapActionFeedback"; const MD5SUM: &'static str = "aae20e09065c3809e8a8e87c4c8953fd"; const DEFINITION: &'static str = r#"Header header @@ -3262,7 +3262,7 @@ string frame_id"#; pub r#goal_id: actionlib_msgs::GoalID, pub r#goal: self::GetMapGoal, } - impl ::roslibrust_codegen::RosMessageType for GetMapActionGoal { + impl ::roslibrust_common::RosMessageType for GetMapActionGoal { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapActionGoal"; const MD5SUM: &'static str = "4b30be6cd12b9e72826df56b481f40e0"; const DEFINITION: &'static str = r#"Header header @@ -3313,7 +3313,7 @@ string frame_id"#; pub r#status: actionlib_msgs::GoalStatus, pub r#result: self::GetMapResult, } - impl ::roslibrust_codegen::RosMessageType for GetMapActionResult { + impl ::roslibrust_common::RosMessageType for GetMapActionResult { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapActionResult"; const MD5SUM: &'static str = "ac66e5b9a79bb4bbd33dab245236c892"; const DEFINITION: &'static str = r#"Header header @@ -3790,7 +3790,7 @@ string frame_id"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct GetMapFeedback {} - impl ::roslibrust_codegen::RosMessageType for GetMapFeedback { + impl ::roslibrust_common::RosMessageType for GetMapFeedback { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapFeedback"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#"# no feedback"#; @@ -3806,7 +3806,7 @@ string frame_id"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct GetMapGoal {} - impl ::roslibrust_codegen::RosMessageType for GetMapGoal { + impl ::roslibrust_common::RosMessageType for GetMapGoal { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapGoal"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#"# Get the map as a nav_msgs/OccupancyGrid"#; @@ -3824,7 +3824,7 @@ string frame_id"#; pub struct GetMapResult { pub r#map: self::OccupancyGrid, } - impl ::roslibrust_codegen::RosMessageType for GetMapResult { + impl ::roslibrust_common::RosMessageType for GetMapResult { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapResult"; const MD5SUM: &'static str = "6cdd0a18e0aff5b0a3ca2326a89b54ff"; const DEFINITION: &'static str = r#"nav_msgs/OccupancyGrid map @@ -4050,7 +4050,7 @@ string frame_id"#; pub r#cell_height: f32, pub r#cells: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for GridCells { + impl ::roslibrust_common::RosMessageType for GridCells { const ROS_TYPE_NAME: &'static str = "nav_msgs/GridCells"; const MD5SUM: &'static str = "b9e4f5df6d28e272ebde00a3994830f5"; const DEFINITION: &'static str = r#"#an array of cells in a 2D grid @@ -4097,7 +4097,7 @@ string frame_id"#; pub r#height: u32, pub r#origin: geometry_msgs::Pose, } - impl ::roslibrust_codegen::RosMessageType for MapMetaData { + impl ::roslibrust_common::RosMessageType for MapMetaData { const ROS_TYPE_NAME: &'static str = "nav_msgs/MapMetaData"; const MD5SUM: &'static str = "10cfc8a2818024d3248802c00c95f11b"; const DEFINITION: &'static str = r#"# This hold basic information about the characterists of the OccupancyGrid @@ -4162,7 +4162,7 @@ float64 w"#; pub r#info: self::MapMetaData, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for OccupancyGrid { + impl ::roslibrust_common::RosMessageType for OccupancyGrid { const ROS_TYPE_NAME: &'static str = "nav_msgs/OccupancyGrid"; const MD5SUM: &'static str = "3381f2d731d4076ec5c71b0759edbe4e"; const DEFINITION: &'static str = r#"# This represents a 2-D grid map, in which each cell represents the probability of @@ -4289,7 +4289,7 @@ string frame_id"#; pub r#pose: geometry_msgs::PoseWithCovariance, pub r#twist: geometry_msgs::TwistWithCovariance, } - impl ::roslibrust_codegen::RosMessageType for Odometry { + impl ::roslibrust_common::RosMessageType for Odometry { const ROS_TYPE_NAME: &'static str = "nav_msgs/Odometry"; const MD5SUM: &'static str = "cd5e73d190d741a2f92e81eda573aca7"; const DEFINITION: &'static str = r#"# This represents an estimate of a position and velocity in free space. @@ -4475,7 +4475,7 @@ string frame_id"#; pub r#header: std_msgs::Header, pub r#poses: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Path { + impl ::roslibrust_common::RosMessageType for Path { const ROS_TYPE_NAME: &'static str = "nav_msgs/Path"; const MD5SUM: &'static str = "6227e2b7e9cce15051f669a5e197bbf7"; const DEFINITION: &'static str = r#"#An array of poses that represents a Path for a robot to follow @@ -4594,7 +4594,7 @@ string frame_id"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct GetMapRequest {} - impl ::roslibrust_codegen::RosMessageType for GetMapRequest { + impl ::roslibrust_common::RosMessageType for GetMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#"# Get the map as a nav_msgs/OccupancyGrid"#; @@ -4612,7 +4612,7 @@ string frame_id"#; pub struct GetMapResponse { pub r#map: self::OccupancyGrid, } - impl ::roslibrust_codegen::RosMessageType for GetMapResponse { + impl ::roslibrust_common::RosMessageType for GetMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapResponse"; const MD5SUM: &'static str = "6cdd0a18e0aff5b0a3ca2326a89b54ff"; const DEFINITION: &'static str = r#"nav_msgs/OccupancyGrid map @@ -4824,7 +4824,7 @@ string frame_id"#; } #[allow(dead_code)] pub struct GetMap {} - impl ::roslibrust_codegen::RosServiceType for GetMap { + impl ::roslibrust_common::RosServiceType for GetMap { const ROS_SERVICE_NAME: &'static str = "nav_msgs/GetMap"; const MD5SUM: &'static str = "6cdd0a18e0aff5b0a3ca2326a89b54ff"; type Request = GetMapRequest; @@ -4845,7 +4845,7 @@ string frame_id"#; pub r#goal: geometry_msgs::PoseStamped, pub r#tolerance: f32, } - impl ::roslibrust_codegen::RosMessageType for GetPlanRequest { + impl ::roslibrust_common::RosMessageType for GetPlanRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetPlanRequest"; const MD5SUM: &'static str = "e25a43e0752bcca599a8c2eef8282df8"; const DEFINITION: &'static str = r#"# Get a plan from the current position to the goal Pose @@ -4974,7 +4974,7 @@ string frame_id"#; pub struct GetPlanResponse { pub r#plan: self::Path, } - impl ::roslibrust_codegen::RosMessageType for GetPlanResponse { + impl ::roslibrust_common::RosMessageType for GetPlanResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetPlanResponse"; const MD5SUM: &'static str = "0002bc113c0259d71f6cf8cbc9430e18"; const DEFINITION: &'static str = r#"nav_msgs/Path plan @@ -5188,7 +5188,7 @@ string frame_id"#; } #[allow(dead_code)] pub struct GetPlan {} - impl ::roslibrust_codegen::RosServiceType for GetPlan { + impl ::roslibrust_common::RosServiceType for GetPlan { const ROS_SERVICE_NAME: &'static str = "nav_msgs/GetPlan"; const MD5SUM: &'static str = "421c8ea4d21c6c9db7054b4bbdf1e024"; type Request = GetPlanRequest; @@ -5207,7 +5207,7 @@ string frame_id"#; pub struct LoadMapRequest { pub r#map_url: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for LoadMapRequest { + impl ::roslibrust_common::RosMessageType for LoadMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/LoadMapRequest"; const MD5SUM: &'static str = "3813ba1ae85fbcd4dc88c90f1426b90b"; const DEFINITION: &'static str = r#"# URL of map resource @@ -5229,7 +5229,7 @@ string map_url"#; pub r#map: self::OccupancyGrid, pub r#result: u8, } - impl ::roslibrust_codegen::RosMessageType for LoadMapResponse { + impl ::roslibrust_common::RosMessageType for LoadMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/LoadMapResponse"; const MD5SUM: &'static str = "079b9c828e9f7c1918bf86932fd7267e"; const DEFINITION: &'static str = r#"# Result code defintions @@ -5458,7 +5458,7 @@ string frame_id"#; } #[allow(dead_code)] pub struct LoadMap {} - impl ::roslibrust_codegen::RosServiceType for LoadMap { + impl ::roslibrust_common::RosServiceType for LoadMap { const ROS_SERVICE_NAME: &'static str = "nav_msgs/LoadMap"; const MD5SUM: &'static str = "22e647fdfbe3b23c8c9f419908afaebd"; type Request = LoadMapRequest; @@ -5478,7 +5478,7 @@ string frame_id"#; pub r#map: self::OccupancyGrid, pub r#initial_pose: geometry_msgs::PoseWithCovarianceStamped, } - impl ::roslibrust_codegen::RosMessageType for SetMapRequest { + impl ::roslibrust_common::RosMessageType for SetMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/SetMapRequest"; const MD5SUM: &'static str = "91149a20d7be299b87c340df8cc94fd4"; const DEFINITION: &'static str = r#"# Set a new map together with an initial pose @@ -5845,14 +5845,14 @@ string frame_id"#; pub struct SetMapResponse { pub r#success: bool, } - impl ::roslibrust_codegen::RosMessageType for SetMapResponse { + impl ::roslibrust_common::RosMessageType for SetMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/SetMapResponse"; const MD5SUM: &'static str = "358e233cde0c8a8bcfea4ce193f8fc15"; const DEFINITION: &'static str = r#"bool success"#; } #[allow(dead_code)] pub struct SetMap {} - impl ::roslibrust_codegen::RosServiceType for SetMap { + impl ::roslibrust_common::RosServiceType for SetMap { const ROS_SERVICE_NAME: &'static str = "nav_msgs/SetMap"; const MD5SUM: &'static str = "c36922319011e63ed7784112ad4fdd32"; type Request = SetMapRequest; @@ -5893,7 +5893,7 @@ pub mod rosapi { pub r#constnames: ::std::vec::Vec<::std::string::String>, pub r#constvalues: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for TypeDef { + impl ::roslibrust_common::RosMessageType for TypeDef { const ROS_TYPE_NAME: &'static str = "rosapi/TypeDef"; const MD5SUM: &'static str = "80597571d79bbeef6c9c4d98f30116a0"; const DEFINITION: &'static str = r#"string type @@ -5917,7 +5917,7 @@ string[] constvalues"#; pub struct DeleteParamRequest { pub r#name: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for DeleteParamRequest { + impl ::roslibrust_common::RosMessageType for DeleteParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/DeleteParamRequest"; const MD5SUM: &'static str = "c1f3d28f1b044c871e6eff2e9fc3c667"; const DEFINITION: &'static str = r#"string name"#; @@ -5933,14 +5933,14 @@ string[] constvalues"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct DeleteParamResponse {} - impl ::roslibrust_codegen::RosMessageType for DeleteParamResponse { + impl ::roslibrust_common::RosMessageType for DeleteParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/DeleteParamResponse"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; } #[allow(dead_code)] pub struct DeleteParam {} - impl ::roslibrust_codegen::RosServiceType for DeleteParam { + impl ::roslibrust_common::RosServiceType for DeleteParam { const ROS_SERVICE_NAME: &'static str = "rosapi/DeleteParam"; const MD5SUM: &'static str = "c1f3d28f1b044c871e6eff2e9fc3c667"; type Request = DeleteParamRequest; @@ -5957,7 +5957,7 @@ string[] constvalues"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct GetActionServersRequest {} - impl ::roslibrust_codegen::RosMessageType for GetActionServersRequest { + impl ::roslibrust_common::RosMessageType for GetActionServersRequest { const ROS_TYPE_NAME: &'static str = "rosapi/GetActionServersRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -5975,14 +5975,14 @@ string[] constvalues"#; pub struct GetActionServersResponse { pub r#action_servers: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for GetActionServersResponse { + impl ::roslibrust_common::RosMessageType for GetActionServersResponse { const ROS_TYPE_NAME: &'static str = "rosapi/GetActionServersResponse"; const MD5SUM: &'static str = "46807ba271844ac5ba4730a47556b236"; const DEFINITION: &'static str = r#"string[] action_servers"#; } #[allow(dead_code)] pub struct GetActionServers {} - impl ::roslibrust_codegen::RosServiceType for GetActionServers { + impl ::roslibrust_common::RosServiceType for GetActionServers { const ROS_SERVICE_NAME: &'static str = "rosapi/GetActionServers"; const MD5SUM: &'static str = "46807ba271844ac5ba4730a47556b236"; type Request = GetActionServersRequest; @@ -6002,7 +6002,7 @@ string[] constvalues"#; pub r#name: ::std::string::String, pub r#default: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for GetParamRequest { + impl ::roslibrust_common::RosMessageType for GetParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/GetParamRequest"; const MD5SUM: &'static str = "1cc3f281ee24ba9406c3e498e4da686f"; const DEFINITION: &'static str = r#"string name @@ -6021,14 +6021,14 @@ string default"#; pub struct GetParamResponse { pub r#value: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for GetParamResponse { + impl ::roslibrust_common::RosMessageType for GetParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/GetParamResponse"; const MD5SUM: &'static str = "64e58419496c7248b4ef25731f88b8c3"; const DEFINITION: &'static str = r#"string value"#; } #[allow(dead_code)] pub struct GetParam {} - impl ::roslibrust_codegen::RosServiceType for GetParam { + impl ::roslibrust_common::RosServiceType for GetParam { const ROS_SERVICE_NAME: &'static str = "rosapi/GetParam"; const MD5SUM: &'static str = "e36fd90759dbac1c5159140a7fa8c644"; type Request = GetParamRequest; @@ -6045,7 +6045,7 @@ string default"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct GetParamNamesRequest {} - impl ::roslibrust_codegen::RosMessageType for GetParamNamesRequest { + impl ::roslibrust_common::RosMessageType for GetParamNamesRequest { const ROS_TYPE_NAME: &'static str = "rosapi/GetParamNamesRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -6063,14 +6063,14 @@ string default"#; pub struct GetParamNamesResponse { pub r#names: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for GetParamNamesResponse { + impl ::roslibrust_common::RosMessageType for GetParamNamesResponse { const ROS_TYPE_NAME: &'static str = "rosapi/GetParamNamesResponse"; const MD5SUM: &'static str = "dc7ae3609524b18034e49294a4ce670e"; const DEFINITION: &'static str = r#"string[] names"#; } #[allow(dead_code)] pub struct GetParamNames {} - impl ::roslibrust_codegen::RosServiceType for GetParamNames { + impl ::roslibrust_common::RosServiceType for GetParamNames { const ROS_SERVICE_NAME: &'static str = "rosapi/GetParamNames"; const MD5SUM: &'static str = "dc7ae3609524b18034e49294a4ce670e"; type Request = GetParamNamesRequest; @@ -6087,7 +6087,7 @@ string default"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct GetTimeRequest {} - impl ::roslibrust_codegen::RosMessageType for GetTimeRequest { + impl ::roslibrust_common::RosMessageType for GetTimeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/GetTimeRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -6105,14 +6105,14 @@ string default"#; pub struct GetTimeResponse { pub r#time: ::roslibrust_codegen::integral_types::Time, } - impl ::roslibrust_codegen::RosMessageType for GetTimeResponse { + impl ::roslibrust_common::RosMessageType for GetTimeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/GetTimeResponse"; const MD5SUM: &'static str = "556a4fb76023a469987922359d08a844"; const DEFINITION: &'static str = r#"time time"#; } #[allow(dead_code)] pub struct GetTime {} - impl ::roslibrust_codegen::RosServiceType for GetTime { + impl ::roslibrust_common::RosServiceType for GetTime { const ROS_SERVICE_NAME: &'static str = "rosapi/GetTime"; const MD5SUM: &'static str = "556a4fb76023a469987922359d08a844"; type Request = GetTimeRequest; @@ -6131,7 +6131,7 @@ string default"#; pub struct HasParamRequest { pub r#name: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for HasParamRequest { + impl ::roslibrust_common::RosMessageType for HasParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/HasParamRequest"; const MD5SUM: &'static str = "c1f3d28f1b044c871e6eff2e9fc3c667"; const DEFINITION: &'static str = r#"string name"#; @@ -6149,14 +6149,14 @@ string default"#; pub struct HasParamResponse { pub r#exists: bool, } - impl ::roslibrust_codegen::RosMessageType for HasParamResponse { + impl ::roslibrust_common::RosMessageType for HasParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/HasParamResponse"; const MD5SUM: &'static str = "e8c90de4adc1219c86af9c2874c0c1b5"; const DEFINITION: &'static str = r#"bool exists"#; } #[allow(dead_code)] pub struct HasParam {} - impl ::roslibrust_codegen::RosServiceType for HasParam { + impl ::roslibrust_common::RosServiceType for HasParam { const ROS_SERVICE_NAME: &'static str = "rosapi/HasParam"; const MD5SUM: &'static str = "ed3df286bd6dff9b961770f577454ea9"; type Request = HasParamRequest; @@ -6175,7 +6175,7 @@ string default"#; pub struct MessageDetailsRequest { pub r#type: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for MessageDetailsRequest { + impl ::roslibrust_common::RosMessageType for MessageDetailsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/MessageDetailsRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; const DEFINITION: &'static str = r#"string type"#; @@ -6193,7 +6193,7 @@ string default"#; pub struct MessageDetailsResponse { pub r#typedefs: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MessageDetailsResponse { + impl ::roslibrust_common::RosMessageType for MessageDetailsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/MessageDetailsResponse"; const MD5SUM: &'static str = "a6b8995777f214f2ed97a1e4890feb10"; const DEFINITION: &'static str = r#"TypeDef[] typedefs @@ -6209,7 +6209,7 @@ string[] constvalues"#; } #[allow(dead_code)] pub struct MessageDetails {} - impl ::roslibrust_codegen::RosServiceType for MessageDetails { + impl ::roslibrust_common::RosServiceType for MessageDetails { const ROS_SERVICE_NAME: &'static str = "rosapi/MessageDetails"; const MD5SUM: &'static str = "f9c88144f6f6bd888dd99d4e0411905d"; type Request = MessageDetailsRequest; @@ -6228,7 +6228,7 @@ string[] constvalues"#; pub struct NodeDetailsRequest { pub r#node: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for NodeDetailsRequest { + impl ::roslibrust_common::RosMessageType for NodeDetailsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/NodeDetailsRequest"; const MD5SUM: &'static str = "a94c40e70a4b82863e6e52ec16732447"; const DEFINITION: &'static str = r#"string node"#; @@ -6248,7 +6248,7 @@ string[] constvalues"#; pub r#publishing: ::std::vec::Vec<::std::string::String>, pub r#services: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for NodeDetailsResponse { + impl ::roslibrust_common::RosMessageType for NodeDetailsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/NodeDetailsResponse"; const MD5SUM: &'static str = "3da1cb16c6ec5885ad291735b6244a48"; const DEFINITION: &'static str = r#"string[] subscribing @@ -6257,7 +6257,7 @@ string[] services"#; } #[allow(dead_code)] pub struct NodeDetails {} - impl ::roslibrust_codegen::RosServiceType for NodeDetails { + impl ::roslibrust_common::RosServiceType for NodeDetails { const ROS_SERVICE_NAME: &'static str = "rosapi/NodeDetails"; const MD5SUM: &'static str = "e1d0ced5ab8d5edb5fc09c98eb1d46f6"; type Request = NodeDetailsRequest; @@ -6274,7 +6274,7 @@ string[] services"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct NodesRequest {} - impl ::roslibrust_codegen::RosMessageType for NodesRequest { + impl ::roslibrust_common::RosMessageType for NodesRequest { const ROS_TYPE_NAME: &'static str = "rosapi/NodesRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -6292,14 +6292,14 @@ string[] services"#; pub struct NodesResponse { pub r#nodes: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for NodesResponse { + impl ::roslibrust_common::RosMessageType for NodesResponse { const ROS_TYPE_NAME: &'static str = "rosapi/NodesResponse"; const MD5SUM: &'static str = "3d07bfda1268b4f76b16b7ba8a82665d"; const DEFINITION: &'static str = r#"string[] nodes"#; } #[allow(dead_code)] pub struct Nodes {} - impl ::roslibrust_codegen::RosServiceType for Nodes { + impl ::roslibrust_common::RosServiceType for Nodes { const ROS_SERVICE_NAME: &'static str = "rosapi/Nodes"; const MD5SUM: &'static str = "3d07bfda1268b4f76b16b7ba8a82665d"; type Request = NodesRequest; @@ -6318,7 +6318,7 @@ string[] services"#; pub struct PublishersRequest { pub r#topic: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for PublishersRequest { + impl ::roslibrust_common::RosMessageType for PublishersRequest { const ROS_TYPE_NAME: &'static str = "rosapi/PublishersRequest"; const MD5SUM: &'static str = "d8f94bae31b356b24d0427f80426d0c3"; const DEFINITION: &'static str = r#"string topic"#; @@ -6336,14 +6336,14 @@ string[] services"#; pub struct PublishersResponse { pub r#publishers: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for PublishersResponse { + impl ::roslibrust_common::RosMessageType for PublishersResponse { const ROS_TYPE_NAME: &'static str = "rosapi/PublishersResponse"; const MD5SUM: &'static str = "167d8030c4ca4018261dff8ae5083dc8"; const DEFINITION: &'static str = r#"string[] publishers"#; } #[allow(dead_code)] pub struct Publishers {} - impl ::roslibrust_codegen::RosServiceType for Publishers { + impl ::roslibrust_common::RosServiceType for Publishers { const ROS_SERVICE_NAME: &'static str = "rosapi/Publishers"; const MD5SUM: &'static str = "cb37f09944e7ba1fc08ee38f7a94291d"; type Request = PublishersRequest; @@ -6362,7 +6362,7 @@ string[] services"#; pub struct SearchParamRequest { pub r#name: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for SearchParamRequest { + impl ::roslibrust_common::RosMessageType for SearchParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/SearchParamRequest"; const MD5SUM: &'static str = "c1f3d28f1b044c871e6eff2e9fc3c667"; const DEFINITION: &'static str = r#"string name"#; @@ -6380,14 +6380,14 @@ string[] services"#; pub struct SearchParamResponse { pub r#global_name: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for SearchParamResponse { + impl ::roslibrust_common::RosMessageType for SearchParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/SearchParamResponse"; const MD5SUM: &'static str = "87c264f142c2aeca13349d90aeec0386"; const DEFINITION: &'static str = r#"string global_name"#; } #[allow(dead_code)] pub struct SearchParam {} - impl ::roslibrust_codegen::RosServiceType for SearchParam { + impl ::roslibrust_common::RosServiceType for SearchParam { const ROS_SERVICE_NAME: &'static str = "rosapi/SearchParam"; const MD5SUM: &'static str = "dfadc39f113c1cc6d7759508d8461d5a"; type Request = SearchParamRequest; @@ -6406,7 +6406,7 @@ string[] services"#; pub struct ServiceHostRequest { pub r#service: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServiceHostRequest { + impl ::roslibrust_common::RosMessageType for ServiceHostRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceHostRequest"; const MD5SUM: &'static str = "1cbcfa13b08f6d36710b9af8741e6112"; const DEFINITION: &'static str = r#"string service"#; @@ -6424,14 +6424,14 @@ string[] services"#; pub struct ServiceHostResponse { pub r#host: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServiceHostResponse { + impl ::roslibrust_common::RosMessageType for ServiceHostResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceHostResponse"; const MD5SUM: &'static str = "092ff9f63242a37704ce411703ec5eaf"; const DEFINITION: &'static str = r#"string host"#; } #[allow(dead_code)] pub struct ServiceHost {} - impl ::roslibrust_codegen::RosServiceType for ServiceHost { + impl ::roslibrust_common::RosServiceType for ServiceHost { const ROS_SERVICE_NAME: &'static str = "rosapi/ServiceHost"; const MD5SUM: &'static str = "a1b60006f8ee69637c856c94dd192f5a"; type Request = ServiceHostRequest; @@ -6450,7 +6450,7 @@ string[] services"#; pub struct ServiceNodeRequest { pub r#service: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServiceNodeRequest { + impl ::roslibrust_common::RosMessageType for ServiceNodeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceNodeRequest"; const MD5SUM: &'static str = "1cbcfa13b08f6d36710b9af8741e6112"; const DEFINITION: &'static str = r#"string service"#; @@ -6468,14 +6468,14 @@ string[] services"#; pub struct ServiceNodeResponse { pub r#node: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServiceNodeResponse { + impl ::roslibrust_common::RosMessageType for ServiceNodeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceNodeResponse"; const MD5SUM: &'static str = "a94c40e70a4b82863e6e52ec16732447"; const DEFINITION: &'static str = r#"string node"#; } #[allow(dead_code)] pub struct ServiceNode {} - impl ::roslibrust_codegen::RosServiceType for ServiceNode { + impl ::roslibrust_common::RosServiceType for ServiceNode { const ROS_SERVICE_NAME: &'static str = "rosapi/ServiceNode"; const MD5SUM: &'static str = "bd2a0a45fd7a73a86c8d6051d5a6db8a"; type Request = ServiceNodeRequest; @@ -6494,7 +6494,7 @@ string[] services"#; pub struct ServiceProvidersRequest { pub r#service: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServiceProvidersRequest { + impl ::roslibrust_common::RosMessageType for ServiceProvidersRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceProvidersRequest"; const MD5SUM: &'static str = "1cbcfa13b08f6d36710b9af8741e6112"; const DEFINITION: &'static str = r#"string service"#; @@ -6512,14 +6512,14 @@ string[] services"#; pub struct ServiceProvidersResponse { pub r#providers: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for ServiceProvidersResponse { + impl ::roslibrust_common::RosMessageType for ServiceProvidersResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceProvidersResponse"; const MD5SUM: &'static str = "945f6849f44f061c178ab393b12c1358"; const DEFINITION: &'static str = r#"string[] providers"#; } #[allow(dead_code)] pub struct ServiceProviders {} - impl ::roslibrust_codegen::RosServiceType for ServiceProviders { + impl ::roslibrust_common::RosServiceType for ServiceProviders { const ROS_SERVICE_NAME: &'static str = "rosapi/ServiceProviders"; const MD5SUM: &'static str = "f30b41d5e347454ae5483ee95eef5cc6"; type Request = ServiceProvidersRequest; @@ -6538,7 +6538,7 @@ string[] services"#; pub struct ServiceRequestDetailsRequest { pub r#type: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServiceRequestDetailsRequest { + impl ::roslibrust_common::RosMessageType for ServiceRequestDetailsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceRequestDetailsRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; const DEFINITION: &'static str = r#"string type"#; @@ -6556,7 +6556,7 @@ string[] services"#; pub struct ServiceRequestDetailsResponse { pub r#typedefs: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for ServiceRequestDetailsResponse { + impl ::roslibrust_common::RosMessageType for ServiceRequestDetailsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceRequestDetailsResponse"; const MD5SUM: &'static str = "a6b8995777f214f2ed97a1e4890feb10"; const DEFINITION: &'static str = r#"TypeDef[] typedefs @@ -6572,7 +6572,7 @@ string[] constvalues"#; } #[allow(dead_code)] pub struct ServiceRequestDetails {} - impl ::roslibrust_codegen::RosServiceType for ServiceRequestDetails { + impl ::roslibrust_common::RosServiceType for ServiceRequestDetails { const ROS_SERVICE_NAME: &'static str = "rosapi/ServiceRequestDetails"; const MD5SUM: &'static str = "f9c88144f6f6bd888dd99d4e0411905d"; type Request = ServiceRequestDetailsRequest; @@ -6591,7 +6591,7 @@ string[] constvalues"#; pub struct ServiceResponseDetailsRequest { pub r#type: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServiceResponseDetailsRequest { + impl ::roslibrust_common::RosMessageType for ServiceResponseDetailsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceResponseDetailsRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; const DEFINITION: &'static str = r#"string type"#; @@ -6609,7 +6609,7 @@ string[] constvalues"#; pub struct ServiceResponseDetailsResponse { pub r#typedefs: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for ServiceResponseDetailsResponse { + impl ::roslibrust_common::RosMessageType for ServiceResponseDetailsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceResponseDetailsResponse"; const MD5SUM: &'static str = "a6b8995777f214f2ed97a1e4890feb10"; const DEFINITION: &'static str = r#"TypeDef[] typedefs @@ -6625,7 +6625,7 @@ string[] constvalues"#; } #[allow(dead_code)] pub struct ServiceResponseDetails {} - impl ::roslibrust_codegen::RosServiceType for ServiceResponseDetails { + impl ::roslibrust_common::RosServiceType for ServiceResponseDetails { const ROS_SERVICE_NAME: &'static str = "rosapi/ServiceResponseDetails"; const MD5SUM: &'static str = "f9c88144f6f6bd888dd99d4e0411905d"; type Request = ServiceResponseDetailsRequest; @@ -6644,7 +6644,7 @@ string[] constvalues"#; pub struct ServiceTypeRequest { pub r#service: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServiceTypeRequest { + impl ::roslibrust_common::RosMessageType for ServiceTypeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceTypeRequest"; const MD5SUM: &'static str = "1cbcfa13b08f6d36710b9af8741e6112"; const DEFINITION: &'static str = r#"string service"#; @@ -6662,14 +6662,14 @@ string[] constvalues"#; pub struct ServiceTypeResponse { pub r#type: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServiceTypeResponse { + impl ::roslibrust_common::RosMessageType for ServiceTypeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceTypeResponse"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; const DEFINITION: &'static str = r#"string type"#; } #[allow(dead_code)] pub struct ServiceType {} - impl ::roslibrust_codegen::RosServiceType for ServiceType { + impl ::roslibrust_common::RosServiceType for ServiceType { const ROS_SERVICE_NAME: &'static str = "rosapi/ServiceType"; const MD5SUM: &'static str = "0e24a2dcdf70e483afc092a35a1f15f7"; type Request = ServiceTypeRequest; @@ -6686,7 +6686,7 @@ string[] constvalues"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct ServicesRequest {} - impl ::roslibrust_codegen::RosMessageType for ServicesRequest { + impl ::roslibrust_common::RosMessageType for ServicesRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServicesRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -6704,14 +6704,14 @@ string[] constvalues"#; pub struct ServicesResponse { pub r#services: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for ServicesResponse { + impl ::roslibrust_common::RosMessageType for ServicesResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServicesResponse"; const MD5SUM: &'static str = "e44a7e7bcb900acadbcc28b132378f0c"; const DEFINITION: &'static str = r#"string[] services"#; } #[allow(dead_code)] pub struct Services {} - impl ::roslibrust_codegen::RosServiceType for Services { + impl ::roslibrust_common::RosServiceType for Services { const ROS_SERVICE_NAME: &'static str = "rosapi/Services"; const MD5SUM: &'static str = "e44a7e7bcb900acadbcc28b132378f0c"; type Request = ServicesRequest; @@ -6730,7 +6730,7 @@ string[] constvalues"#; pub struct ServicesForTypeRequest { pub r#type: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for ServicesForTypeRequest { + impl ::roslibrust_common::RosMessageType for ServicesForTypeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServicesForTypeRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; const DEFINITION: &'static str = r#"string type"#; @@ -6748,14 +6748,14 @@ string[] constvalues"#; pub struct ServicesForTypeResponse { pub r#services: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for ServicesForTypeResponse { + impl ::roslibrust_common::RosMessageType for ServicesForTypeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServicesForTypeResponse"; const MD5SUM: &'static str = "e44a7e7bcb900acadbcc28b132378f0c"; const DEFINITION: &'static str = r#"string[] services"#; } #[allow(dead_code)] pub struct ServicesForType {} - impl ::roslibrust_codegen::RosServiceType for ServicesForType { + impl ::roslibrust_common::RosServiceType for ServicesForType { const ROS_SERVICE_NAME: &'static str = "rosapi/ServicesForType"; const MD5SUM: &'static str = "93e9fe8ae5a9136008e260fe510bd2b0"; type Request = ServicesForTypeRequest; @@ -6775,7 +6775,7 @@ string[] constvalues"#; pub r#name: ::std::string::String, pub r#value: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for SetParamRequest { + impl ::roslibrust_common::RosMessageType for SetParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/SetParamRequest"; const MD5SUM: &'static str = "bc6ccc4a57f61779c8eaae61e9f422e0"; const DEFINITION: &'static str = r#"string name @@ -6792,14 +6792,14 @@ string value"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct SetParamResponse {} - impl ::roslibrust_codegen::RosMessageType for SetParamResponse { + impl ::roslibrust_common::RosMessageType for SetParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/SetParamResponse"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; } #[allow(dead_code)] pub struct SetParam {} - impl ::roslibrust_codegen::RosServiceType for SetParam { + impl ::roslibrust_common::RosServiceType for SetParam { const ROS_SERVICE_NAME: &'static str = "rosapi/SetParam"; const MD5SUM: &'static str = "bc6ccc4a57f61779c8eaae61e9f422e0"; type Request = SetParamRequest; @@ -6818,7 +6818,7 @@ string value"#; pub struct SubscribersRequest { pub r#topic: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for SubscribersRequest { + impl ::roslibrust_common::RosMessageType for SubscribersRequest { const ROS_TYPE_NAME: &'static str = "rosapi/SubscribersRequest"; const MD5SUM: &'static str = "d8f94bae31b356b24d0427f80426d0c3"; const DEFINITION: &'static str = r#"string topic"#; @@ -6836,14 +6836,14 @@ string value"#; pub struct SubscribersResponse { pub r#subscribers: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for SubscribersResponse { + impl ::roslibrust_common::RosMessageType for SubscribersResponse { const ROS_TYPE_NAME: &'static str = "rosapi/SubscribersResponse"; const MD5SUM: &'static str = "22418cab5ba9531d8c2b738b4e56153b"; const DEFINITION: &'static str = r#"string[] subscribers"#; } #[allow(dead_code)] pub struct Subscribers {} - impl ::roslibrust_codegen::RosServiceType for Subscribers { + impl ::roslibrust_common::RosServiceType for Subscribers { const ROS_SERVICE_NAME: &'static str = "rosapi/Subscribers"; const MD5SUM: &'static str = "cb387b68f5b29bc1456398ee8476b973"; type Request = SubscribersRequest; @@ -6862,7 +6862,7 @@ string value"#; pub struct TopicTypeRequest { pub r#topic: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for TopicTypeRequest { + impl ::roslibrust_common::RosMessageType for TopicTypeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/TopicTypeRequest"; const MD5SUM: &'static str = "d8f94bae31b356b24d0427f80426d0c3"; const DEFINITION: &'static str = r#"string topic"#; @@ -6880,14 +6880,14 @@ string value"#; pub struct TopicTypeResponse { pub r#type: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for TopicTypeResponse { + impl ::roslibrust_common::RosMessageType for TopicTypeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/TopicTypeResponse"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; const DEFINITION: &'static str = r#"string type"#; } #[allow(dead_code)] pub struct TopicType {} - impl ::roslibrust_codegen::RosServiceType for TopicType { + impl ::roslibrust_common::RosServiceType for TopicType { const ROS_SERVICE_NAME: &'static str = "rosapi/TopicType"; const MD5SUM: &'static str = "0d30b3f53a0fd5036523a7141e524ddf"; type Request = TopicTypeRequest; @@ -6904,7 +6904,7 @@ string value"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct TopicsRequest {} - impl ::roslibrust_codegen::RosMessageType for TopicsRequest { + impl ::roslibrust_common::RosMessageType for TopicsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -6923,7 +6923,7 @@ string value"#; pub r#topics: ::std::vec::Vec<::std::string::String>, pub r#types: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for TopicsResponse { + impl ::roslibrust_common::RosMessageType for TopicsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsResponse"; const MD5SUM: &'static str = "d966d98fc333fa1f3135af765eac1ba8"; const DEFINITION: &'static str = r#"string[] topics @@ -6931,7 +6931,7 @@ string[] types"#; } #[allow(dead_code)] pub struct Topics {} - impl ::roslibrust_codegen::RosServiceType for Topics { + impl ::roslibrust_common::RosServiceType for Topics { const ROS_SERVICE_NAME: &'static str = "rosapi/Topics"; const MD5SUM: &'static str = "d966d98fc333fa1f3135af765eac1ba8"; type Request = TopicsRequest; @@ -6948,7 +6948,7 @@ string[] types"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct TopicsAndRawTypesRequest {} - impl ::roslibrust_codegen::RosMessageType for TopicsAndRawTypesRequest { + impl ::roslibrust_common::RosMessageType for TopicsAndRawTypesRequest { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsAndRawTypesRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -6968,7 +6968,7 @@ string[] types"#; pub r#types: ::std::vec::Vec<::std::string::String>, pub r#typedefs_full_text: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for TopicsAndRawTypesResponse { + impl ::roslibrust_common::RosMessageType for TopicsAndRawTypesResponse { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsAndRawTypesResponse"; const MD5SUM: &'static str = "e1432466c8f64316723276ba07c59d12"; const DEFINITION: &'static str = r#"string[] topics @@ -6977,7 +6977,7 @@ string[] typedefs_full_text"#; } #[allow(dead_code)] pub struct TopicsAndRawTypes {} - impl ::roslibrust_codegen::RosServiceType for TopicsAndRawTypes { + impl ::roslibrust_common::RosServiceType for TopicsAndRawTypes { const ROS_SERVICE_NAME: &'static str = "rosapi/TopicsAndRawTypes"; const MD5SUM: &'static str = "e1432466c8f64316723276ba07c59d12"; type Request = TopicsAndRawTypesRequest; @@ -6996,7 +6996,7 @@ string[] typedefs_full_text"#; pub struct TopicsForTypeRequest { pub r#type: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for TopicsForTypeRequest { + impl ::roslibrust_common::RosMessageType for TopicsForTypeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsForTypeRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; const DEFINITION: &'static str = r#"string type"#; @@ -7014,14 +7014,14 @@ string[] typedefs_full_text"#; pub struct TopicsForTypeResponse { pub r#topics: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for TopicsForTypeResponse { + impl ::roslibrust_common::RosMessageType for TopicsForTypeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsForTypeResponse"; const MD5SUM: &'static str = "b0eef9a05d4e829092fc2f2c3c2aad3d"; const DEFINITION: &'static str = r#"string[] topics"#; } #[allow(dead_code)] pub struct TopicsForType {} - impl ::roslibrust_codegen::RosServiceType for TopicsForType { + impl ::roslibrust_common::RosServiceType for TopicsForType { const ROS_SERVICE_NAME: &'static str = "rosapi/TopicsForType"; const MD5SUM: &'static str = "56f77ff6da756dd27c1ed16ec721072a"; type Request = TopicsForTypeRequest; @@ -7056,7 +7056,7 @@ pub mod rosgraph_msgs { pub struct Clock { pub r#clock: ::roslibrust_codegen::integral_types::Time, } - impl ::roslibrust_codegen::RosMessageType for Clock { + impl ::roslibrust_common::RosMessageType for Clock { const ROS_TYPE_NAME: &'static str = "rosgraph_msgs/Clock"; const MD5SUM: &'static str = "a9c97c1d230cfc112e270351a944ee47"; const DEFINITION: &'static str = r#"# roslib/Clock is used for publishing simulated time in ROS. @@ -7084,7 +7084,7 @@ time clock"#; pub r#line: u32, pub r#topics: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for Log { + impl ::roslibrust_common::RosMessageType for Log { const ROS_TYPE_NAME: &'static str = "rosgraph_msgs/Log"; const MD5SUM: &'static str = "acffd30cd6b6de30f120938c17c593fb"; const DEFINITION: &'static str = r#"## @@ -7156,7 +7156,7 @@ string frame_id"#; pub r#stamp_age_stddev: ::roslibrust_codegen::integral_types::Duration, pub r#stamp_age_max: ::roslibrust_codegen::integral_types::Duration, } - impl ::roslibrust_codegen::RosMessageType for TopicStatistics { + impl ::roslibrust_common::RosMessageType for TopicStatistics { const ROS_TYPE_NAME: &'static str = "rosgraph_msgs/TopicStatistics"; const MD5SUM: &'static str = "10152ed868c5097a5e2e4a89d7daa710"; const DEFINITION: &'static str = r#"# name of the topic @@ -7236,7 +7236,7 @@ pub mod sensor_msgs { pub r#location: ::std::string::String, pub r#serial_number: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for BatteryState { + impl ::roslibrust_common::RosMessageType for BatteryState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/BatteryState"; const MD5SUM: &'static str = "4ddae7f048e32fda22cac764685e3974"; const DEFINITION: &'static str = r#"# Constants are chosen to match the enums in the linux kernel @@ -7353,7 +7353,7 @@ string frame_id"#; pub r#binning_y: u32, pub r#roi: self::RegionOfInterest, } - impl ::roslibrust_codegen::RosMessageType for CameraInfo { + impl ::roslibrust_common::RosMessageType for CameraInfo { const ROS_TYPE_NAME: &'static str = "sensor_msgs/CameraInfo"; const MD5SUM: &'static str = "c9a58c1b0b154e0e6da7578cb991d214"; const DEFINITION: &'static str = r#"# This message defines meta information for a camera. It should be in a @@ -7538,7 +7538,7 @@ string frame_id"#; pub r#name: ::std::string::String, pub r#values: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for ChannelFloat32 { + impl ::roslibrust_common::RosMessageType for ChannelFloat32 { const ROS_TYPE_NAME: &'static str = "sensor_msgs/ChannelFloat32"; const MD5SUM: &'static str = "3d40139cdd33dfedcb71ffeeeb42ae7f"; const DEFINITION: &'static str = r#"# This message is used by the PointCloud message to hold optional data @@ -7582,7 +7582,7 @@ float32[] values"#; #[serde(with = "::roslibrust_codegen::serde_bytes")] pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for CompressedImage { + impl ::roslibrust_common::RosMessageType for CompressedImage { const ROS_TYPE_NAME: &'static str = "sensor_msgs/CompressedImage"; const MD5SUM: &'static str = "8f7a12909da2c9d3332d540a0977563f"; const DEFINITION: &'static str = r#"# This message contains a compressed image @@ -7629,7 +7629,7 @@ string frame_id"#; pub r#fluid_pressure: f64, pub r#variance: f64, } - impl ::roslibrust_codegen::RosMessageType for FluidPressure { + impl ::roslibrust_common::RosMessageType for FluidPressure { const ROS_TYPE_NAME: &'static str = "sensor_msgs/FluidPressure"; const MD5SUM: &'static str = "804dc5cea1c5306d6a2eb80b9833befe"; const DEFINITION: &'static str = r#"# Single pressure reading. This message is appropriate for measuring the @@ -7675,7 +7675,7 @@ string frame_id"#; pub r#illuminance: f64, pub r#variance: f64, } - impl ::roslibrust_codegen::RosMessageType for Illuminance { + impl ::roslibrust_common::RosMessageType for Illuminance { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Illuminance"; const MD5SUM: &'static str = "8cf5febb0952fca9d650c3d11a81a188"; const DEFINITION: &'static str = r#"# Single photometric illuminance measurement. Light should be assumed to be @@ -7735,7 +7735,7 @@ string frame_id"#; #[serde(with = "::roslibrust_codegen::serde_bytes")] pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Image { + impl ::roslibrust_common::RosMessageType for Image { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Image"; const MD5SUM: &'static str = "060021388200f6f0f447d0fcd9c64743"; const DEFINITION: &'static str = r#"# This message contains an uncompressed image @@ -7800,7 +7800,7 @@ string frame_id"#; pub r#linear_acceleration: geometry_msgs::Vector3, pub r#linear_acceleration_covariance: [f64; 9], } - impl ::roslibrust_codegen::RosMessageType for Imu { + impl ::roslibrust_common::RosMessageType for Imu { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Imu"; const MD5SUM: &'static str = "6a62c6daae103f4ff57a132d6f95cec2"; const DEFINITION: &'static str = r#"# This is a message to hold data from an IMU (Inertial Measurement Unit) @@ -7880,7 +7880,7 @@ string frame_id"#; pub r#velocity: ::std::vec::Vec, pub r#effort: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for JointState { + impl ::roslibrust_common::RosMessageType for JointState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JointState"; const MD5SUM: &'static str = "3066dcd76a6cfaef579bd0f34173e9fd"; const DEFINITION: &'static str = r#"# This is a message that holds data to describe the state of a set of torque controlled joints. @@ -7940,7 +7940,7 @@ string frame_id"#; pub r#axes: ::std::vec::Vec, pub r#buttons: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Joy { + impl ::roslibrust_common::RosMessageType for Joy { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Joy"; const MD5SUM: &'static str = "5a9ea5f83505693b71e785041e67a8bb"; const DEFINITION: &'static str = r#"# Reports the state of a joysticks axes and buttons. @@ -7978,7 +7978,7 @@ string frame_id"#; pub r#id: u8, pub r#intensity: f32, } - impl ::roslibrust_codegen::RosMessageType for JoyFeedback { + impl ::roslibrust_common::RosMessageType for JoyFeedback { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JoyFeedback"; const MD5SUM: &'static str = "f4dcd73460360d98f36e55ee7f2e46f1"; const DEFINITION: &'static str = r#"# Declare of the type of feedback @@ -8015,7 +8015,7 @@ float32 intensity"#; pub struct JoyFeedbackArray { pub r#array: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for JoyFeedbackArray { + impl ::roslibrust_common::RosMessageType for JoyFeedbackArray { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JoyFeedbackArray"; const MD5SUM: &'static str = "cde5730a895b1fc4dee6f91b754b213d"; const DEFINITION: &'static str = r#"# This message publishes values for multiple feedback at once. @@ -8050,7 +8050,7 @@ float32 intensity"#; pub struct LaserEcho { pub r#echoes: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for LaserEcho { + impl ::roslibrust_common::RosMessageType for LaserEcho { const ROS_TYPE_NAME: &'static str = "sensor_msgs/LaserEcho"; const MD5SUM: &'static str = "8bc5ae449b200fba4d552b4225586696"; const DEFINITION: &'static str = r#"# This message is a submessage of MultiEchoLaserScan and is not intended @@ -8081,7 +8081,7 @@ float32[] echoes # Multiple values of ranges or intensities. pub r#ranges: ::std::vec::Vec, pub r#intensities: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for LaserScan { + impl ::roslibrust_common::RosMessageType for LaserScan { const ROS_TYPE_NAME: &'static str = "sensor_msgs/LaserScan"; const MD5SUM: &'static str = "90c7ef2dc6895d81024acba2ac42f369"; const DEFINITION: &'static str = r#"# Single scan from a planar laser range-finder @@ -8144,7 +8144,7 @@ string frame_id"#; pub r#magnetic_field: geometry_msgs::Vector3, pub r#magnetic_field_covariance: [f64; 9], } - impl ::roslibrust_codegen::RosMessageType for MagneticField { + impl ::roslibrust_common::RosMessageType for MagneticField { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MagneticField"; const MD5SUM: &'static str = "2f3b0b43eed0c9501de0fa3ff89a45aa"; const DEFINITION: &'static str = r#"# Measurement of the Magnetic Field vector at a specific location. @@ -8214,7 +8214,7 @@ string frame_id"#; pub r#twist: ::std::vec::Vec, pub r#wrench: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MultiDOFJointState { + impl ::roslibrust_common::RosMessageType for MultiDOFJointState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MultiDOFJointState"; const MD5SUM: &'static str = "690f272f0640d2631c305eeb8301e59d"; const DEFINITION: &'static str = r#"# Representation of state for joints with multiple degrees of freedom, @@ -8362,7 +8362,7 @@ string frame_id"#; pub r#ranges: ::std::vec::Vec, pub r#intensities: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MultiEchoLaserScan { + impl ::roslibrust_common::RosMessageType for MultiEchoLaserScan { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MultiEchoLaserScan"; const MD5SUM: &'static str = "6fefb0c6da89d7c8abe4b339f5c2f8fb"; const DEFINITION: &'static str = r#"# Single scan from a multi-echo planar laser range-finder @@ -8438,7 +8438,7 @@ string frame_id"#; pub r#position_covariance: [f64; 9], pub r#position_covariance_type: u8, } - impl ::roslibrust_codegen::RosMessageType for NavSatFix { + impl ::roslibrust_common::RosMessageType for NavSatFix { const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatFix"; const MD5SUM: &'static str = "2d3a8cd499b9b4a0249fb98fd05cfa48"; const DEFINITION: &'static str = r#"# Navigation Satellite fix for any Global Navigation Satellite System @@ -8548,7 +8548,7 @@ string frame_id"#; pub r#status: i8, pub r#service: u16, } - impl ::roslibrust_codegen::RosMessageType for NavSatStatus { + impl ::roslibrust_common::RosMessageType for NavSatStatus { const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatStatus"; const MD5SUM: &'static str = "331cdbddfa4bc96ffc3b9ad98900a54c"; const DEFINITION: &'static str = r#"# Navigation Satellite fix status for any Global Navigation Satellite System @@ -8600,7 +8600,7 @@ uint16 service"#; pub r#points: ::std::vec::Vec, pub r#channels: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for PointCloud { + impl ::roslibrust_common::RosMessageType for PointCloud { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointCloud"; const MD5SUM: &'static str = "d8e9c3f5afbdd8a130fd1d2763945fca"; const DEFINITION: &'static str = r#"# This message holds a collection of 3d points, plus optional additional @@ -8694,7 +8694,7 @@ string frame_id"#; pub r#data: ::std::vec::Vec, pub r#is_dense: bool, } - impl ::roslibrust_codegen::RosMessageType for PointCloud2 { + impl ::roslibrust_common::RosMessageType for PointCloud2 { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointCloud2"; const MD5SUM: &'static str = "1158d486dd51d683ce2f1be655c3c181"; const DEFINITION: &'static str = r#"# This message holds a collection of N-dimensional points, which may @@ -8773,7 +8773,7 @@ string frame_id"#; pub r#datatype: u8, pub r#count: u32, } - impl ::roslibrust_codegen::RosMessageType for PointField { + impl ::roslibrust_common::RosMessageType for PointField { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointField"; const MD5SUM: &'static str = "268eacb2962780ceac86cbd17e328150"; const DEFINITION: &'static str = r#"# This message holds the description of one point entry in the @@ -8821,7 +8821,7 @@ uint32 count # How many elements in the field"#; pub r#max_range: f32, pub r#range: f32, } - impl ::roslibrust_codegen::RosMessageType for Range { + impl ::roslibrust_common::RosMessageType for Range { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Range"; const MD5SUM: &'static str = "c005c34273dc426c67a020a87bc24148"; const DEFINITION: &'static str = r#"# Single range reading from an active ranger that emits energy and reports @@ -8902,7 +8902,7 @@ string frame_id"#; pub r#width: u32, pub r#do_rectify: bool, } - impl ::roslibrust_codegen::RosMessageType for RegionOfInterest { + impl ::roslibrust_common::RosMessageType for RegionOfInterest { const ROS_TYPE_NAME: &'static str = "sensor_msgs/RegionOfInterest"; const MD5SUM: &'static str = "bdb633039d588fcccb441a4d43ccfe09"; const DEFINITION: &'static str = r#"# This message is used to specify a region of interest within an image. @@ -8940,7 +8940,7 @@ bool do_rectify"#; pub r#relative_humidity: f64, pub r#variance: f64, } - impl ::roslibrust_codegen::RosMessageType for RelativeHumidity { + impl ::roslibrust_common::RosMessageType for RelativeHumidity { const ROS_TYPE_NAME: &'static str = "sensor_msgs/RelativeHumidity"; const MD5SUM: &'static str = "8730015b05955b7e992ce29a2678d90f"; const DEFINITION: &'static str = r#"# Single reading from a relative humidity sensor. Defines the ratio of partial @@ -8986,7 +8986,7 @@ string frame_id"#; pub r#temperature: f64, pub r#variance: f64, } - impl ::roslibrust_codegen::RosMessageType for Temperature { + impl ::roslibrust_common::RosMessageType for Temperature { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Temperature"; const MD5SUM: &'static str = "ff71b307acdbe7c871a5a6d7ed359100"; const DEFINITION: &'static str = r#"# Single temperature reading. @@ -9028,7 +9028,7 @@ string frame_id"#; pub r#time_ref: ::roslibrust_codegen::integral_types::Time, pub r#source: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for TimeReference { + impl ::roslibrust_common::RosMessageType for TimeReference { const ROS_TYPE_NAME: &'static str = "sensor_msgs/TimeReference"; const MD5SUM: &'static str = "fded64a0265108ba86c3d38fb11c0c16"; const DEFINITION: &'static str = r#"# Measurement from an external time source not actively synchronized with the system clock. @@ -9067,7 +9067,7 @@ string frame_id"#; pub struct SetCameraInfoRequest { pub r#camera_info: self::CameraInfo, } - impl ::roslibrust_codegen::RosMessageType for SetCameraInfoRequest { + impl ::roslibrust_common::RosMessageType for SetCameraInfoRequest { const ROS_TYPE_NAME: &'static str = "sensor_msgs/SetCameraInfoRequest"; const MD5SUM: &'static str = "ee34be01fdeee563d0d99cd594d5581d"; const DEFINITION: &'static str = r#"# This service requests that a camera stores the given CameraInfo @@ -9299,7 +9299,7 @@ string frame_id"#; pub r#success: bool, pub r#status_message: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for SetCameraInfoResponse { + impl ::roslibrust_common::RosMessageType for SetCameraInfoResponse { const ROS_TYPE_NAME: &'static str = "sensor_msgs/SetCameraInfoResponse"; const MD5SUM: &'static str = "2ec6f3eff0161f4257b808b12bc830c2"; const DEFINITION: &'static str = r#"bool success # True if the call succeeded @@ -9307,7 +9307,7 @@ string status_message # Used to give details about success"#; } #[allow(dead_code)] pub struct SetCameraInfo {} - impl ::roslibrust_codegen::RosServiceType for SetCameraInfo { + impl ::roslibrust_common::RosServiceType for SetCameraInfo { const ROS_SERVICE_NAME: &'static str = "sensor_msgs/SetCameraInfo"; const MD5SUM: &'static str = "bef1df590ed75ed1f393692395e15482"; type Request = SetCameraInfoRequest; @@ -9343,7 +9343,7 @@ pub mod shape_msgs { pub r#triangles: ::std::vec::Vec, pub r#vertices: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Mesh { + impl ::roslibrust_common::RosMessageType for Mesh { const ROS_TYPE_NAME: &'static str = "shape_msgs/Mesh"; const MD5SUM: &'static str = "1ffdae9486cd3316a121c578b47a85cc"; const DEFINITION: &'static str = r#"# Definition of a mesh @@ -9377,7 +9377,7 @@ uint32[3] vertex_indices"#; pub struct MeshTriangle { pub r#vertex_indices: [u32; 3], } - impl ::roslibrust_codegen::RosMessageType for MeshTriangle { + impl ::roslibrust_common::RosMessageType for MeshTriangle { const ROS_TYPE_NAME: &'static str = "shape_msgs/MeshTriangle"; const MD5SUM: &'static str = "23688b2e6d2de3d32fe8af104a903253"; const DEFINITION: &'static str = r#"# Definition of a triangle's vertices @@ -9396,7 +9396,7 @@ uint32[3] vertex_indices"#; pub struct Plane { pub r#coef: [f64; 4], } - impl ::roslibrust_codegen::RosMessageType for Plane { + impl ::roslibrust_common::RosMessageType for Plane { const ROS_TYPE_NAME: &'static str = "shape_msgs/Plane"; const MD5SUM: &'static str = "2c1b92ed8f31492f8e73f6a4a44ca796"; const DEFINITION: &'static str = r#"# Representation of a plane, using the plane equation ax + by + cz + d = 0 @@ -9422,7 +9422,7 @@ float64[4] coef"#; pub r#type: u8, pub r#dimensions: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for SolidPrimitive { + impl ::roslibrust_common::RosMessageType for SolidPrimitive { const ROS_TYPE_NAME: &'static str = "shape_msgs/SolidPrimitive"; const MD5SUM: &'static str = "d8f8cbc74c5ff283fca29569ccefb45d"; const DEFINITION: &'static str = r#"# Define box, sphere, cylinder, cone @@ -9512,7 +9512,7 @@ pub mod std_msgs { pub struct Bool { pub r#data: bool, } - impl ::roslibrust_codegen::RosMessageType for Bool { + impl ::roslibrust_common::RosMessageType for Bool { const ROS_TYPE_NAME: &'static str = "std_msgs/Bool"; const MD5SUM: &'static str = "8b94c1b53db61fb6aed406028ad6332a"; const DEFINITION: &'static str = r#"bool data"#; @@ -9530,7 +9530,7 @@ pub mod std_msgs { pub struct Byte { pub r#data: u8, } - impl ::roslibrust_codegen::RosMessageType for Byte { + impl ::roslibrust_common::RosMessageType for Byte { const ROS_TYPE_NAME: &'static str = "std_msgs/Byte"; const MD5SUM: &'static str = "ad736a2e8818154c487bb80fe42ce43b"; const DEFINITION: &'static str = r#"byte data"#; @@ -9549,7 +9549,7 @@ pub mod std_msgs { pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for ByteMultiArray { + impl ::roslibrust_common::RosMessageType for ByteMultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/ByteMultiArray"; const MD5SUM: &'static str = "70ea476cbcfd65ac2f68f3cda1e891fe"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -9609,7 +9609,7 @@ uint32 stride # stride of given dimension"#; pub struct Char { pub r#data: u8, } - impl ::roslibrust_codegen::RosMessageType for Char { + impl ::roslibrust_common::RosMessageType for Char { const ROS_TYPE_NAME: &'static str = "std_msgs/Char"; const MD5SUM: &'static str = "1bf77f25acecdedba0e224b162199717"; const DEFINITION: &'static str = r#"char data"#; @@ -9630,7 +9630,7 @@ uint32 stride # stride of given dimension"#; pub r#b: f32, pub r#a: f32, } - impl ::roslibrust_codegen::RosMessageType for ColorRGBA { + impl ::roslibrust_common::RosMessageType for ColorRGBA { const ROS_TYPE_NAME: &'static str = "std_msgs/ColorRGBA"; const MD5SUM: &'static str = "a29a96539573343b1310c73607334b00"; const DEFINITION: &'static str = r#"float32 r @@ -9651,7 +9651,7 @@ float32 a"#; pub struct Duration { pub r#data: ::roslibrust_codegen::integral_types::Duration, } - impl ::roslibrust_codegen::RosMessageType for Duration { + impl ::roslibrust_common::RosMessageType for Duration { const ROS_TYPE_NAME: &'static str = "std_msgs/Duration"; const MD5SUM: &'static str = "3e286caf4241d664e55f3ad380e2ae46"; const DEFINITION: &'static str = r#"duration data"#; @@ -9667,7 +9667,7 @@ float32 a"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct Empty {} - impl ::roslibrust_codegen::RosMessageType for Empty { + impl ::roslibrust_common::RosMessageType for Empty { const ROS_TYPE_NAME: &'static str = "std_msgs/Empty"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -9685,7 +9685,7 @@ float32 a"#; pub struct Float32 { pub r#data: f32, } - impl ::roslibrust_codegen::RosMessageType for Float32 { + impl ::roslibrust_common::RosMessageType for Float32 { const ROS_TYPE_NAME: &'static str = "std_msgs/Float32"; const MD5SUM: &'static str = "73fcbf46b49191e672908e50842a83d4"; const DEFINITION: &'static str = r#"float32 data"#; @@ -9704,7 +9704,7 @@ float32 a"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Float32MultiArray { + impl ::roslibrust_common::RosMessageType for Float32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Float32MultiArray"; const MD5SUM: &'static str = "6a40e0ffa6a17a503ac3f8616991b1f6"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -9764,7 +9764,7 @@ uint32 stride # stride of given dimension"#; pub struct Float64 { pub r#data: f64, } - impl ::roslibrust_codegen::RosMessageType for Float64 { + impl ::roslibrust_common::RosMessageType for Float64 { const ROS_TYPE_NAME: &'static str = "std_msgs/Float64"; const MD5SUM: &'static str = "fdb28210bfa9d7c91146260178d9a584"; const DEFINITION: &'static str = r#"float64 data"#; @@ -9783,7 +9783,7 @@ uint32 stride # stride of given dimension"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Float64MultiArray { + impl ::roslibrust_common::RosMessageType for Float64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Float64MultiArray"; const MD5SUM: &'static str = "4b7d974086d4060e7db4613a7e6c3ba4"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -9845,7 +9845,7 @@ uint32 stride # stride of given dimension"#; pub r#stamp: ::roslibrust_codegen::integral_types::Time, pub r#frame_id: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for Header { + impl ::roslibrust_common::RosMessageType for Header { const ROS_TYPE_NAME: &'static str = "std_msgs/Header"; const MD5SUM: &'static str = "2176decaecbce78abc3b96ef049fabed"; const DEFINITION: &'static str = r#"# Standard metadata for higher-level stamped data types. @@ -9875,7 +9875,7 @@ string frame_id"#; pub struct Int16 { pub r#data: i16, } - impl ::roslibrust_codegen::RosMessageType for Int16 { + impl ::roslibrust_common::RosMessageType for Int16 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int16"; const MD5SUM: &'static str = "8524586e34fbd7cb1c08c5f5f1ca0e57"; const DEFINITION: &'static str = r#"int16 data"#; @@ -9894,7 +9894,7 @@ string frame_id"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Int16MultiArray { + impl ::roslibrust_common::RosMessageType for Int16MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int16MultiArray"; const MD5SUM: &'static str = "d9338d7f523fcb692fae9d0a0e9f067c"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -9954,7 +9954,7 @@ uint32 stride # stride of given dimension"#; pub struct Int32 { pub r#data: i32, } - impl ::roslibrust_codegen::RosMessageType for Int32 { + impl ::roslibrust_common::RosMessageType for Int32 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int32"; const MD5SUM: &'static str = "da5909fbe378aeaf85e547e830cc1bb7"; const DEFINITION: &'static str = r#"int32 data"#; @@ -9973,7 +9973,7 @@ uint32 stride # stride of given dimension"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Int32MultiArray { + impl ::roslibrust_common::RosMessageType for Int32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int32MultiArray"; const MD5SUM: &'static str = "1d99f79f8b325b44fee908053e9c945b"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -10033,7 +10033,7 @@ uint32 stride # stride of given dimension"#; pub struct Int64 { pub r#data: i64, } - impl ::roslibrust_codegen::RosMessageType for Int64 { + impl ::roslibrust_common::RosMessageType for Int64 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int64"; const MD5SUM: &'static str = "34add168574510e6e17f5d23ecc077ef"; const DEFINITION: &'static str = r#"int64 data"#; @@ -10052,7 +10052,7 @@ uint32 stride # stride of given dimension"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Int64MultiArray { + impl ::roslibrust_common::RosMessageType for Int64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int64MultiArray"; const MD5SUM: &'static str = "54865aa6c65be0448113a2afc6a49270"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -10112,7 +10112,7 @@ uint32 stride # stride of given dimension"#; pub struct Int8 { pub r#data: i8, } - impl ::roslibrust_codegen::RosMessageType for Int8 { + impl ::roslibrust_common::RosMessageType for Int8 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int8"; const MD5SUM: &'static str = "27ffa0c9c4b8fb8492252bcad9e5c57b"; const DEFINITION: &'static str = r#"int8 data"#; @@ -10131,7 +10131,7 @@ uint32 stride # stride of given dimension"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Int8MultiArray { + impl ::roslibrust_common::RosMessageType for Int8MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int8MultiArray"; const MD5SUM: &'static str = "d7c1af35a1b4781bbe79e03dd94b7c13"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -10193,7 +10193,7 @@ uint32 stride # stride of given dimension"#; pub r#size: u32, pub r#stride: u32, } - impl ::roslibrust_codegen::RosMessageType for MultiArrayDimension { + impl ::roslibrust_common::RosMessageType for MultiArrayDimension { const ROS_TYPE_NAME: &'static str = "std_msgs/MultiArrayDimension"; const MD5SUM: &'static str = "4cd0c83a8683deae40ecdac60e53bfa8"; const DEFINITION: &'static str = r#"string label # label of given dimension @@ -10214,7 +10214,7 @@ uint32 stride # stride of given dimension"#; pub r#dim: ::std::vec::Vec, pub r#data_offset: u32, } - impl ::roslibrust_codegen::RosMessageType for MultiArrayLayout { + impl ::roslibrust_common::RosMessageType for MultiArrayLayout { const ROS_TYPE_NAME: &'static str = "std_msgs/MultiArrayLayout"; const MD5SUM: &'static str = "0fed2a11c13e11c5571b4e2a995a91a3"; const DEFINITION: &'static str = r#"# The multiarray declares a generic multi-dimensional array of a @@ -10262,7 +10262,7 @@ uint32 stride # stride of given dimension"#; pub struct String { pub r#data: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for String { + impl ::roslibrust_common::RosMessageType for String { const ROS_TYPE_NAME: &'static str = "std_msgs/String"; const MD5SUM: &'static str = "992ce8a1687cec8c8bd883ec73ca41d1"; const DEFINITION: &'static str = r#"string data"#; @@ -10280,7 +10280,7 @@ uint32 stride # stride of given dimension"#; pub struct Time { pub r#data: ::roslibrust_codegen::integral_types::Time, } - impl ::roslibrust_codegen::RosMessageType for Time { + impl ::roslibrust_common::RosMessageType for Time { const ROS_TYPE_NAME: &'static str = "std_msgs/Time"; const MD5SUM: &'static str = "cd7166c74c552c311fbcc2fe5a7bc289"; const DEFINITION: &'static str = r#"time data"#; @@ -10298,7 +10298,7 @@ uint32 stride # stride of given dimension"#; pub struct UInt16 { pub r#data: u16, } - impl ::roslibrust_codegen::RosMessageType for UInt16 { + impl ::roslibrust_common::RosMessageType for UInt16 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt16"; const MD5SUM: &'static str = "1df79edf208b629fe6b81923a544552d"; const DEFINITION: &'static str = r#"uint16 data"#; @@ -10317,7 +10317,7 @@ uint32 stride # stride of given dimension"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for UInt16MultiArray { + impl ::roslibrust_common::RosMessageType for UInt16MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt16MultiArray"; const MD5SUM: &'static str = "52f264f1c973c4b73790d384c6cb4484"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -10377,7 +10377,7 @@ uint32 stride # stride of given dimension"#; pub struct UInt32 { pub r#data: u32, } - impl ::roslibrust_codegen::RosMessageType for UInt32 { + impl ::roslibrust_common::RosMessageType for UInt32 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt32"; const MD5SUM: &'static str = "304a39449588c7f8ce2df6e8001c5fce"; const DEFINITION: &'static str = r#"uint32 data"#; @@ -10396,7 +10396,7 @@ uint32 stride # stride of given dimension"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for UInt32MultiArray { + impl ::roslibrust_common::RosMessageType for UInt32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt32MultiArray"; const MD5SUM: &'static str = "4d6a180abc9be191b96a7eda6c8a233d"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -10456,7 +10456,7 @@ uint32 stride # stride of given dimension"#; pub struct UInt64 { pub r#data: u64, } - impl ::roslibrust_codegen::RosMessageType for UInt64 { + impl ::roslibrust_common::RosMessageType for UInt64 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt64"; const MD5SUM: &'static str = "1b2a79973e8bf53d7b53acb71299cb57"; const DEFINITION: &'static str = r#"uint64 data"#; @@ -10475,7 +10475,7 @@ uint32 stride # stride of given dimension"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for UInt64MultiArray { + impl ::roslibrust_common::RosMessageType for UInt64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt64MultiArray"; const MD5SUM: &'static str = "6088f127afb1d6c72927aa1247e945af"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -10535,7 +10535,7 @@ uint32 stride # stride of given dimension"#; pub struct UInt8 { pub r#data: u8, } - impl ::roslibrust_codegen::RosMessageType for UInt8 { + impl ::roslibrust_common::RosMessageType for UInt8 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt8"; const MD5SUM: &'static str = "7c8164229e7d2c17eb95e9231617fdee"; const DEFINITION: &'static str = r#"uint8 data"#; @@ -10555,7 +10555,7 @@ uint32 stride # stride of given dimension"#; #[serde(with = "::roslibrust_codegen::serde_bytes")] pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for UInt8MultiArray { + impl ::roslibrust_common::RosMessageType for UInt8MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt8MultiArray"; const MD5SUM: &'static str = "82373f1612381bb6ee473b5cd6f5d89c"; const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for @@ -10629,7 +10629,7 @@ pub mod std_srvs { )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct EmptyRequest {} - impl ::roslibrust_codegen::RosMessageType for EmptyRequest { + impl ::roslibrust_common::RosMessageType for EmptyRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/EmptyRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -10645,14 +10645,14 @@ pub mod std_srvs { )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct EmptyResponse {} - impl ::roslibrust_codegen::RosMessageType for EmptyResponse { + impl ::roslibrust_common::RosMessageType for EmptyResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/EmptyResponse"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; } #[allow(dead_code)] pub struct Empty {} - impl ::roslibrust_codegen::RosServiceType for Empty { + impl ::roslibrust_common::RosServiceType for Empty { const ROS_SERVICE_NAME: &'static str = "std_srvs/Empty"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; type Request = EmptyRequest; @@ -10671,7 +10671,7 @@ pub mod std_srvs { pub struct SetBoolRequest { pub r#data: bool, } - impl ::roslibrust_codegen::RosMessageType for SetBoolRequest { + impl ::roslibrust_common::RosMessageType for SetBoolRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/SetBoolRequest"; const MD5SUM: &'static str = "8b94c1b53db61fb6aed406028ad6332a"; const DEFINITION: &'static str = r#"bool data # e.g. for hardware enabling / disabling"#; @@ -10690,7 +10690,7 @@ pub mod std_srvs { pub r#success: bool, pub r#message: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for SetBoolResponse { + impl ::roslibrust_common::RosMessageType for SetBoolResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/SetBoolResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; const DEFINITION: &'static str = r#"bool success # indicate successful run of triggered service @@ -10698,7 +10698,7 @@ string message # informational, e.g. for error messages"#; } #[allow(dead_code)] pub struct SetBool {} - impl ::roslibrust_codegen::RosServiceType for SetBool { + impl ::roslibrust_common::RosServiceType for SetBool { const ROS_SERVICE_NAME: &'static str = "std_srvs/SetBool"; const MD5SUM: &'static str = "09fb03525b03e7ea1fd3992bafd87e16"; type Request = SetBoolRequest; @@ -10715,7 +10715,7 @@ string message # informational, e.g. for error messages"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct TriggerRequest {} - impl ::roslibrust_codegen::RosMessageType for TriggerRequest { + impl ::roslibrust_common::RosMessageType for TriggerRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/TriggerRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -10734,7 +10734,7 @@ string message # informational, e.g. for error messages"#; pub r#success: bool, pub r#message: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for TriggerResponse { + impl ::roslibrust_common::RosMessageType for TriggerResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/TriggerResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; const DEFINITION: &'static str = r#"bool success # indicate successful run of triggered service @@ -10742,7 +10742,7 @@ string message # informational, e.g. for error messages"#; } #[allow(dead_code)] pub struct Trigger {} - impl ::roslibrust_codegen::RosServiceType for Trigger { + impl ::roslibrust_common::RosServiceType for Trigger { const ROS_SERVICE_NAME: &'static str = "std_srvs/Trigger"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; type Request = TriggerRequest; @@ -10784,7 +10784,7 @@ pub mod stereo_msgs { pub r#max_disparity: f32, pub r#delta_d: f32, } - impl ::roslibrust_codegen::RosMessageType for DisparityImage { + impl ::roslibrust_common::RosMessageType for DisparityImage { const ROS_TYPE_NAME: &'static str = "stereo_msgs/DisparityImage"; const MD5SUM: &'static str = "04a177815f75271039fa21f16acad8c9"; const DEFINITION: &'static str = r#"# Separate header for compatibility with current TimeSynchronizer. @@ -10924,7 +10924,7 @@ pub mod test_msgs { )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct Constants {} - impl ::roslibrust_codegen::RosMessageType for Constants { + impl ::roslibrust_common::RosMessageType for Constants { const ROS_TYPE_NAME: &'static str = "test_msgs/Constants"; const MD5SUM: &'static str = "027df5f26b72c57b1e40902038ca3eec"; const DEFINITION: &'static str = r#"string TEST_STR="/topic" @@ -10956,7 +10956,7 @@ float32 TEST_FLOAT=0 # testing"#; pub r#header: std_msgs::Header, pub r#value: f64, } - impl ::roslibrust_codegen::RosMessageType for Float64Stamped { + impl ::roslibrust_common::RosMessageType for Float64Stamped { const ROS_TYPE_NAME: &'static str = "test_msgs/Float64Stamped"; const MD5SUM: &'static str = "d053817de0764f9ee90dbc89c4cdd751"; const DEFINITION: &'static str = r#"Header header @@ -10990,7 +10990,7 @@ string frame_id"#; pub struct LoggerLevel { pub r#level: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for LoggerLevel { + impl ::roslibrust_common::RosMessageType for LoggerLevel { const ROS_TYPE_NAME: &'static str = "test_msgs/LoggerLevel"; const MD5SUM: &'static str = "097b0e938d0dd7788057f4cdc9013238"; const DEFINITION: &'static str = r#"string level"#; @@ -11010,7 +11010,7 @@ string frame_id"#; pub r#time: f64, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Metric { + impl ::roslibrust_common::RosMessageType for Metric { const ROS_TYPE_NAME: &'static str = "test_msgs/Metric"; const MD5SUM: &'static str = "474be567370f515a7d5d3f3243aad369"; const DEFINITION: &'static str = r#"#Metric data type @@ -11040,7 +11040,7 @@ float64 value"#; pub r#key: ::std::string::String, pub r#value: f64, } - impl ::roslibrust_codegen::RosMessageType for MetricPair { + impl ::roslibrust_common::RosMessageType for MetricPair { const ROS_TYPE_NAME: &'static str = "test_msgs/MetricPair"; const MD5SUM: &'static str = "a681f679e1c39fbe570b7737e7cf183d"; const DEFINITION: &'static str = r#"#Data type for storing the key/value pairs from the Metric.data map @@ -11063,7 +11063,7 @@ float64 value"#; pub r#pid: i64, pub r#status: u8, } - impl ::roslibrust_codegen::RosMessageType for NodeInfo { + impl ::roslibrust_common::RosMessageType for NodeInfo { const ROS_TYPE_NAME: &'static str = "test_msgs/NodeInfo"; const MD5SUM: &'static str = "7fab1acc377fd48898b00b7f3a897f47"; const DEFINITION: &'static str = r#"string node_name @@ -11106,7 +11106,7 @@ uint8 status"#; pub r#a: i64, pub r#b: i64, } - impl ::roslibrust_codegen::RosMessageType for AddTwoIntsRequest { + impl ::roslibrust_common::RosMessageType for AddTwoIntsRequest { const ROS_TYPE_NAME: &'static str = "test_msgs/AddTwoIntsRequest"; const MD5SUM: &'static str = "36d09b846be0b371c5f190354dd3153e"; const DEFINITION: &'static str = r#"# AddTwoInts.srv @@ -11128,7 +11128,7 @@ int64 b"#; pub struct AddTwoIntsResponse { pub r#sum: i64, } - impl ::roslibrust_codegen::RosMessageType for AddTwoIntsResponse { + impl ::roslibrust_common::RosMessageType for AddTwoIntsResponse { const ROS_TYPE_NAME: &'static str = "test_msgs/AddTwoIntsResponse"; const MD5SUM: &'static str = "b88405221c77b1878a3cbbfff53428d7"; const DEFINITION: &'static str = r#"# Overflow? What overflow? @@ -11136,7 +11136,7 @@ int64 sum"#; } #[allow(dead_code)] pub struct AddTwoInts {} - impl ::roslibrust_codegen::RosServiceType for AddTwoInts { + impl ::roslibrust_common::RosServiceType for AddTwoInts { const ROS_SERVICE_NAME: &'static str = "test_msgs/AddTwoInts"; const MD5SUM: &'static str = "6a2e34150c00229791cc89ff309fff21"; type Request = AddTwoIntsRequest; @@ -11156,7 +11156,7 @@ int64 sum"#; #[serde(with = "::roslibrust_codegen::serde_bytes")] pub r#bytes: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for RoundTripArrayRequest { + impl ::roslibrust_common::RosMessageType for RoundTripArrayRequest { const ROS_TYPE_NAME: &'static str = "test_msgs/RoundTripArrayRequest"; const MD5SUM: &'static str = "d159f2bd8169d3b3339e6f1fce045c6d"; const DEFINITION: &'static str = r#"# Purpose of this array is send and receive a large payload @@ -11176,14 +11176,14 @@ uint8[] bytes"#; #[serde(with = "::roslibrust_codegen::serde_bytes")] pub r#bytes: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for RoundTripArrayResponse { + impl ::roslibrust_common::RosMessageType for RoundTripArrayResponse { const ROS_TYPE_NAME: &'static str = "test_msgs/RoundTripArrayResponse"; const MD5SUM: &'static str = "d159f2bd8169d3b3339e6f1fce045c6d"; const DEFINITION: &'static str = r#"uint8[] bytes"#; } #[allow(dead_code)] pub struct RoundTripArray {} - impl ::roslibrust_codegen::RosServiceType for RoundTripArray { + impl ::roslibrust_common::RosServiceType for RoundTripArray { const ROS_SERVICE_NAME: &'static str = "test_msgs/RoundTripArray"; const MD5SUM: &'static str = "6a66b36cb6abf834a48739776dfbe789"; type Request = RoundTripArrayRequest; @@ -11220,7 +11220,7 @@ pub mod trajectory_msgs { pub r#joint_names: ::std::vec::Vec<::std::string::String>, pub r#points: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for JointTrajectory { + impl ::roslibrust_common::RosMessageType for JointTrajectory { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/JointTrajectory"; const MD5SUM: &'static str = "65b4f94a94d1ed67169da35a02f33d3f"; const DEFINITION: &'static str = r#"Header header @@ -11270,7 +11270,7 @@ duration time_from_start"#; pub r#effort: ::std::vec::Vec, pub r#time_from_start: ::roslibrust_codegen::integral_types::Duration, } - impl ::roslibrust_codegen::RosMessageType for JointTrajectoryPoint { + impl ::roslibrust_common::RosMessageType for JointTrajectoryPoint { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/JointTrajectoryPoint"; const MD5SUM: &'static str = "f3cd1e1c4d320c79d6985c904ae5dcd3"; const DEFINITION: &'static str = r#"# Each trajectory point specifies either positions[, velocities[, accelerations]] @@ -11298,7 +11298,7 @@ duration time_from_start"#; pub r#joint_names: ::std::vec::Vec<::std::string::String>, pub r#points: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MultiDOFJointTrajectory { + impl ::roslibrust_common::RosMessageType for MultiDOFJointTrajectory { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/MultiDOFJointTrajectory"; const MD5SUM: &'static str = "ef145a45a5f47b77b7f5cdde4b16c942"; const DEFINITION: &'static str = r#"# The header is used to specify the coordinate frame and the reference time for the trajectory durations @@ -11481,7 +11481,7 @@ float64 z"#; pub r#accelerations: ::std::vec::Vec, pub r#time_from_start: ::roslibrust_codegen::integral_types::Duration, } - impl ::roslibrust_codegen::RosMessageType for MultiDOFJointTrajectoryPoint { + impl ::roslibrust_common::RosMessageType for MultiDOFJointTrajectoryPoint { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/MultiDOFJointTrajectoryPoint"; const MD5SUM: &'static str = "3ebe08d1abd5b65862d50e09430db776"; const DEFINITION: &'static str = r#"# Each multi-dof joint can specify a transform (up to 6 DOF) @@ -11599,7 +11599,7 @@ pub mod visualization_msgs { pub r#points: ::std::vec::Vec, pub r#outline_colors: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for ImageMarker { + impl ::roslibrust_common::RosMessageType for ImageMarker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/ImageMarker"; const MD5SUM: &'static str = "1de93c67ec8858b831025a08fbf1b35c"; const DEFINITION: &'static str = r#"uint8 CIRCLE=0 @@ -11683,7 +11683,7 @@ string frame_id"#; pub r#menu_entries: ::std::vec::Vec, pub r#controls: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarker { + impl ::roslibrust_common::RosMessageType for InteractiveMarker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarker"; const MD5SUM: &'static str = "dd86d22909d5a3364b384492e35c10af"; const DEFINITION: &'static str = r#"# Time/frame info. @@ -12224,7 +12224,7 @@ uint8 command_type"#; pub r#independent_marker_orientation: bool, pub r#description: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerControl { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerControl { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerControl"; const MD5SUM: &'static str = "b3c81e785788195d1840b86c28da1aac"; const DEFINITION: &'static str = r#"# Represents a control that is to be displayed together with an interactive marker @@ -12520,7 +12520,7 @@ string frame_id"#; pub r#mouse_point: geometry_msgs::Point, pub r#mouse_point_valid: bool, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerFeedback { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerFeedback { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerFeedback"; const MD5SUM: &'static str = "ab0f1eee058667e28c19ff3ffc3f4b78"; const DEFINITION: &'static str = r#"# Time/frame info. @@ -12638,7 +12638,7 @@ string frame_id"#; pub r#seq_num: u64, pub r#markers: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerInit { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerInit { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerInit"; const MD5SUM: &'static str = "d5f2c5045a72456d228676ab91048734"; const DEFINITION: &'static str = r#"# Identifying string. Must be unique in the topic namespace @@ -13681,7 +13681,7 @@ uint8 command_type"#; pub r#pose: geometry_msgs::Pose, pub r#name: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerPose { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerPose { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerPose"; const MD5SUM: &'static str = "a6e6833209a196a38d798dadb02c81f8"; const DEFINITION: &'static str = r#"# Time/frame info. @@ -13760,7 +13760,7 @@ string frame_id"#; pub r#poses: ::std::vec::Vec, pub r#erases: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerUpdate { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerUpdate { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerUpdate"; const MD5SUM: &'static str = "710d308d0a9276d65945e92dd30b3946"; const DEFINITION: &'static str = r#"# Identifying string. Must be unique in the topic namespace @@ -14896,7 +14896,7 @@ uint8 command_type"#; pub r#mesh_resource: ::std::string::String, pub r#mesh_use_embedded_materials: bool, } - impl ::roslibrust_codegen::RosMessageType for Marker { + impl ::roslibrust_common::RosMessageType for Marker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/Marker"; const MD5SUM: &'static str = "4048c9de2a16f4ae8e0538085ebf1b97"; const DEFINITION: &'static str = r#"# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz @@ -15042,7 +15042,7 @@ string frame_id"#; pub struct MarkerArray { pub r#markers: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MarkerArray { + impl ::roslibrust_common::RosMessageType for MarkerArray { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MarkerArray"; const MD5SUM: &'static str = "d155b9ce5188fbaf89745847fd5882d7"; const DEFINITION: &'static str = r#"Marker[] markers @@ -15242,7 +15242,7 @@ string frame_id"#; pub r#command: ::std::string::String, pub r#command_type: u8, } - impl ::roslibrust_codegen::RosMessageType for MenuEntry { + impl ::roslibrust_common::RosMessageType for MenuEntry { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MenuEntry"; const MD5SUM: &'static str = "b90ec63024573de83b57aa93eb39be2d"; const DEFINITION: &'static str = r#"# MenuEntry message. diff --git a/roslibrust_test/src/ros2.rs b/roslibrust_test/src/ros2.rs index 41c40f54..bd0a602a 100644 --- a/roslibrust_test/src/ros2.rs +++ b/roslibrust_test/src/ros2.rs @@ -25,7 +25,7 @@ pub mod actionlib_msgs { pub r#stamp: ::roslibrust_codegen::integral_types::Time, pub r#id: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for GoalID { + impl ::roslibrust_common::RosMessageType for GoalID { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalID"; const MD5SUM: &'static str = "29380925936d499346662d2ed1573d06"; const DEFINITION: &'static str = r#"# The stamp should store the time at which this goal was requested. @@ -53,7 +53,7 @@ string id"#; pub r#status: u8, pub r#text: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for GoalStatus { + impl ::roslibrust_common::RosMessageType for GoalStatus { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalStatus"; const MD5SUM: &'static str = "c24a9e244d837a856267339807550287"; const DEFINITION: &'static str = r#"GoalID goal_id @@ -118,7 +118,7 @@ string id"#; pub r#header: std_msgs::Header, pub r#status_list: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for GoalStatusArray { + impl ::roslibrust_common::RosMessageType for GoalStatusArray { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalStatusArray"; const MD5SUM: &'static str = "ad4c7a55992b9ff34d89596ca74a28e0"; const DEFINITION: &'static str = r#"# Stores the statuses for goals that are currently being tracked @@ -212,7 +212,7 @@ pub mod diagnostic_msgs { pub r#header: std_msgs::Header, pub r#status: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for DiagnosticArray { + impl ::roslibrust_common::RosMessageType for DiagnosticArray { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/DiagnosticArray"; const MD5SUM: &'static str = "7f04f8332be7e46b680724aa4e9a9d71"; const DEFINITION: &'static str = r#"# This message is used to send diagnostic information about the state of the robot. @@ -279,7 +279,7 @@ string frame_id"#; pub r#hardware_id: ::std::string::String, pub r#values: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for DiagnosticStatus { + impl ::roslibrust_common::RosMessageType for DiagnosticStatus { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/DiagnosticStatus"; const MD5SUM: &'static str = "d0ce08bc6e5ba34c7754f563a9cabaf1"; const DEFINITION: &'static str = r#"# This message holds the status of an individual component of the robot. @@ -328,7 +328,7 @@ string value"#; pub r#key: ::std::string::String, pub r#value: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for KeyValue { + impl ::roslibrust_common::RosMessageType for KeyValue { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/KeyValue"; const MD5SUM: &'static str = "cf57fdc6617a881a88c16e768132149c"; const DEFINITION: &'static str = r#"# What to label this value when viewing. @@ -349,7 +349,7 @@ string value"#; pub struct AddDiagnosticsRequest { pub r#load_namespace: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for AddDiagnosticsRequest { + impl ::roslibrust_common::RosMessageType for AddDiagnosticsRequest { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/AddDiagnosticsRequest"; const MD5SUM: &'static str = "c26cf6e164288fbc6050d74f838bcdf0"; const DEFINITION: &'static str = r#"# This service is used as part of the process for loading analyzers at runtime, @@ -384,7 +384,7 @@ string load_namespace"#; pub r#success: bool, pub r#message: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for AddDiagnosticsResponse { + impl ::roslibrust_common::RosMessageType for AddDiagnosticsResponse { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/AddDiagnosticsResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; const DEFINITION: &'static str = r#"# True if diagnostic aggregator was updated with new diagnostics, False @@ -398,7 +398,7 @@ string message"#; } #[allow(dead_code)] pub struct AddDiagnostics {} - impl ::roslibrust_codegen::RosServiceType for AddDiagnostics { + impl ::roslibrust_common::RosServiceType for AddDiagnostics { const ROS_SERVICE_NAME: &'static str = "diagnostic_msgs/AddDiagnostics"; const MD5SUM: &'static str = "e6ac9bbde83d0d3186523c3687aecaee"; type Request = AddDiagnosticsRequest; @@ -415,7 +415,7 @@ string message"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct SelfTestRequest {} - impl ::roslibrust_codegen::RosMessageType for SelfTestRequest { + impl ::roslibrust_common::RosMessageType for SelfTestRequest { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/SelfTestRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -435,7 +435,7 @@ string message"#; pub r#passed: u8, pub r#status: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for SelfTestResponse { + impl ::roslibrust_common::RosMessageType for SelfTestResponse { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/SelfTestResponse"; const MD5SUM: &'static str = "ac21b1bab7ab17546986536c22eb34e9"; const DEFINITION: &'static str = r#"string id @@ -476,7 +476,7 @@ string value"#; } #[allow(dead_code)] pub struct SelfTest {} - impl ::roslibrust_codegen::RosServiceType for SelfTest { + impl ::roslibrust_common::RosServiceType for SelfTest { const ROS_SERVICE_NAME: &'static str = "diagnostic_msgs/SelfTest"; const MD5SUM: &'static str = "ac21b1bab7ab17546986536c22eb34e9"; type Request = SelfTestRequest; @@ -510,7 +510,7 @@ pub mod geometry_msgs { pub r#linear: self::Vector3, pub r#angular: self::Vector3, } - impl ::roslibrust_codegen::RosMessageType for Accel { + impl ::roslibrust_common::RosMessageType for Accel { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Accel"; const MD5SUM: &'static str = "9f195f881246fdfa2798d1d3eebca84a"; const DEFINITION: &'static str = r#"# This expresses acceleration in free space broken into its linear and angular parts. @@ -542,7 +542,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#accel: self::Accel, } - impl ::roslibrust_codegen::RosMessageType for AccelStamped { + impl ::roslibrust_common::RosMessageType for AccelStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelStamped"; const MD5SUM: &'static str = "19a31cf6d39a90e769a5539f9a293621"; const DEFINITION: &'static str = r#"# An accel with reference coordinate frame and timestamp @@ -603,7 +603,7 @@ string frame_id"#; #[serde(with = "::roslibrust_codegen::BigArray")] pub r#covariance: [f64; 36], } - impl ::roslibrust_codegen::RosMessageType for AccelWithCovariance { + impl ::roslibrust_common::RosMessageType for AccelWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovariance"; const MD5SUM: &'static str = "ad5a718d699c6be72a02b8d6a139f334"; const DEFINITION: &'static str = r#"# This expresses acceleration in free space with uncertainty. @@ -657,7 +657,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#accel: self::AccelWithCovariance, } - impl ::roslibrust_codegen::RosMessageType for AccelWithCovarianceStamped { + impl ::roslibrust_common::RosMessageType for AccelWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovarianceStamped"; const MD5SUM: &'static str = "36b6f1177d3c3f476d4c306279c6f18a"; const DEFINITION: &'static str = r#"# This represents an estimated accel with reference coordinate frame and timestamp. @@ -760,7 +760,7 @@ string frame_id"#; pub r#iyz: f64, pub r#izz: f64, } - impl ::roslibrust_codegen::RosMessageType for Inertia { + impl ::roslibrust_common::RosMessageType for Inertia { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Inertia"; const MD5SUM: &'static str = "1d26e4bb6c83ff141c5cf0d883c2b0fe"; const DEFINITION: &'static str = r#"# Mass [kg] @@ -805,7 +805,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#inertia: self::Inertia, } - impl ::roslibrust_codegen::RosMessageType for InertiaStamped { + impl ::roslibrust_common::RosMessageType for InertiaStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/InertiaStamped"; const MD5SUM: &'static str = "d4fb75ac056292d6c4bbec5e51d25080"; const DEFINITION: &'static str = r#"# An Inertia with a time stamp and reference frame. @@ -879,7 +879,7 @@ string frame_id"#; pub r#y: f64, pub r#z: f64, } - impl ::roslibrust_codegen::RosMessageType for Point { + impl ::roslibrust_common::RosMessageType for Point { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Point"; const MD5SUM: &'static str = "4a842b65f413084dc2b10fb484ea7f17"; const DEFINITION: &'static str = r#"# This contains the position of a point in free space @@ -902,7 +902,7 @@ float64 z"#; pub r#y: f32, pub r#z: f32, } - impl ::roslibrust_codegen::RosMessageType for Point32 { + impl ::roslibrust_common::RosMessageType for Point32 { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Point32"; const MD5SUM: &'static str = "cc153912f1453b708d221682bc23d9ac"; const DEFINITION: &'static str = r#"# This contains the position of a point in free space(with 32 bits of precision). @@ -931,7 +931,7 @@ float32 z"#; pub r#header: std_msgs::Header, pub r#point: self::Point, } - impl ::roslibrust_codegen::RosMessageType for PointStamped { + impl ::roslibrust_common::RosMessageType for PointStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PointStamped"; const MD5SUM: &'static str = "938cb86faf4572821e49e2490701e6df"; const DEFINITION: &'static str = r#"# This represents a Point with reference coordinate frame and timestamp @@ -969,7 +969,7 @@ string frame_id"#; pub struct Polygon { pub r#points: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Polygon { + impl ::roslibrust_common::RosMessageType for Polygon { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Polygon"; const MD5SUM: &'static str = "cd60a26494a087f577976f0329fa120e"; const DEFINITION: &'static str = r#"# A specification of a polygon where the first and last points are assumed to be connected @@ -1003,7 +1003,7 @@ float32 z"#; pub r#header: std_msgs::Header, pub r#polygon: self::Polygon, } - impl ::roslibrust_codegen::RosMessageType for PolygonStamped { + impl ::roslibrust_common::RosMessageType for PolygonStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PolygonStamped"; const MD5SUM: &'static str = "56a3a2a80165092f696df3db62e18fbf"; const DEFINITION: &'static str = r#"# This represents a Polygon with reference coordinate frame and timestamp @@ -1067,7 +1067,7 @@ string frame_id"#; pub r#position: self::Point, pub r#orientation: self::Quaternion, } - impl ::roslibrust_codegen::RosMessageType for Pose { + impl ::roslibrust_common::RosMessageType for Pose { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Pose"; const MD5SUM: &'static str = "e45d45a5a1ce597b249e23fb30fc871f"; const DEFINITION: &'static str = r#"# A representation of pose in free space, composed of position and orientation. @@ -1104,7 +1104,7 @@ float64 w 1"#; pub r#y: f64, pub r#theta: f64, } - impl ::roslibrust_codegen::RosMessageType for Pose2D { + impl ::roslibrust_common::RosMessageType for Pose2D { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Pose2D"; const MD5SUM: &'static str = "938fa65709584ad8e77d238529be13b8"; const DEFINITION: &'static str = r#"# Deprecated as of Foxy and will potentially be removed in any following release. @@ -1132,7 +1132,7 @@ float64 theta"#; pub r#header: std_msgs::Header, pub r#poses: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for PoseArray { + impl ::roslibrust_common::RosMessageType for PoseArray { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseArray"; const MD5SUM: &'static str = "ea7300c78ec47498d5f226be74a155e8"; const DEFINITION: &'static str = r#"# An array of poses with a header for global reference. @@ -1200,7 +1200,7 @@ string frame_id"#; pub r#header: std_msgs::Header, pub r#pose: self::Pose, } - impl ::roslibrust_codegen::RosMessageType for PoseStamped { + impl ::roslibrust_common::RosMessageType for PoseStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseStamped"; const MD5SUM: &'static str = "c088ec4a70a5930b0ca46520d5745e2d"; const DEFINITION: &'static str = r#"# A Pose with reference coordinate frame and timestamp @@ -1269,7 +1269,7 @@ string frame_id"#; #[serde(with = "::roslibrust_codegen::BigArray")] pub r#covariance: [f64; 36], } - impl ::roslibrust_codegen::RosMessageType for PoseWithCovariance { + impl ::roslibrust_common::RosMessageType for PoseWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovariance"; const MD5SUM: &'static str = "c23e848cf1b7533a8d7c259073a97e6f"; const DEFINITION: &'static str = r#"# This represents a pose in free space with uncertainty. @@ -1330,7 +1330,7 @@ float64 w 1"#; pub r#header: std_msgs::Header, pub r#pose: self::PoseWithCovariance, } - impl ::roslibrust_codegen::RosMessageType for PoseWithCovarianceStamped { + impl ::roslibrust_common::RosMessageType for PoseWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovarianceStamped"; const MD5SUM: &'static str = "2178452bf195c1abe1e99b07b4e6c8f0"; const DEFINITION: &'static str = r#"# This expresses an estimated pose with a reference coordinate frame and timestamp @@ -1448,7 +1448,7 @@ string frame_id"#; #[default(1f64)] pub r#w: f64, } - impl ::roslibrust_codegen::RosMessageType for Quaternion { + impl ::roslibrust_common::RosMessageType for Quaternion { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Quaternion"; const MD5SUM: &'static str = "a779879fadf0160734f906b8c19c7004"; const DEFINITION: &'static str = r#"# This represents an orientation in free space in quaternion form. @@ -1472,7 +1472,7 @@ float64 w 1"#; pub r#header: std_msgs::Header, pub r#quaternion: self::Quaternion, } - impl ::roslibrust_codegen::RosMessageType for QuaternionStamped { + impl ::roslibrust_common::RosMessageType for QuaternionStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/QuaternionStamped"; const MD5SUM: &'static str = "8f93ed7c8430d06bd82fefcc6f7a349e"; const DEFINITION: &'static str = r#"# This represents an orientation with reference coordinate frame and timestamp. @@ -1513,7 +1513,7 @@ string frame_id"#; pub r#translation: self::Vector3, pub r#rotation: self::Quaternion, } - impl ::roslibrust_codegen::RosMessageType for Transform { + impl ::roslibrust_common::RosMessageType for Transform { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Transform"; const MD5SUM: &'static str = "ac9eff44abf714214112b05d54a3cf9b"; const DEFINITION: &'static str = r#"# This represents the transform between two coordinate frames in free space. @@ -1555,7 +1555,7 @@ float64 z"#; pub r#child_frame_id: ::std::string::String, pub r#transform: self::Transform, } - impl ::roslibrust_codegen::RosMessageType for TransformStamped { + impl ::roslibrust_common::RosMessageType for TransformStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TransformStamped"; const MD5SUM: &'static str = "09bf247c06cf7c69e8c55300b05a7a04"; const DEFINITION: &'static str = r#"# This expresses a transform from coordinate frame header.frame_id @@ -1647,7 +1647,7 @@ string frame_id"#; pub r#linear: self::Vector3, pub r#angular: self::Vector3, } - impl ::roslibrust_codegen::RosMessageType for Twist { + impl ::roslibrust_common::RosMessageType for Twist { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Twist"; const MD5SUM: &'static str = "9f195f881246fdfa2798d1d3eebca84a"; const DEFINITION: &'static str = r#"# This expresses velocity in free space broken into its linear and angular parts. @@ -1680,7 +1680,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#twist: self::Twist, } - impl ::roslibrust_codegen::RosMessageType for TwistStamped { + impl ::roslibrust_common::RosMessageType for TwistStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistStamped"; const MD5SUM: &'static str = "09f84400c1ca2e7e26a9da1232813bd0"; const DEFINITION: &'static str = r#"# A twist with reference coordinate frame and timestamp @@ -1743,7 +1743,7 @@ string frame_id"#; #[serde(with = "::roslibrust_codegen::BigArray")] pub r#covariance: [f64; 36], } - impl ::roslibrust_codegen::RosMessageType for TwistWithCovariance { + impl ::roslibrust_common::RosMessageType for TwistWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovariance"; const MD5SUM: &'static str = "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; const DEFINITION: &'static str = r#"# This expresses velocity in free space with uncertainty. @@ -1798,7 +1798,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#twist: self::TwistWithCovariance, } - impl ::roslibrust_codegen::RosMessageType for TwistWithCovarianceStamped { + impl ::roslibrust_common::RosMessageType for TwistWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovarianceStamped"; const MD5SUM: &'static str = "7019807c85ce8602fb83180366470670"; const DEFINITION: &'static str = r#"# This represents an estimated twist with reference coordinate frame and timestamp. @@ -1899,7 +1899,7 @@ string frame_id"#; pub r#y: f64, pub r#z: f64, } - impl ::roslibrust_codegen::RosMessageType for Vector3 { + impl ::roslibrust_common::RosMessageType for Vector3 { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Vector3"; const MD5SUM: &'static str = "4a842b65f413084dc2b10fb484ea7f17"; const DEFINITION: &'static str = r#"# This represents a vector in free space. @@ -1926,7 +1926,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#vector: self::Vector3, } - impl ::roslibrust_codegen::RosMessageType for Vector3Stamped { + impl ::roslibrust_common::RosMessageType for Vector3Stamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Vector3Stamped"; const MD5SUM: &'static str = "5cd361f2989a2e76d5aaf432c3bf0fb9"; const DEFINITION: &'static str = r#"# This represents a Vector3 with reference coordinate frame and timestamp @@ -1973,7 +1973,7 @@ string frame_id"#; pub r#force: self::Vector3, pub r#torque: self::Vector3, } - impl ::roslibrust_codegen::RosMessageType for Wrench { + impl ::roslibrust_common::RosMessageType for Wrench { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Wrench"; const MD5SUM: &'static str = "4f539cf138b23283b520fd271b567936"; const DEFINITION: &'static str = r#"# This represents force in free space, separated into its linear and angular parts. @@ -2006,7 +2006,7 @@ float64 z"#; pub r#header: std_msgs::Header, pub r#wrench: self::Wrench, } - impl ::roslibrust_codegen::RosMessageType for WrenchStamped { + impl ::roslibrust_common::RosMessageType for WrenchStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/WrenchStamped"; const MD5SUM: &'static str = "5bc71556ab354cd6274d262a7de094a5"; const DEFINITION: &'static str = r#"# A wrench with reference coordinate frame and timestamp @@ -2083,7 +2083,7 @@ pub mod nav_msgs { pub r#cell_height: f32, pub r#cells: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for GridCells { + impl ::roslibrust_common::RosMessageType for GridCells { const ROS_TYPE_NAME: &'static str = "nav_msgs/GridCells"; const MD5SUM: &'static str = "bb9f07bfd2183241b5719f45a81f8cc5"; const DEFINITION: &'static str = r#"# An array of cells in a 2D grid @@ -2133,7 +2133,7 @@ string frame_id"#; pub r#height: u32, pub r#origin: geometry_msgs::Pose, } - impl ::roslibrust_codegen::RosMessageType for MapMetaData { + impl ::roslibrust_common::RosMessageType for MapMetaData { const ROS_TYPE_NAME: &'static str = "nav_msgs/MapMetaData"; const MD5SUM: &'static str = "d10232bae3de4ae536d98f679fce2cf2"; const DEFINITION: &'static str = r#"# This hold basic information about the characteristics of the OccupancyGrid @@ -2203,7 +2203,7 @@ float64 w 1"#; pub r#info: self::MapMetaData, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for OccupancyGrid { + impl ::roslibrust_common::RosMessageType for OccupancyGrid { const ROS_TYPE_NAME: &'static str = "nav_msgs/OccupancyGrid"; const MD5SUM: &'static str = "2b0657f1993991bf3953916eb5ff5203"; const DEFINITION: &'static str = r#"# This represents a 2-D grid map @@ -2334,7 +2334,7 @@ string frame_id"#; pub r#pose: geometry_msgs::PoseWithCovariance, pub r#twist: geometry_msgs::TwistWithCovariance, } - impl ::roslibrust_codegen::RosMessageType for Odometry { + impl ::roslibrust_common::RosMessageType for Odometry { const ROS_TYPE_NAME: &'static str = "nav_msgs/Odometry"; const MD5SUM: &'static str = "81a0900daae2c6c0acc71c9f8df88947"; const DEFINITION: &'static str = r#"# This represents an estimate of a position and velocity in free space. @@ -2524,7 +2524,7 @@ string frame_id"#; pub r#header: std_msgs::Header, pub r#poses: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Path { + impl ::roslibrust_common::RosMessageType for Path { const ROS_TYPE_NAME: &'static str = "nav_msgs/Path"; const MD5SUM: &'static str = "9f78b006a4c2cc2a146c12ed59d1bb7f"; const DEFINITION: &'static str = r#"# An array of poses that represents a Path for a robot to follow. @@ -2642,7 +2642,7 @@ string frame_id"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct GetMapRequest {} - impl ::roslibrust_codegen::RosMessageType for GetMapRequest { + impl ::roslibrust_common::RosMessageType for GetMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#"# Get the map as a nav_msgs/OccupancyGrid"#; @@ -2660,7 +2660,7 @@ string frame_id"#; pub struct GetMapResponse { pub r#map: self::OccupancyGrid, } - impl ::roslibrust_codegen::RosMessageType for GetMapResponse { + impl ::roslibrust_common::RosMessageType for GetMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapResponse"; const MD5SUM: &'static str = "d6e8b0301af2dfe2244959ba20a4080a"; const DEFINITION: &'static str = r#"# The current map hosted by this map service. @@ -2879,7 +2879,7 @@ string frame_id"#; } #[allow(dead_code)] pub struct GetMap {} - impl ::roslibrust_codegen::RosServiceType for GetMap { + impl ::roslibrust_common::RosServiceType for GetMap { const ROS_SERVICE_NAME: &'static str = "nav_msgs/GetMap"; const MD5SUM: &'static str = "d6e8b0301af2dfe2244959ba20a4080a"; type Request = GetMapRequest; @@ -2900,7 +2900,7 @@ string frame_id"#; pub r#goal: geometry_msgs::PoseStamped, pub r#tolerance: f32, } - impl ::roslibrust_codegen::RosMessageType for GetPlanRequest { + impl ::roslibrust_common::RosMessageType for GetPlanRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetPlanRequest"; const MD5SUM: &'static str = "e4855e4d3c7377c76ec90e403202286a"; const DEFINITION: &'static str = r#"# Get a plan from the current position to the goal Pose @@ -3024,7 +3024,7 @@ string frame_id"#; pub struct GetPlanResponse { pub r#plan: self::Path, } - impl ::roslibrust_codegen::RosMessageType for GetPlanResponse { + impl ::roslibrust_common::RosMessageType for GetPlanResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetPlanResponse"; const MD5SUM: &'static str = "37c13f9b42d0ee04e1dae0d4f7d14878"; const DEFINITION: &'static str = r#"# Array of poses from start to goal if one was successfully found. @@ -3233,7 +3233,7 @@ string frame_id"#; } #[allow(dead_code)] pub struct GetPlan {} - impl ::roslibrust_codegen::RosServiceType for GetPlan { + impl ::roslibrust_common::RosServiceType for GetPlan { const ROS_SERVICE_NAME: &'static str = "nav_msgs/GetPlan"; const MD5SUM: &'static str = "135edd06523950427d2cf5e0bb9780a2"; type Request = GetPlanRequest; @@ -3252,7 +3252,7 @@ string frame_id"#; pub struct LoadMapRequest { pub r#map_url: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for LoadMapRequest { + impl ::roslibrust_common::RosMessageType for LoadMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/LoadMapRequest"; const MD5SUM: &'static str = "3813ba1ae85fbcd4dc88c90f1426b90b"; const DEFINITION: &'static str = r#"# URL of map resource @@ -3274,7 +3274,7 @@ string map_url"#; pub r#map: self::OccupancyGrid, pub r#result: u8, } - impl ::roslibrust_codegen::RosMessageType for LoadMapResponse { + impl ::roslibrust_common::RosMessageType for LoadMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/LoadMapResponse"; const MD5SUM: &'static str = "cdb849e3dfaed8b5fe66776d7a64b83e"; const DEFINITION: &'static str = r#"# Result code defintions @@ -3509,7 +3509,7 @@ string frame_id"#; } #[allow(dead_code)] pub struct LoadMap {} - impl ::roslibrust_codegen::RosServiceType for LoadMap { + impl ::roslibrust_common::RosServiceType for LoadMap { const ROS_SERVICE_NAME: &'static str = "nav_msgs/LoadMap"; const MD5SUM: &'static str = "96c8a15e8fe5c33ee245f610f020d6ba"; type Request = LoadMapRequest; @@ -3529,7 +3529,7 @@ string frame_id"#; pub r#map: self::OccupancyGrid, pub r#initial_pose: geometry_msgs::PoseWithCovarianceStamped, } - impl ::roslibrust_codegen::RosMessageType for SetMapRequest { + impl ::roslibrust_common::RosMessageType for SetMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/SetMapRequest"; const MD5SUM: &'static str = "98782a373ad73e1165352caf85923850"; const DEFINITION: &'static str = r#"# Set a new map together with an initial pose @@ -3905,7 +3905,7 @@ string frame_id"#; pub struct SetMapResponse { pub r#success: bool, } - impl ::roslibrust_codegen::RosMessageType for SetMapResponse { + impl ::roslibrust_common::RosMessageType for SetMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/SetMapResponse"; const MD5SUM: &'static str = "358e233cde0c8a8bcfea4ce193f8fc15"; const DEFINITION: &'static str = r#"# True if the map was successfully set, false otherwise. @@ -3913,7 +3913,7 @@ bool success"#; } #[allow(dead_code)] pub struct SetMap {} - impl ::roslibrust_codegen::RosServiceType for SetMap { + impl ::roslibrust_common::RosServiceType for SetMap { const ROS_SERVICE_NAME: &'static str = "nav_msgs/SetMap"; const MD5SUM: &'static str = "6c3f8182fbcb3d4ee7aef02d1dcd1e16"; type Request = SetMapRequest; @@ -3961,7 +3961,7 @@ pub mod sensor_msgs { pub r#location: ::std::string::String, pub r#serial_number: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for BatteryState { + impl ::roslibrust_common::RosMessageType for BatteryState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/BatteryState"; const MD5SUM: &'static str = "0e25cedcd370a46961764fe3a9d2ddcb"; const DEFINITION: &'static str = r#"# Constants are chosen to match the enums in the linux kernel @@ -4074,7 +4074,7 @@ string frame_id"#; pub r#binning_y: u32, pub r#roi: self::RegionOfInterest, } - impl ::roslibrust_codegen::RosMessageType for CameraInfo { + impl ::roslibrust_common::RosMessageType for CameraInfo { const ROS_TYPE_NAME: &'static str = "sensor_msgs/CameraInfo"; const MD5SUM: &'static str = "47b55ddbbf2ec398f94cddf328bbc2ac"; const DEFINITION: &'static str = r#"# This message defines meta information for a camera. It should be in a @@ -4255,7 +4255,7 @@ string frame_id"#; pub r#name: ::std::string::String, pub r#values: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for ChannelFloat32 { + impl ::roslibrust_common::RosMessageType for ChannelFloat32 { const ROS_TYPE_NAME: &'static str = "sensor_msgs/ChannelFloat32"; const MD5SUM: &'static str = "3d40139cdd33dfedcb71ffeeeb42ae7f"; const DEFINITION: &'static str = r#"# This message is used by the PointCloud message to hold optional data @@ -4299,7 +4299,7 @@ float32[] values"#; #[serde(with = "::roslibrust_codegen::serde_bytes")] pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for CompressedImage { + impl ::roslibrust_common::RosMessageType for CompressedImage { const ROS_TYPE_NAME: &'static str = "sensor_msgs/CompressedImage"; const MD5SUM: &'static str = "1df88053b24348f5f499666c7cb1d980"; const DEFINITION: &'static str = r#"# This message contains a compressed image. @@ -4343,7 +4343,7 @@ string frame_id"#; pub r#fluid_pressure: f64, pub r#variance: f64, } - impl ::roslibrust_codegen::RosMessageType for FluidPressure { + impl ::roslibrust_common::RosMessageType for FluidPressure { const ROS_TYPE_NAME: &'static str = "sensor_msgs/FluidPressure"; const MD5SUM: &'static str = "4967e6ff4dcf72e6b8fca0600661e0b6"; const DEFINITION: &'static str = r#"# Single pressure reading. This message is appropriate for measuring the @@ -4385,7 +4385,7 @@ string frame_id"#; pub r#illuminance: f64, pub r#variance: f64, } - impl ::roslibrust_codegen::RosMessageType for Illuminance { + impl ::roslibrust_common::RosMessageType for Illuminance { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Illuminance"; const MD5SUM: &'static str = "94ccac1a1be684df74466dfc561512aa"; const DEFINITION: &'static str = r#"# Single photometric illuminance measurement. Light should be assumed to be @@ -4440,7 +4440,7 @@ string frame_id"#; #[serde(with = "::roslibrust_codegen::serde_bytes")] pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Image { + impl ::roslibrust_common::RosMessageType for Image { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Image"; const MD5SUM: &'static str = "9c8b3d25a28b72f070da359dbecf985b"; const DEFINITION: &'static str = r#"# This message contains an uncompressed image @@ -4500,7 +4500,7 @@ string frame_id"#; pub r#linear_acceleration: geometry_msgs::Vector3, pub r#linear_acceleration_covariance: [f64; 9], } - impl ::roslibrust_codegen::RosMessageType for Imu { + impl ::roslibrust_common::RosMessageType for Imu { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Imu"; const MD5SUM: &'static str = "058a92f712764b4ade1563e82041c569"; const DEFINITION: &'static str = r#"# This is a message to hold data from an IMU (Inertial Measurement Unit) @@ -4575,7 +4575,7 @@ string frame_id"#; pub r#velocity: ::std::vec::Vec, pub r#effort: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for JointState { + impl ::roslibrust_common::RosMessageType for JointState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JointState"; const MD5SUM: &'static str = "3f61f1439a9898cdd864497d378ce55c"; const DEFINITION: &'static str = r#"# This is a message that holds data to describe the state of a set of torque controlled joints. @@ -4630,7 +4630,7 @@ string frame_id"#; pub r#axes: ::std::vec::Vec, pub r#buttons: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Joy { + impl ::roslibrust_common::RosMessageType for Joy { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Joy"; const MD5SUM: &'static str = "967f985c9ca9013a4669430613e3e016"; const DEFINITION: &'static str = r#"# Reports the state of a joystick's axes and buttons. @@ -4670,7 +4670,7 @@ string frame_id"#; pub r#id: u8, pub r#intensity: f32, } - impl ::roslibrust_codegen::RosMessageType for JoyFeedback { + impl ::roslibrust_common::RosMessageType for JoyFeedback { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JoyFeedback"; const MD5SUM: &'static str = "f4dcd73460360d98f36e55ee7f2e46f1"; const DEFINITION: &'static str = r#"# Declare of the type of feedback @@ -4707,7 +4707,7 @@ float32 intensity"#; pub struct JoyFeedbackArray { pub r#array: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for JoyFeedbackArray { + impl ::roslibrust_common::RosMessageType for JoyFeedbackArray { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JoyFeedbackArray"; const MD5SUM: &'static str = "cde5730a895b1fc4dee6f91b754b213d"; const DEFINITION: &'static str = r#"# This message publishes values for multiple feedback at once. @@ -4742,7 +4742,7 @@ float32 intensity"#; pub struct LaserEcho { pub r#echoes: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for LaserEcho { + impl ::roslibrust_common::RosMessageType for LaserEcho { const ROS_TYPE_NAME: &'static str = "sensor_msgs/LaserEcho"; const MD5SUM: &'static str = "8bc5ae449b200fba4d552b4225586696"; const DEFINITION: &'static str = r#"# This message is a submessage of MultiEchoLaserScan and is not intended @@ -4773,7 +4773,7 @@ float32[] echoes # Multiple values of ranges or intensities. pub r#ranges: ::std::vec::Vec, pub r#intensities: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for LaserScan { + impl ::roslibrust_common::RosMessageType for LaserScan { const ROS_TYPE_NAME: &'static str = "sensor_msgs/LaserScan"; const MD5SUM: &'static str = "f86984b4383bf67523c75820e114e988"; const DEFINITION: &'static str = r#"# Single scan from a planar laser range-finder @@ -4833,7 +4833,7 @@ string frame_id"#; pub r#magnetic_field: geometry_msgs::Vector3, pub r#magnetic_field_covariance: [f64; 9], } - impl ::roslibrust_codegen::RosMessageType for MagneticField { + impl ::roslibrust_common::RosMessageType for MagneticField { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MagneticField"; const MD5SUM: &'static str = "c8761d20eb9dc59addd882f1d4de2266"; const DEFINITION: &'static str = r#"# Measurement of the Magnetic Field vector at a specific location. @@ -4897,7 +4897,7 @@ string frame_id"#; pub r#twist: ::std::vec::Vec, pub r#wrench: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MultiDOFJointState { + impl ::roslibrust_common::RosMessageType for MultiDOFJointState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MultiDOFJointState"; const MD5SUM: &'static str = "9eb02d78422731545fd7e9b60069f261"; const DEFINITION: &'static str = r#"# Representation of state for joints with multiple degrees of freedom, @@ -5038,7 +5038,7 @@ string frame_id"#; pub r#ranges: ::std::vec::Vec, pub r#intensities: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MultiEchoLaserScan { + impl ::roslibrust_common::RosMessageType for MultiEchoLaserScan { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MultiEchoLaserScan"; const MD5SUM: &'static str = "fda674281c16cdee9a79d075ab27d12f"; const DEFINITION: &'static str = r#"# Single scan from a multi-echo planar laser range-finder @@ -5111,7 +5111,7 @@ string frame_id"#; pub r#position_covariance: [f64; 9], pub r#position_covariance_type: u8, } - impl ::roslibrust_codegen::RosMessageType for NavSatFix { + impl ::roslibrust_common::RosMessageType for NavSatFix { const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatFix"; const MD5SUM: &'static str = "faa1756146a6a934d7e4ef0e3855c531"; const DEFINITION: &'static str = r#"# Navigation Satellite fix for any Global Navigation Satellite System @@ -5216,7 +5216,7 @@ string frame_id"#; pub r#status: i8, pub r#service: u16, } - impl ::roslibrust_codegen::RosMessageType for NavSatStatus { + impl ::roslibrust_common::RosMessageType for NavSatStatus { const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatStatus"; const MD5SUM: &'static str = "331cdbddfa4bc96ffc3b9ad98900a54c"; const DEFINITION: &'static str = r#"# Navigation Satellite fix status for any Global Navigation Satellite System. @@ -5268,7 +5268,7 @@ uint16 service"#; pub r#points: ::std::vec::Vec, pub r#channels: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for PointCloud { + impl ::roslibrust_common::RosMessageType for PointCloud { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointCloud"; const MD5SUM: &'static str = "95c9c548e015c235b38b961c79973db7"; const DEFINITION: &'static str = r#"## THIS MESSAGE IS DEPRECATED AS OF FOXY @@ -5361,7 +5361,7 @@ string frame_id"#; pub r#data: ::std::vec::Vec, pub r#is_dense: bool, } - impl ::roslibrust_codegen::RosMessageType for PointCloud2 { + impl ::roslibrust_common::RosMessageType for PointCloud2 { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointCloud2"; const MD5SUM: &'static str = "c61ffb665fe19735825e4dd31b53913d"; const DEFINITION: &'static str = r#"# This message holds a collection of N-dimensional points, which may @@ -5436,7 +5436,7 @@ string frame_id"#; pub r#datatype: u8, pub r#count: u32, } - impl ::roslibrust_codegen::RosMessageType for PointField { + impl ::roslibrust_common::RosMessageType for PointField { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointField"; const MD5SUM: &'static str = "268eacb2962780ceac86cbd17e328150"; const DEFINITION: &'static str = r#"# This message holds the description of one point entry in the @@ -5485,7 +5485,7 @@ uint32 count # How many elements in the field"#; pub r#max_range: f32, pub r#range: f32, } - impl ::roslibrust_codegen::RosMessageType for Range { + impl ::roslibrust_common::RosMessageType for Range { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Range"; const MD5SUM: &'static str = "1ec40687acdf15b9559a6ff690722eae"; const DEFINITION: &'static str = r#"# Single range reading from an active ranger that emits energy and reports @@ -5561,7 +5561,7 @@ string frame_id"#; pub r#width: u32, pub r#do_rectify: bool, } - impl ::roslibrust_codegen::RosMessageType for RegionOfInterest { + impl ::roslibrust_common::RosMessageType for RegionOfInterest { const ROS_TYPE_NAME: &'static str = "sensor_msgs/RegionOfInterest"; const MD5SUM: &'static str = "bdb633039d588fcccb441a4d43ccfe09"; const DEFINITION: &'static str = r#"# This message is used to specify a region of interest within an image. @@ -5599,7 +5599,7 @@ bool do_rectify"#; pub r#relative_humidity: f64, pub r#variance: f64, } - impl ::roslibrust_codegen::RosMessageType for RelativeHumidity { + impl ::roslibrust_common::RosMessageType for RelativeHumidity { const ROS_TYPE_NAME: &'static str = "sensor_msgs/RelativeHumidity"; const MD5SUM: &'static str = "71cfefa31dcc94f47083b1e89e6fa5c9"; const DEFINITION: &'static str = r#"# Single reading from a relative humidity sensor. @@ -5642,7 +5642,7 @@ string frame_id"#; pub r#temperature: f64, pub r#variance: f64, } - impl ::roslibrust_codegen::RosMessageType for Temperature { + impl ::roslibrust_common::RosMessageType for Temperature { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Temperature"; const MD5SUM: &'static str = "c6df0674fcfebff84a15927a80ebb14b"; const DEFINITION: &'static str = r#"# Single temperature reading. @@ -5680,7 +5680,7 @@ string frame_id"#; pub r#time_ref: ::roslibrust_codegen::integral_types::Time, pub r#source: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for TimeReference { + impl ::roslibrust_common::RosMessageType for TimeReference { const ROS_TYPE_NAME: &'static str = "sensor_msgs/TimeReference"; const MD5SUM: &'static str = "7cb7ae5aa838323e9028637e304e0ad7"; const DEFINITION: &'static str = r#"# Measurement from an external time source not actively synchronized with the system clock. @@ -5715,7 +5715,7 @@ string frame_id"#; pub struct SetCameraInfoRequest { pub r#camera_info: self::CameraInfo, } - impl ::roslibrust_codegen::RosMessageType for SetCameraInfoRequest { + impl ::roslibrust_common::RosMessageType for SetCameraInfoRequest { const ROS_TYPE_NAME: &'static str = "sensor_msgs/SetCameraInfoRequest"; const MD5SUM: &'static str = "251c96e357751cc7c699c496178141d5"; const DEFINITION: &'static str = r#"# This service requests that a camera stores the given CameraInfo as that @@ -5939,7 +5939,7 @@ string frame_id"#; pub r#success: bool, pub r#status_message: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for SetCameraInfoResponse { + impl ::roslibrust_common::RosMessageType for SetCameraInfoResponse { const ROS_TYPE_NAME: &'static str = "sensor_msgs/SetCameraInfoResponse"; const MD5SUM: &'static str = "2ec6f3eff0161f4257b808b12bc830c2"; const DEFINITION: &'static str = r#"bool success # True if the call succeeded @@ -5947,7 +5947,7 @@ string status_message # Used to give details about success"#; } #[allow(dead_code)] pub struct SetCameraInfo {} - impl ::roslibrust_codegen::RosServiceType for SetCameraInfo { + impl ::roslibrust_common::RosServiceType for SetCameraInfo { const ROS_SERVICE_NAME: &'static str = "sensor_msgs/SetCameraInfo"; const MD5SUM: &'static str = "c191a50a3d5730b8679f4b95b3948b15"; type Request = SetCameraInfoRequest; @@ -5981,7 +5981,7 @@ pub mod shape_msgs { pub r#triangles: ::std::vec::Vec, pub r#vertices: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Mesh { + impl ::roslibrust_common::RosMessageType for Mesh { const ROS_TYPE_NAME: &'static str = "shape_msgs/Mesh"; const MD5SUM: &'static str = "1ffdae9486cd3316a121c578b47a85cc"; const DEFINITION: &'static str = r#"# Definition of a mesh. @@ -6016,7 +6016,7 @@ uint32[3] vertex_indices"#; pub struct MeshTriangle { pub r#vertex_indices: [u32; 3], } - impl ::roslibrust_codegen::RosMessageType for MeshTriangle { + impl ::roslibrust_common::RosMessageType for MeshTriangle { const ROS_TYPE_NAME: &'static str = "shape_msgs/MeshTriangle"; const MD5SUM: &'static str = "23688b2e6d2de3d32fe8af104a903253"; const DEFINITION: &'static str = r#"# Definition of a triangle's vertices. @@ -6036,7 +6036,7 @@ uint32[3] vertex_indices"#; pub struct Plane { pub r#coef: [f64; 4], } - impl ::roslibrust_codegen::RosMessageType for Plane { + impl ::roslibrust_common::RosMessageType for Plane { const ROS_TYPE_NAME: &'static str = "shape_msgs/Plane"; const MD5SUM: &'static str = "2c1b92ed8f31492f8e73f6a4a44ca796"; const DEFINITION: &'static str = r#"# Representation of a plane, using the plane equation ax + by + cz + d = 0. @@ -6062,7 +6062,7 @@ float64[4] coef"#; pub r#dimensions: [f64; 0], pub r#polygon: geometry_msgs::Polygon, } - impl ::roslibrust_codegen::RosMessageType for SolidPrimitive { + impl ::roslibrust_common::RosMessageType for SolidPrimitive { const ROS_TYPE_NAME: &'static str = "shape_msgs/SolidPrimitive"; const MD5SUM: &'static str = "0cdf91a0a45ccd7bc1e0deb784cb2958"; const DEFINITION: &'static str = r#"# Defines box, sphere, cylinder, cone and prism. @@ -6191,7 +6191,7 @@ pub mod std_msgs { pub struct Bool { pub r#data: bool, } - impl ::roslibrust_codegen::RosMessageType for Bool { + impl ::roslibrust_common::RosMessageType for Bool { const ROS_TYPE_NAME: &'static str = "std_msgs/Bool"; const MD5SUM: &'static str = "8b94c1b53db61fb6aed406028ad6332a"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6214,7 +6214,7 @@ bool data"#; pub struct Byte { pub r#data: u8, } - impl ::roslibrust_codegen::RosMessageType for Byte { + impl ::roslibrust_common::RosMessageType for Byte { const ROS_TYPE_NAME: &'static str = "std_msgs/Byte"; const MD5SUM: &'static str = "ad736a2e8818154c487bb80fe42ce43b"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6238,7 +6238,7 @@ byte data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for ByteMultiArray { + impl ::roslibrust_common::RosMessageType for ByteMultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/ByteMultiArray"; const MD5SUM: &'static str = "70ea476cbcfd65ac2f68f3cda1e891fe"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6318,7 +6318,7 @@ uint32 stride # stride of given dimension"#; pub struct Char { pub r#data: u8, } - impl ::roslibrust_codegen::RosMessageType for Char { + impl ::roslibrust_common::RosMessageType for Char { const ROS_TYPE_NAME: &'static str = "std_msgs/Char"; const MD5SUM: &'static str = "1bf77f25acecdedba0e224b162199717"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6344,7 +6344,7 @@ char data"#; pub r#b: f32, pub r#a: f32, } - impl ::roslibrust_codegen::RosMessageType for ColorRGBA { + impl ::roslibrust_common::RosMessageType for ColorRGBA { const ROS_TYPE_NAME: &'static str = "std_msgs/ColorRGBA"; const MD5SUM: &'static str = "a29a96539573343b1310c73607334b00"; const DEFINITION: &'static str = r#"float32 r @@ -6363,7 +6363,7 @@ float32 a"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct Empty {} - impl ::roslibrust_codegen::RosMessageType for Empty { + impl ::roslibrust_common::RosMessageType for Empty { const ROS_TYPE_NAME: &'static str = "std_msgs/Empty"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -6381,7 +6381,7 @@ float32 a"#; pub struct Float32 { pub r#data: f32, } - impl ::roslibrust_codegen::RosMessageType for Float32 { + impl ::roslibrust_common::RosMessageType for Float32 { const ROS_TYPE_NAME: &'static str = "std_msgs/Float32"; const MD5SUM: &'static str = "73fcbf46b49191e672908e50842a83d4"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6405,7 +6405,7 @@ float32 data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Float32MultiArray { + impl ::roslibrust_common::RosMessageType for Float32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Float32MultiArray"; const MD5SUM: &'static str = "6a40e0ffa6a17a503ac3f8616991b1f6"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6485,7 +6485,7 @@ uint32 stride # stride of given dimension"#; pub struct Float64 { pub r#data: f64, } - impl ::roslibrust_codegen::RosMessageType for Float64 { + impl ::roslibrust_common::RosMessageType for Float64 { const ROS_TYPE_NAME: &'static str = "std_msgs/Float64"; const MD5SUM: &'static str = "fdb28210bfa9d7c91146260178d9a584"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6509,7 +6509,7 @@ float64 data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Float64MultiArray { + impl ::roslibrust_common::RosMessageType for Float64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Float64MultiArray"; const MD5SUM: &'static str = "4b7d974086d4060e7db4613a7e6c3ba4"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6590,7 +6590,7 @@ uint32 stride # stride of given dimension"#; pub r#stamp: ::roslibrust_codegen::integral_types::Time, pub r#frame_id: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for Header { + impl ::roslibrust_common::RosMessageType for Header { const ROS_TYPE_NAME: &'static str = "std_msgs/Header"; const MD5SUM: &'static str = "5ed6b5dd1ef879ffb9c2ac51bab61a63"; const DEFINITION: &'static str = r#"# Standard metadata for higher-level stamped data types. @@ -6616,7 +6616,7 @@ string frame_id"#; pub struct Int16 { pub r#data: i16, } - impl ::roslibrust_codegen::RosMessageType for Int16 { + impl ::roslibrust_common::RosMessageType for Int16 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int16"; const MD5SUM: &'static str = "8524586e34fbd7cb1c08c5f5f1ca0e57"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6640,7 +6640,7 @@ int16 data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Int16MultiArray { + impl ::roslibrust_common::RosMessageType for Int16MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int16MultiArray"; const MD5SUM: &'static str = "d9338d7f523fcb692fae9d0a0e9f067c"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6720,7 +6720,7 @@ uint32 stride # stride of given dimension"#; pub struct Int32 { pub r#data: i32, } - impl ::roslibrust_codegen::RosMessageType for Int32 { + impl ::roslibrust_common::RosMessageType for Int32 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int32"; const MD5SUM: &'static str = "da5909fbe378aeaf85e547e830cc1bb7"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6744,7 +6744,7 @@ int32 data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Int32MultiArray { + impl ::roslibrust_common::RosMessageType for Int32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int32MultiArray"; const MD5SUM: &'static str = "1d99f79f8b325b44fee908053e9c945b"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6824,7 +6824,7 @@ uint32 stride # stride of given dimension"#; pub struct Int64 { pub r#data: i64, } - impl ::roslibrust_codegen::RosMessageType for Int64 { + impl ::roslibrust_common::RosMessageType for Int64 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int64"; const MD5SUM: &'static str = "34add168574510e6e17f5d23ecc077ef"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6848,7 +6848,7 @@ int64 data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Int64MultiArray { + impl ::roslibrust_common::RosMessageType for Int64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int64MultiArray"; const MD5SUM: &'static str = "54865aa6c65be0448113a2afc6a49270"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6928,7 +6928,7 @@ uint32 stride # stride of given dimension"#; pub struct Int8 { pub r#data: i8, } - impl ::roslibrust_codegen::RosMessageType for Int8 { + impl ::roslibrust_common::RosMessageType for Int8 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int8"; const MD5SUM: &'static str = "27ffa0c9c4b8fb8492252bcad9e5c57b"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -6952,7 +6952,7 @@ int8 data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for Int8MultiArray { + impl ::roslibrust_common::RosMessageType for Int8MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int8MultiArray"; const MD5SUM: &'static str = "d7c1af35a1b4781bbe79e03dd94b7c13"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7034,7 +7034,7 @@ uint32 stride # stride of given dimension"#; pub r#size: u32, pub r#stride: u32, } - impl ::roslibrust_codegen::RosMessageType for MultiArrayDimension { + impl ::roslibrust_common::RosMessageType for MultiArrayDimension { const ROS_TYPE_NAME: &'static str = "std_msgs/MultiArrayDimension"; const MD5SUM: &'static str = "4cd0c83a8683deae40ecdac60e53bfa8"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7060,7 +7060,7 @@ uint32 stride # stride of given dimension"#; pub r#dim: ::std::vec::Vec, pub r#data_offset: u32, } - impl ::roslibrust_codegen::RosMessageType for MultiArrayLayout { + impl ::roslibrust_common::RosMessageType for MultiArrayLayout { const ROS_TYPE_NAME: &'static str = "std_msgs/MultiArrayLayout"; const MD5SUM: &'static str = "0fed2a11c13e11c5571b4e2a995a91a3"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7118,7 +7118,7 @@ uint32 stride # stride of given dimension"#; pub struct String { pub r#data: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for String { + impl ::roslibrust_common::RosMessageType for String { const ROS_TYPE_NAME: &'static str = "std_msgs/String"; const MD5SUM: &'static str = "992ce8a1687cec8c8bd883ec73ca41d1"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7141,7 +7141,7 @@ string data"#; pub struct UInt16 { pub r#data: u16, } - impl ::roslibrust_codegen::RosMessageType for UInt16 { + impl ::roslibrust_common::RosMessageType for UInt16 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt16"; const MD5SUM: &'static str = "1df79edf208b629fe6b81923a544552d"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7165,7 +7165,7 @@ uint16 data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for UInt16MultiArray { + impl ::roslibrust_common::RosMessageType for UInt16MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt16MultiArray"; const MD5SUM: &'static str = "52f264f1c973c4b73790d384c6cb4484"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7245,7 +7245,7 @@ uint32 stride # stride of given dimension"#; pub struct UInt32 { pub r#data: u32, } - impl ::roslibrust_codegen::RosMessageType for UInt32 { + impl ::roslibrust_common::RosMessageType for UInt32 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt32"; const MD5SUM: &'static str = "304a39449588c7f8ce2df6e8001c5fce"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7269,7 +7269,7 @@ uint32 data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for UInt32MultiArray { + impl ::roslibrust_common::RosMessageType for UInt32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt32MultiArray"; const MD5SUM: &'static str = "4d6a180abc9be191b96a7eda6c8a233d"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7349,7 +7349,7 @@ uint32 stride # stride of given dimension"#; pub struct UInt64 { pub r#data: u64, } - impl ::roslibrust_codegen::RosMessageType for UInt64 { + impl ::roslibrust_common::RosMessageType for UInt64 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt64"; const MD5SUM: &'static str = "1b2a79973e8bf53d7b53acb71299cb57"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7373,7 +7373,7 @@ uint64 data"#; pub r#layout: self::MultiArrayLayout, pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for UInt64MultiArray { + impl ::roslibrust_common::RosMessageType for UInt64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt64MultiArray"; const MD5SUM: &'static str = "6088f127afb1d6c72927aa1247e945af"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7453,7 +7453,7 @@ uint32 stride # stride of given dimension"#; pub struct UInt8 { pub r#data: u8, } - impl ::roslibrust_codegen::RosMessageType for UInt8 { + impl ::roslibrust_common::RosMessageType for UInt8 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt8"; const MD5SUM: &'static str = "7c8164229e7d2c17eb95e9231617fdee"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7478,7 +7478,7 @@ uint8 data"#; #[serde(with = "::roslibrust_codegen::serde_bytes")] pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for UInt8MultiArray { + impl ::roslibrust_common::RosMessageType for UInt8MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt8MultiArray"; const MD5SUM: &'static str = "82373f1612381bb6ee473b5cd6f5d89c"; const DEFINITION: &'static str = r#"# This was originally provided as an example message. @@ -7570,7 +7570,7 @@ pub mod std_srvs { )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct EmptyRequest {} - impl ::roslibrust_codegen::RosMessageType for EmptyRequest { + impl ::roslibrust_common::RosMessageType for EmptyRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/EmptyRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -7586,14 +7586,14 @@ pub mod std_srvs { )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct EmptyResponse {} - impl ::roslibrust_codegen::RosMessageType for EmptyResponse { + impl ::roslibrust_common::RosMessageType for EmptyResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/EmptyResponse"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; } #[allow(dead_code)] pub struct Empty {} - impl ::roslibrust_codegen::RosServiceType for Empty { + impl ::roslibrust_common::RosServiceType for Empty { const ROS_SERVICE_NAME: &'static str = "std_srvs/Empty"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; type Request = EmptyRequest; @@ -7612,7 +7612,7 @@ pub mod std_srvs { pub struct SetBoolRequest { pub r#data: bool, } - impl ::roslibrust_codegen::RosMessageType for SetBoolRequest { + impl ::roslibrust_common::RosMessageType for SetBoolRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/SetBoolRequest"; const MD5SUM: &'static str = "8b94c1b53db61fb6aed406028ad6332a"; const DEFINITION: &'static str = r#"bool data # e.g. for hardware enabling / disabling"#; @@ -7631,7 +7631,7 @@ pub mod std_srvs { pub r#success: bool, pub r#message: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for SetBoolResponse { + impl ::roslibrust_common::RosMessageType for SetBoolResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/SetBoolResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; const DEFINITION: &'static str = r#"bool success # indicate successful run of triggered service @@ -7639,7 +7639,7 @@ string message # informational, e.g. for error messages"#; } #[allow(dead_code)] pub struct SetBool {} - impl ::roslibrust_codegen::RosServiceType for SetBool { + impl ::roslibrust_common::RosServiceType for SetBool { const ROS_SERVICE_NAME: &'static str = "std_srvs/SetBool"; const MD5SUM: &'static str = "09fb03525b03e7ea1fd3992bafd87e16"; type Request = SetBoolRequest; @@ -7656,7 +7656,7 @@ string message # informational, e.g. for error messages"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct TriggerRequest {} - impl ::roslibrust_codegen::RosMessageType for TriggerRequest { + impl ::roslibrust_common::RosMessageType for TriggerRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/TriggerRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -7675,7 +7675,7 @@ string message # informational, e.g. for error messages"#; pub r#success: bool, pub r#message: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for TriggerResponse { + impl ::roslibrust_common::RosMessageType for TriggerResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/TriggerResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; const DEFINITION: &'static str = r#"bool success # indicate successful run of triggered service @@ -7683,7 +7683,7 @@ string message # informational, e.g. for error messages"#; } #[allow(dead_code)] pub struct Trigger {} - impl ::roslibrust_codegen::RosServiceType for Trigger { + impl ::roslibrust_common::RosServiceType for Trigger { const ROS_SERVICE_NAME: &'static str = "std_srvs/Trigger"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; type Request = TriggerRequest; @@ -7723,7 +7723,7 @@ pub mod stereo_msgs { pub r#max_disparity: f32, pub r#delta_d: f32, } - impl ::roslibrust_codegen::RosMessageType for DisparityImage { + impl ::roslibrust_common::RosMessageType for DisparityImage { const ROS_TYPE_NAME: &'static str = "stereo_msgs/DisparityImage"; const MD5SUM: &'static str = "cb0de8feef04280238c7b77d74b2beca"; const DEFINITION: &'static str = r#"# Separate header for compatibility with current TimeSynchronizer. @@ -7865,7 +7865,7 @@ pub mod test_msgs { #[default(_code = "[\"hello\", \"world\"].iter().map(|x| x.to_string()).collect()")] pub r#s_vec: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for Defaults { + impl ::roslibrust_common::RosMessageType for Defaults { const ROS_TYPE_NAME: &'static str = "test_msgs/Defaults"; const MD5SUM: &'static str = "43c441dc2b521c313f54affd982b5314"; const DEFINITION: &'static str = r#"# This message is specifically for testing generating of default values @@ -7914,7 +7914,7 @@ pub mod trajectory_msgs { pub r#joint_names: ::std::vec::Vec<::std::string::String>, pub r#points: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for JointTrajectory { + impl ::roslibrust_common::RosMessageType for JointTrajectory { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/JointTrajectory"; const MD5SUM: &'static str = "d63e3b4556d9dbd9f48b5ab4a03f1fee"; const DEFINITION: &'static str = r#"# The header is used to specify the coordinate frame and the reference time for @@ -7985,7 +7985,7 @@ builtin_interfaces/Duration time_from_start"#; pub r#effort: ::std::vec::Vec, pub r#time_from_start: ::roslibrust_codegen::integral_types::Duration, } - impl ::roslibrust_codegen::RosMessageType for JointTrajectoryPoint { + impl ::roslibrust_common::RosMessageType for JointTrajectoryPoint { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/JointTrajectoryPoint"; const MD5SUM: &'static str = "2c812f86aa886c93954e333721749ac5"; const DEFINITION: &'static str = r#"# Each trajectory point specifies either positions[, velocities[, accelerations]] @@ -8030,7 +8030,7 @@ builtin_interfaces/Duration time_from_start"#; pub r#joint_names: ::std::vec::Vec<::std::string::String>, pub r#points: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MultiDOFJointTrajectory { + impl ::roslibrust_common::RosMessageType for MultiDOFJointTrajectory { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/MultiDOFJointTrajectory"; const MD5SUM: &'static str = "d00d14d97bd70c5eb648278240cfb066"; const DEFINITION: &'static str = r#"# The header is used to specify the coordinate frame and the reference time for the trajectory durations @@ -8206,7 +8206,7 @@ float64 z"#; pub r#accelerations: ::std::vec::Vec, pub r#time_from_start: ::roslibrust_codegen::integral_types::Duration, } - impl ::roslibrust_codegen::RosMessageType for MultiDOFJointTrajectoryPoint { + impl ::roslibrust_common::RosMessageType for MultiDOFJointTrajectoryPoint { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/MultiDOFJointTrajectoryPoint"; const MD5SUM: &'static str = "6731945e53cbc0fbc6e93c28f7416a71"; const DEFINITION: &'static str = r#"# Each multi-dof joint can specify a transform (up to 6 DOF). @@ -8321,7 +8321,7 @@ pub mod visualization_msgs { pub r#points: ::std::vec::Vec, pub r#outline_colors: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for ImageMarker { + impl ::roslibrust_common::RosMessageType for ImageMarker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/ImageMarker"; const MD5SUM: &'static str = "829dd5d9ba39b8c3844252ebd8b47b96"; const DEFINITION: &'static str = r#"int32 CIRCLE=0 @@ -8413,7 +8413,7 @@ string frame_id"#; pub r#menu_entries: ::std::vec::Vec, pub r#controls: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarker { + impl ::roslibrust_common::RosMessageType for InteractiveMarker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarker"; const MD5SUM: &'static str = "d71737fa44c5bdefd6bdb4fa9b2b86e5"; const DEFINITION: &'static str = r#"# Time/frame info. @@ -9182,7 +9182,7 @@ float32 v"#; pub r#independent_marker_orientation: bool, pub r#description: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerControl { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerControl { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerControl"; const MD5SUM: &'static str = "7b945e790a2d68f430a6eb79f33bf8df"; const DEFINITION: &'static str = r#"# Represents a control that is to be displayed together with an interactive marker @@ -9592,7 +9592,7 @@ float32 v"#; pub r#mouse_point: geometry_msgs::Point, pub r#mouse_point_valid: bool, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerFeedback { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerFeedback { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerFeedback"; const MD5SUM: &'static str = "880e5141421ed8d30906fad686bc17bd"; const DEFINITION: &'static str = r#"# Time/frame info. @@ -9707,7 +9707,7 @@ string frame_id"#; pub r#seq_num: u64, pub r#markers: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerInit { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerInit { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerInit"; const MD5SUM: &'static str = "5d275694a5cb7ea4627f917a9eb1b4cd"; const DEFINITION: &'static str = r#"# Identifying string. Must be unique in the topic namespace @@ -11206,7 +11206,7 @@ float32 v"#; pub r#pose: geometry_msgs::Pose, pub r#name: ::std::string::String, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerPose { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerPose { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerPose"; const MD5SUM: &'static str = "b88540594a0f8e3fe46c720be41faa03"; const DEFINITION: &'static str = r#"# Time/frame info. @@ -11282,7 +11282,7 @@ string frame_id"#; pub r#poses: ::std::vec::Vec, pub r#erases: ::std::vec::Vec<::std::string::String>, } - impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerUpdate { + impl ::roslibrust_common::RosMessageType for InteractiveMarkerUpdate { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerUpdate"; const MD5SUM: &'static str = "8f52c675c849441ae87da82eaa4d6eb5"; const DEFINITION: &'static str = r#"# Identifying string. Must be unique in the topic namespace @@ -12875,7 +12875,7 @@ float32 v"#; pub r#mesh_file: self::MeshFile, pub r#mesh_use_embedded_materials: bool, } - impl ::roslibrust_codegen::RosMessageType for Marker { + impl ::roslibrust_common::RosMessageType for Marker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/Marker"; const MD5SUM: &'static str = "56c6324983a404ead7a426609371feed"; const DEFINITION: &'static str = r#"# See: @@ -13096,7 +13096,7 @@ float32 v"#; pub struct MarkerArray { pub r#markers: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MarkerArray { + impl ::roslibrust_common::RosMessageType for MarkerArray { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MarkerArray"; const MD5SUM: &'static str = "11e38f15427197858cf46456867167bd"; const DEFINITION: &'static str = r#"Marker[] markers @@ -13410,7 +13410,7 @@ float32 v"#; pub r#command: ::std::string::String, pub r#command_type: u8, } - impl ::roslibrust_codegen::RosMessageType for MenuEntry { + impl ::roslibrust_common::RosMessageType for MenuEntry { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MenuEntry"; const MD5SUM: &'static str = "b90ec63024573de83b57aa93eb39be2d"; const DEFINITION: &'static str = r#"# MenuEntry message. @@ -13489,7 +13489,7 @@ uint8 command_type"#; #[serde(with = "::roslibrust_codegen::serde_bytes")] pub r#data: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for MeshFile { + impl ::roslibrust_common::RosMessageType for MeshFile { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MeshFile"; const MD5SUM: &'static str = "39f264648e441626a1045a7d9ef1ba17"; const DEFINITION: &'static str = r#"# Used to send raw mesh files. @@ -13515,7 +13515,7 @@ uint8[] data"#; pub r#u: f32, pub r#v: f32, } - impl ::roslibrust_codegen::RosMessageType for UVCoordinate { + impl ::roslibrust_common::RosMessageType for UVCoordinate { const ROS_TYPE_NAME: &'static str = "visualization_msgs/UVCoordinate"; const MD5SUM: &'static str = "4f5254e0e12914c461d4b17a0cd07f7f"; const DEFINITION: &'static str = r#"# Location of the pixel as a ratio of the width of a 2D texture. @@ -13534,7 +13534,7 @@ float32 v"#; )] #[serde(crate = "::roslibrust_codegen::serde")] pub struct GetInteractiveMarkersRequest {} - impl ::roslibrust_codegen::RosMessageType for GetInteractiveMarkersRequest { + impl ::roslibrust_common::RosMessageType for GetInteractiveMarkersRequest { const ROS_TYPE_NAME: &'static str = "visualization_msgs/GetInteractiveMarkersRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; const DEFINITION: &'static str = r#""#; @@ -13553,7 +13553,7 @@ float32 v"#; pub r#sequence_number: u64, pub r#markers: ::std::vec::Vec, } - impl ::roslibrust_codegen::RosMessageType for GetInteractiveMarkersResponse { + impl ::roslibrust_common::RosMessageType for GetInteractiveMarkersResponse { const ROS_TYPE_NAME: &'static str = "visualization_msgs/GetInteractiveMarkersResponse"; const MD5SUM: &'static str = "923b76ef2c497d4ff5f83a061d424d3b"; const DEFINITION: &'static str = r#"# Sequence number. @@ -15033,7 +15033,7 @@ float32 v"#; } #[allow(dead_code)] pub struct GetInteractiveMarkers {} - impl ::roslibrust_codegen::RosServiceType for GetInteractiveMarkers { + impl ::roslibrust_common::RosServiceType for GetInteractiveMarkers { const ROS_SERVICE_NAME: &'static str = "visualization_msgs/GetInteractiveMarkers"; const MD5SUM: &'static str = "923b76ef2c497d4ff5f83a061d424d3b"; type Request = GetInteractiveMarkersRequest; diff --git a/roslibrust_zenoh/Cargo.toml b/roslibrust_zenoh/Cargo.toml index 729b2f90..2a8818fc 100644 --- a/roslibrust_zenoh/Cargo.toml +++ b/roslibrust_zenoh/Cargo.toml @@ -22,3 +22,5 @@ log = "0.4" env_logger = "0.11" # Used to generate message types for the examples roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } +# Relied on by generate types in the macro this should be cleaned up +roslibrust_common = { path = "../roslibrust_common" } From 76fa3dc569aaa928f1702dd422f0709008981d9a Mon Sep 17 00:00:00 2001 From: carter Date: Tue, 10 Dec 2024 11:17:23 -0700 Subject: [PATCH 02/14] Fix tests --- Cargo.lock | 2 ++ roslibrust_ros1/Cargo.toml | 7 +++++++ roslibrust_ros1/tests/ros1_native_integration_tests.rs | 8 ++++---- roslibrust_ros1/tests/ros1_xmlrpc.rs | 2 +- 4 files changed, 14 insertions(+), 5 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index da2b0f48..06047ace 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -2686,7 +2686,9 @@ dependencies = [ "log", "regex", "reqwest", + "roslibrust", "roslibrust_codegen", + "roslibrust_codegen_macro", "roslibrust_common", "roslibrust_serde_rosmsg", "serde", diff --git a/roslibrust_ros1/Cargo.toml b/roslibrust_ros1/Cargo.toml index 5693a9df..e10bbd1a 100644 --- a/roslibrust_ros1/Cargo.toml +++ b/roslibrust_ros1/Cargo.toml @@ -28,6 +28,13 @@ byteorder = "1.4" thiserror = "2.0" anyhow = "1.0" +[dev-dependencies] +# Used to provide message types for the examples +# TODO generate a roslibrust_std_msgs crate we can depend on instead of this +roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } +# Used to test topic provider? Maybe move those tests to roslibrust directly? +roslibrust = { path = "../roslibrust"} + [features] # Used for enabling tests that rely on a running ros1 master ros1_test = [] diff --git a/roslibrust_ros1/tests/ros1_native_integration_tests.rs b/roslibrust_ros1/tests/ros1_native_integration_tests.rs index 2e2facfb..1db573d7 100644 --- a/roslibrust_ros1/tests/ros1_native_integration_tests.rs +++ b/roslibrust_ros1/tests/ros1_native_integration_tests.rs @@ -4,7 +4,7 @@ #[cfg(feature = "ros1_test")] mod tests { use log::*; - use roslibrust::ros1::{NodeError, NodeHandle}; + use roslibrust_ros1::{NodeError, NodeHandle}; use tokio::time::timeout; roslibrust_codegen_macro::find_and_generate_ros_messages!( @@ -436,7 +436,7 @@ mod tests { .await .unwrap(); - let master_client = roslibrust::ros1::MasterClient::new( + let master_client = roslibrust_ros1::MasterClient::new( "http://localhost:11311", "NAN", "/test_dropping_publisher_mc", @@ -467,7 +467,7 @@ mod tests { } #[test_log::test(tokio::test)] - #[cfg(all(feature = "ros1_test", feature = "topic_provider"))] + #[cfg(all(feature = "ros1_test"))] async fn topic_provider_publish_functionality_test() { use roslibrust::topic_provider::*; use roslibrust::ClientHandle; @@ -569,7 +569,7 @@ mod tests { .await .unwrap(); - let master_client = roslibrust::ros1::MasterClient::new( + let master_client = roslibrust_ros1::MasterClient::new( "http://localhost:11311", "NAN", "/test_node_cleanup_checker", diff --git a/roslibrust_ros1/tests/ros1_xmlrpc.rs b/roslibrust_ros1/tests/ros1_xmlrpc.rs index f26046ec..4baf0b11 100644 --- a/roslibrust_ros1/tests/ros1_xmlrpc.rs +++ b/roslibrust_ros1/tests/ros1_xmlrpc.rs @@ -1,6 +1,6 @@ #[cfg(feature = "ros1_test")] mod tests { - use roslibrust::ros1::NodeHandle; + use roslibrust_ros1::NodeHandle; use roslibrust_codegen::RosMessageType; use serde::de::DeserializeOwned; use serde_xmlrpc::Value; From 331f2913d7abfda8829bf30c49c9a87aba08f0de Mon Sep 17 00:00:00 2001 From: carter Date: Tue, 10 Dec 2024 11:17:33 -0700 Subject: [PATCH 03/14] Lint --- roslibrust_ros1/tests/ros1_xmlrpc.rs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/roslibrust_ros1/tests/ros1_xmlrpc.rs b/roslibrust_ros1/tests/ros1_xmlrpc.rs index 4baf0b11..10e1ecea 100644 --- a/roslibrust_ros1/tests/ros1_xmlrpc.rs +++ b/roslibrust_ros1/tests/ros1_xmlrpc.rs @@ -1,7 +1,7 @@ #[cfg(feature = "ros1_test")] mod tests { - use roslibrust_ros1::NodeHandle; use roslibrust_codegen::RosMessageType; + use roslibrust_ros1::NodeHandle; use serde::de::DeserializeOwned; use serde_xmlrpc::Value; roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); From cb36a656334a4296518651c3278563eb97a8bbd8 Mon Sep 17 00:00:00 2001 From: carter Date: Tue, 10 Dec 2024 13:38:19 -0700 Subject: [PATCH 04/14] Removed leaky dependency to codegen from ros1 by moving md5sum stuff up to common --- Cargo.lock | 2 +- roslibrust_codegen/src/lib.rs | 770 +----------------------------- roslibrust_common/Cargo.toml | 2 + roslibrust_common/src/lib.rs | 4 + roslibrust_common/src/md5sum.rs | 769 +++++++++++++++++++++++++++++ roslibrust_ros1/Cargo.toml | 2 - roslibrust_ros1/src/node/actor.rs | 2 +- roslibrust_test/Cargo.toml | 3 +- 8 files changed, 780 insertions(+), 774 deletions(-) create mode 100644 roslibrust_common/src/md5sum.rs diff --git a/Cargo.lock b/Cargo.lock index 06047ace..8b7319ee 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -2637,6 +2637,7 @@ name = "roslibrust_common" version = "0.1.0" dependencies = [ "anyhow", + "md5", "serde", "serde_json", "thiserror 2.0.6", @@ -2687,7 +2688,6 @@ dependencies = [ "regex", "reqwest", "roslibrust", - "roslibrust_codegen", "roslibrust_codegen_macro", "roslibrust_common", "roslibrust_serde_rosmsg", diff --git a/roslibrust_codegen/src/lib.rs b/roslibrust_codegen/src/lib.rs index 94d5698c..7eaec728 100644 --- a/roslibrust_codegen/src/lib.rs +++ b/roslibrust_codegen/src/lib.rs @@ -2,7 +2,7 @@ use log::*; use proc_macro2::TokenStream; use quote::quote; use simple_error::{bail, SimpleError as Error}; -use std::collections::{BTreeMap, BTreeSet, HashMap, HashSet, VecDeque}; +use std::collections::{BTreeMap, BTreeSet, VecDeque}; use std::fmt::{Debug, Display}; use std::path::PathBuf; use utils::Package; @@ -30,172 +30,6 @@ pub use smart_default::SmartDefault; // Used in generated code for default value // Export the common types so they can be found under this namespace for backwards compatibility reasons pub use roslibrust_common::*; -/// Taking in a message definition -/// reformat it according to the md5sum algorithm: -/// - Comments removed -/// - Extra whitespace removed -/// - package names of dependencies removed -/// - constants reordered to be at the front -fn clean_msg(msg: &str) -> String { - let mut result_params = vec![]; - let mut result_constants = vec![]; - for line in msg.lines() { - let line = line.trim(); - // Skip comment lines - if line.starts_with('#') { - continue; - } - // Strip comment from the end of the line (if present) - let line = line.split('#').collect::>()[0].trim(); - // Remove any extra whitespace from inside the line - let line = line.split_whitespace().collect::>().join(" "); - // Remove any whitespace on either side of the "=" for constants - let line = line.replace(" = ", "="); - // Skip any empty lines - if line.is_empty() { - continue; - } - // Determine if constant or not - if line.contains('=') { - result_constants.push(line); - } else { - result_params.push(line); - } - } - format!( - "{}\n{}", - result_constants.join("\n"), - result_params.join("\n") - ) - .trim() - .to_string() // Last trim here is lazy, but gets job done -} - -// TODO(lucasw) this deserves a lot of str vs String cleanup -// TODO(lucasw) the msg_type isn't actually needed - Carter (it actually is, or we need to know the package name at least) -/// This function will calculate the md5sum of an expanded message definition. -/// The expanded message definition is the output of `gendeps --cat` see: -/// This definition is typically sent in the connection header of a ros1 topic and is also stored in bag files. -/// This can be used to calculate the md5sum when message definitions aren't available at compile time. -pub fn message_definition_to_md5sum(msg_name: &str, full_def: &str) -> Result { - if full_def.is_empty() { - return Err("empty input definition".into()); - } - - // Split the full definition into sections per message - let sep: &str = - "================================================================================\n"; - let sections = full_def.split(sep).collect::>(); - if sections.is_empty() { - // Carter: this error is impossible, split only gives empty iterator when input string is empty - // which we've already checked for above - return Err("empty sections".into()); - } - - // Split the overall definition into seperate sub-messages sorted by message type (incluidng package name) - let mut sub_messages: HashMap<&str, String> = HashMap::new(); - // Note: the first section doesn't contain the "MSG: " line so we don't need to strip it here - let clean_root = clean_msg(sections[0]); - if clean_root.is_empty() { - return Err("empty cleaned root definition".into()); - } - sub_messages.insert(msg_name, clean_root); - - for section in §ions[1..] { - let line0 = section.lines().next().ok_or("empty section")?; - if !line0.starts_with("MSG: ") { - return Err("bad section {section} -> {line0} doesn't start with 'MSG: '".into()); - } - // TODO(lucasw) the full text definition doesn't always have the full message types with - // the package name, - // but I think this is only when the message type is Header or the package of the message - // being define is the same as the message in the field - // Carter: I agree with this, we found the same when dealing with this previously - let section_type = line0.split_whitespace().collect::>()[1]; - let end_of_first_line = section.find('\n').ok_or("No body found in section")?; - let body = clean_msg(§ion[end_of_first_line + 1..]); - sub_messages.insert(section_type, body); - } - - // TODO MAJOR(carter): I'd like to convert this loop to a recursive function where we pass in the map of hashes - // and update them as we go, this tripple loop is stinky to my eye. - // TODO(carter) we should be able to do this in close to one pass if we iterate the full_def backwards - let mut hashed = HashMap::new(); - let hash = message_definition_to_md5sum_recursive(msg_name, &sub_messages, &mut hashed)?; - - Ok(hash) -} - -/// Calculates the hash of the specified message type by recursively calling itself on all dependencies -/// Uses defs as the list of message definitions available for it (expects them to already be cleaned) -/// Uses hashes as the cache of already calculated hashes so we don't redo work -fn message_definition_to_md5sum_recursive( - msg_type: &str, - defs: &HashMap<&str, String>, - hashes: &mut HashMap, -) -> Result { - let base_types: HashSet = HashSet::from_iter( - [ - "bool", "byte", "int8", "int16", "int32", "int64", "uint8", "uint16", "uint32", - "uint64", "float32", "float64", "time", "duration", "string", - ] - .map(|name| name.to_string()), - ); - let def = defs.get(msg_type).ok_or(simple_error::simple_error!( - "Couldn't find message type: {msg_type}" - ))?; - let pkg_name = msg_type.split('/').collect::>()[0]; - // We'll store the expanded hash definition in this string as we go - let mut field_def = "".to_string(); - for line_raw in def.lines() { - let line_split = line_raw.split_whitespace().collect::>(); - if line_split.len() < 2 { - log::error!("bad line to split '{line_raw}'"); - // TODO(lucasw) or error out - continue; - } - let (raw_field_type, _field_name) = (line_split[0], line_split[1]); - // leave array characters alone, could be [] [C] where C is a constant - let field_type = raw_field_type.split('[').collect::>()[0].to_string(); - - let full_field_type; - let line; - if base_types.contains(&field_type) { - line = line_raw.to_string(); - } else { - // TODO(lucasw) are there other special message types besides header- or is it anything in std_msgs? - if field_type == "Header" { - full_field_type = "std_msgs/Header".to_string(); - } else if !field_type.contains('/') { - full_field_type = format!("{pkg_name}/{field_type}"); - } else { - full_field_type = field_type; - } - - match hashes.get(&full_field_type) { - Some(hash_value) => { - // Hash already exists in cache so we can use it - line = line_raw.replace(raw_field_type, hash_value).to_string(); - } - None => { - // Recurse! To calculate hash of this field type - let hash = - message_definition_to_md5sum_recursive(&full_field_type, defs, hashes)?; - line = line_raw.replace(raw_field_type, &hash).to_string(); - } - } - } - field_def += &format!("{line}\n"); - } - field_def = field_def.trim().to_string(); - let md5sum = md5::compute(field_def.trim_end().as_bytes()); - let md5sum_text = format!("{md5sum:x}"); - // Insert our hash into the cache before we return - hashes.insert(msg_type.to_string(), md5sum_text.clone()); - - Ok(md5sum_text) -} - #[derive(Clone, Debug)] pub struct MessageFile { pub(crate) parsed: ParsedMessageFile, @@ -924,606 +758,4 @@ mod test { assert!(!source.is_empty()); assert!(!paths.is_empty()); } - - /// Confirm md5sum from the connection header message definition matches normally - /// generated checksums - #[test_log::test] - fn msg_def_to_md5() { - { - let def = "byte DEBUG=1\nbyte INFO=2\nbyte WARN=4\nbyte ERROR=8\nbyte FATAL=16\n\ - 2176decaecbce78abc3b96ef049fabed header\n\ - byte level\nstring name\nstring msg\nstring file\nstring function\nuint32 line\nstring[] topics"; - let expected = "acffd30cd6b6de30f120938c17c593fb"; - let md5sum = format!("{:x}", md5::compute(def.trim_end().as_bytes())); - assert_eq!(md5sum, expected, "partially checksumed rosgraph_msgs/Log"); - } - - { - let msg_type = "bad_msgs/Empty"; - let def = ""; - let _md5sum = - crate::message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); - } - - { - let msg_type = "bad_msgs/CommentSpacesOnly"; - let def = - "# message with only comments and whitespace\n# another line comment\n\n \n"; - let _md5sum = - crate::message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); - } - - { - let msg_type = "fake_msgs/MissingSectionMsg"; - let def = "string name\nstring msg\n================================================================================\n# message with only comments and whitespace\n# another line comment\n\n \n"; - let _md5sum = - crate::message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); - } - - { - let msg_type = "bad_msgs/BadLog"; - let def = "## -## Severity level constants -byte DEUG=1 #debug level -byte FATAL=16 #fatal/critical level -## -## Fields -## -Header header -byte level -string name # name of the node -uint32 line # line the message came from -string[] topics # topic names that the node publishes - -================================================================================ -MSG: std_msgs/badHeader -# Standard metadata for higher-level stamped data types. -# -# sequence ID: consecutively increasing ID -uint32 seq -#Two-integer timestamp that is expressed as: -time stamp -"; - let _md5sum = - crate::message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); - } - - { - // TODO(lucasw) not sure if this is an ok message, currently it passes - let expected = "96c44a027b586ee888fe95ac325151ae"; - let msg_type = "fake_msgs/CommentSpacesOnlySection"; - let def = "string name\nstring msg\n================================================================================\nMSG: foo/bar\n# message with only comments and whitespace\n# another line comment\n\n \n"; - let md5sum = crate::message_definition_to_md5sum(msg_type.into(), def.into()).unwrap(); - println!("{msg_type}, computed {md5sum}, expected {expected}"); - assert_eq!(md5sum, expected, "{msg_type}"); - } - - { - let msg_type = "fake_msgs/Garbage"; - let def = r#" -fsdajklf - -== #fdjkl - -MSG: jklfd -# -================================================================================ -f - -vjk -"#; - let _md5sum = - crate::message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); - } - - // TODO(lucasw) it would be nice to pull these out of the real messages, but to avoid - // dependencies just storing expected definition and md5sum - // from roslib.message import get_message_class - // msg = get_message_class("std_msgs/Header") - // md5 = msg._md5sum - // def = msg._full_text - // - - { - let msg_type = "sensor_msgs/CameraInfo"; - // This definition contains double quotes, so representing it with r# and newlines which is nicer - // for limited width text editing anyhow - let def = r#" -# This message defines meta information for a camera. It should be in a -# camera namespace on topic "camera_info" and accompanied by up to five -# image topics named: -# -# image_raw - raw data from the camera driver, possibly Bayer encoded -# image - monochrome, distorted -# image_color - color, distorted -# image_rect - monochrome, rectified -# image_rect_color - color, rectified -# -# The image_pipeline contains packages (image_proc, stereo_image_proc) -# for producing the four processed image topics from image_raw and -# camera_info. The meaning of the camera parameters are described in -# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. -# -# The image_geometry package provides a user-friendly interface to -# common operations using this meta information. If you want to, e.g., -# project a 3d point into image coordinates, we strongly recommend -# using image_geometry. -# -# If the camera is uncalibrated, the matrices D, K, R, P should be left -# zeroed out. In particular, clients may assume that K[0] == 0.0 -# indicates an uncalibrated camera. - -####################################################################### -# Image acquisition info # -####################################################################### - -# Time of image acquisition, camera coordinate frame ID -Header header # Header timestamp should be acquisition time of image - # Header frame_id should be optical frame of camera - # origin of frame should be optical center of camera - # +x should point to the right in the image - # +y should point down in the image - # +z should point into the plane of the image - - -####################################################################### -# Calibration Parameters # -####################################################################### -# These are fixed during camera calibration. Their values will be the # -# same in all messages until the camera is recalibrated. Note that # -# self-calibrating systems may "recalibrate" frequently. # -# # -# The internal parameters can be used to warp a raw (distorted) image # -# to: # -# 1. An undistorted image (requires D and K) # -# 2. A rectified image (requires D, K, R) # -# The projection matrix P projects 3D points into the rectified image.# -####################################################################### - -# The image dimensions with which the camera was calibrated. Normally -# this will be the full camera resolution in pixels. -uint32 height -uint32 width - -# The distortion model used. Supported models are listed in -# sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a -# simple model of radial and tangential distortion - is sufficient. -string distortion_model - -# The distortion parameters, size depending on the distortion model. -# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). -float64[] D - -# Intrinsic camera matrix for the raw (distorted) images. -# [fx 0 cx] -# K = [ 0 fy cy] -# [ 0 0 1] -# Projects 3D points in the camera coordinate frame to 2D pixel -# coordinates using the focal lengths (fx, fy) and principal point -# (cx, cy). -float64[9] K # 3x3 row-major matrix - -# Rectification matrix (stereo cameras only) -# A rotation matrix aligning the camera coordinate system to the ideal -# stereo image plane so that epipolar lines in both stereo images are -# parallel. -float64[9] R # 3x3 row-major matrix - -# Projection/camera matrix -# [fx' 0 cx' Tx] -# P = [ 0 fy' cy' Ty] -# [ 0 0 1 0] -# By convention, this matrix specifies the intrinsic (camera) matrix -# of the processed (rectified) image. That is, the left 3x3 portion -# is the normal camera intrinsic matrix for the rectified image. -# It projects 3D points in the camera coordinate frame to 2D pixel -# coordinates using the focal lengths (fx', fy') and principal point -# (cx', cy') - these may differ from the values in K. -# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will -# also have R = the identity and P[1:3,1:3] = K. -# For a stereo pair, the fourth column [Tx Ty 0]' is related to the -# position of the optical center of the second camera in the first -# camera's frame. We assume Tz = 0 so both cameras are in the same -# stereo image plane. The first camera always has Tx = Ty = 0. For -# the right (second) camera of a horizontal stereo pair, Ty = 0 and -# Tx = -fx' * B, where B is the baseline between the cameras. -# Given a 3D point [X Y Z]', the projection (x, y) of the point onto -# the rectified image is given by: -# [u v w]' = P * [X Y Z 1]' -# x = u / w -# y = v / w -# This holds for both images of a stereo pair. -float64[12] P # 3x4 row-major matrix - - -####################################################################### -# Operational Parameters # -####################################################################### -# These define the image region actually captured by the camera # -# driver. Although they affect the geometry of the output image, they # -# may be changed freely without recalibrating the camera. # -####################################################################### - -# Binning refers here to any camera setting which combines rectangular -# neighborhoods of pixels into larger "super-pixels." It reduces the -# resolution of the output image to -# (width / binning_x) x (height / binning_y). -# The default values binning_x = binning_y = 0 is considered the same -# as binning_x = binning_y = 1 (no subsampling). -uint32 binning_x -uint32 binning_y - -# Region of interest (subwindow of full camera resolution), given in -# full resolution (unbinned) image coordinates. A particular ROI -# always denotes the same window of pixels on the camera sensor, -# regardless of binning settings. -# The default setting of roi (all values 0) is considered the same as -# full resolution (roi.width = width, roi.height = height). -RegionOfInterest roi - -================================================================================ -MSG: std_msgs/Header -# Standard metadata for higher-level stamped data types. -# This is generally used to communicate timestamped data -# in a particular coordinate frame. -# -# sequence ID: consecutively increasing ID -uint32 seq -#Two-integer timestamp that is expressed as: -# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') -# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') -# time-handling sugar is provided by the client library -time stamp -#Frame this data is associated with -string frame_id - -================================================================================ -MSG: sensor_msgs/RegionOfInterest -# This message is used to specify a region of interest within an image. -# -# When used to specify the ROI setting of the camera when the image was -# taken, the height and width fields should either match the height and -# width fields for the associated image; or height = width = 0 -# indicates that the full resolution image was captured. - -uint32 x_offset # Leftmost pixel of the ROI - # (0 if the ROI includes the left edge of the image) -uint32 y_offset # Topmost pixel of the ROI - # (0 if the ROI includes the top edge of the image) -uint32 height # Height of ROI -uint32 width # Width of ROI - -# True if a distinct rectified ROI should be calculated from the "raw" -# ROI in this message. Typically this should be False if the full image -# is captured (ROI not used), and True if a subwindow is captured (ROI -# used). -bool do_rectify - -"#; - let expected = "c9a58c1b0b154e0e6da7578cb991d214"; - let md5sum = crate::message_definition_to_md5sum(msg_type, def.into()).unwrap(); - println!("{msg_type}, computed {md5sum}, expected {expected}"); - assert_eq!(md5sum, expected, "{msg_type}"); - } - - { - let msg_type = "std_msgs/Header"; - let def = "# Standard metadata for higher-level stamped data types.\n# This is generally used to communicate timestamped data \n# in a particular coordinate frame.\n# \n# sequence ID: consecutively increasing ID \nuint32 seq\n#Two-integer timestamp that is expressed as:\n# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n# time-handling sugar is provided by the client library\ntime stamp\n#Frame this data is associated with\nstring frame_id\n"; - let expected = "2176decaecbce78abc3b96ef049fabed"; - let md5sum = crate::message_definition_to_md5sum(msg_type, def.into()).unwrap(); - println!("{msg_type}, computed {md5sum}, expected {expected}"); - assert_eq!(md5sum, expected, "{msg_type}"); - } - - { - let msg_type = "rosgraph_msgs/Log"; - let def = "##\n## Severity level constants\n##\nbyte DEBUG=1 #debug level\nbyte INFO=2 #general level\nbyte WARN=4 #warning level\nbyte ERROR=8 #error level\nbyte FATAL=16 #fatal/critical level\n##\n## Fields\n##\nHeader header\nbyte level\nstring name # name of the node\nstring msg # message \nstring file # file the message came from\nstring function # function the message came from\nuint32 line # line the message came from\nstring[] topics # topic names that the node publishes\n\n================================================================================\nMSG: std_msgs/Header\n# Standard metadata for higher-level stamped data types.\n# This is generally used to communicate timestamped data \n# in a particular coordinate frame.\n# \n# sequence ID: consecutively increasing ID \nuint32 seq\n#Two-integer timestamp that is expressed as:\n# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n# time-handling sugar is provided by the client library\ntime stamp\n#Frame this data is associated with\nstring frame_id\n"; - let expected = "acffd30cd6b6de30f120938c17c593fb"; - let md5sum = crate::message_definition_to_md5sum(msg_type, def.into()).unwrap(); - println!("{msg_type}, computed {md5sum}, expected {expected}"); - assert_eq!(md5sum, expected, "{msg_type}"); - } - - { - let msg_type = "nav_msgs/Odometry"; - let def = "# This represents an estimate of a position and velocity in free space. \n# The pose in this message should be specified in the coordinate frame given by header.frame_id.\n# The twist in this message should be specified in the coordinate frame given by the child_frame_id\nHeader header\nstring child_frame_id\ngeometry_msgs/PoseWithCovariance pose\ngeometry_msgs/TwistWithCovariance twist\n\n================================================================================\nMSG: std_msgs/Header\n# Standard metadata for higher-level stamped data types.\n# This is generally used to communicate timestamped data \n# in a particular coordinate frame.\n# \n# sequence ID: consecutively increasing ID \nuint32 seq\n#Two-integer timestamp that is expressed as:\n# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n# time-handling sugar is provided by the client library\ntime stamp\n#Frame this data is associated with\nstring frame_id\n\n================================================================================\nMSG: geometry_msgs/PoseWithCovariance\n# This represents a pose in free space with uncertainty.\n\nPose pose\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance\n\n================================================================================\nMSG: geometry_msgs/Pose\n# A representation of pose in free space, composed of position and orientation. \nPoint position\nQuaternion orientation\n\n================================================================================\nMSG: geometry_msgs/Point\n# This contains the position of a point in free space\nfloat64 x\nfloat64 y\nfloat64 z\n\n================================================================================\nMSG: geometry_msgs/Quaternion\n# This represents an orientation in free space in quaternion form.\n\nfloat64 x\nfloat64 y\nfloat64 z\nfloat64 w\n\n================================================================================\nMSG: geometry_msgs/TwistWithCovariance\n# This expresses velocity in free space with uncertainty.\n\nTwist twist\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance\n\n================================================================================\nMSG: geometry_msgs/Twist\n# This expresses velocity in free space broken into its linear and angular parts.\nVector3 linear\nVector3 angular\n\n================================================================================\nMSG: geometry_msgs/Vector3\n# This represents a vector in free space. \n# It is only meant to represent a direction. Therefore, it does not\n# make sense to apply a translation to it (e.g., when applying a \n# generic rigid transformation to a Vector3, tf2 will only apply the\n# rotation). If you want your data to be translatable too, use the\n# geometry_msgs/Point message instead.\n\nfloat64 x\nfloat64 y\nfloat64 z"; - let expected = "cd5e73d190d741a2f92e81eda573aca7"; - let md5sum = crate::message_definition_to_md5sum(msg_type, def.into()).unwrap(); - println!("{msg_type}, computed {md5sum}, expected {expected}"); - assert_eq!(md5sum, expected); - } - - { - let msg_type = "tf2_msgs/TFMessage"; - let def = r#" -geometry_msgs/TransformStamped[] transforms - -================================================================================ -MSG: geometry_msgs/TransformStamped -# This expresses a transform from coordinate frame header.frame_id -# to the coordinate frame child_frame_id -# -# This message is mostly used by the -# tf package. -# See its documentation for more information. - -Header header -string child_frame_id # the frame id of the child frame -Transform transform - -================================================================================ -MSG: std_msgs/Header -# Standard metadata for higher-level stamped data types. -# This is generally used to communicate timestamped data -# in a particular coordinate frame. -# -# sequence ID: consecutively increasing ID -uint32 seq -#Two-integer timestamp that is expressed as: -# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') -# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') -# time-handling sugar is provided by the client library -time stamp -#Frame this data is associated with -string frame_id - -================================================================================ -MSG: geometry_msgs/Transform -# This represents the transform between two coordinate frames in free space. - -Vector3 translation -Quaternion rotation - -================================================================================ -MSG: geometry_msgs/Vector3 -# This represents a vector in free space. -# It is only meant to represent a direction. Therefore, it does not -# make sense to apply a translation to it (e.g., when applying a -# generic rigid transformation to a Vector3, tf2 will only apply the -# rotation). If you want your data to be translatable too, use the -# geometry_msgs/Point message instead. - -float64 x -float64 y -float64 z -================================================================================ -MSG: geometry_msgs/Quaternion -# This represents an orientation in free space in quaternion form. - -float64 x -float64 y -float64 z -float64 w - -"#; - let expected = "94810edda583a504dfda3829e70d7eec"; - let md5sum = crate::message_definition_to_md5sum(msg_type, def.into()).unwrap(); - println!("{msg_type}, computed {md5sum}, expected {expected}"); - assert_eq!(md5sum, expected); - } - - { - let msg_type = "vision_msgs/Detection3DArray"; - let def = r#" -# A list of 3D detections, for a multi-object 3D detector. - -Header header - -# A list of the detected proposals. A multi-proposal detector might generate -# this list with many candidate detections generated from a single input. -Detection3D[] detections - -================================================================================ -MSG: std_msgs/Header -# Standard metadata for higher-level stamped data types. -# This is generally used to communicate timestamped data -# in a particular coordinate frame. -# -# sequence ID: consecutively increasing ID -uint32 seq -#Two-integer timestamp that is expressed as: -# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') -# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') -# time-handling sugar is provided by the client library -time stamp -#Frame this data is associated with -string frame_id - -================================================================================ -MSG: vision_msgs/Detection3D -# Defines a 3D detection result. -# -# This extends a basic 3D classification by including position information, -# allowing a classification result for a specific position in an image to -# to be located in the larger image. - -Header header - -# Class probabilities. Does not have to include hypotheses for all possible -# object ids, the scores for any ids not listed are assumed to be 0. -ObjectHypothesisWithPose[] results - -# 3D bounding box surrounding the object. -BoundingBox3D bbox - -# The 3D data that generated these results (i.e. region proposal cropped out of -# the image). This information is not required for all detectors, so it may -# be empty. -sensor_msgs/PointCloud2 source_cloud - -================================================================================ -MSG: vision_msgs/ObjectHypothesisWithPose -# An object hypothesis that contains position information. - -# The unique numeric ID of object detected. To get additional information about -# this ID, such as its human-readable name, listeners should perform a lookup -# in a metadata database. See vision_msgs/VisionInfo.msg for more detail. -int64 id - -# The probability or confidence value of the detected object. By convention, -# this value should lie in the range [0-1]. -float64 score - -# The 6D pose of the object hypothesis. This pose should be -# defined as the pose of some fixed reference point on the object, such a -# the geometric center of the bounding box or the center of mass of the -# object. -# Note that this pose is not stamped; frame information can be defined by -# parent messages. -# Also note that different classes predicted for the same input data may have -# different predicted 6D poses. -geometry_msgs/PoseWithCovariance pose -================================================================================ -MSG: geometry_msgs/PoseWithCovariance -# This represents a pose in free space with uncertainty. - -Pose pose - -# Row-major representation of the 6x6 covariance matrix -# The orientation parameters use a fixed-axis representation. -# In order, the parameters are: -# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) -float64[36] covariance - -================================================================================ -MSG: geometry_msgs/Pose -# A representation of pose in free space, composed of position and orientation. -Point position -Quaternion orientation - -================================================================================ -MSG: geometry_msgs/Point -# This contains the position of a point in free space -float64 x -float64 y -float64 z - -================================================================================ -MSG: geometry_msgs/Quaternion -# This represents an orientation in free space in quaternion form. - -float64 x -float64 y -float64 z -float64 w - -================================================================================ -MSG: vision_msgs/BoundingBox3D -# A 3D bounding box that can be positioned and rotated about its center (6 DOF) -# Dimensions of this box are in meters, and as such, it may be migrated to -# another package, such as geometry_msgs, in the future. - -# The 3D position and orientation of the bounding box center -geometry_msgs/Pose center - -# The size of the bounding box, in meters, surrounding the object's center -# pose. -geometry_msgs/Vector3 size - -================================================================================ -MSG: geometry_msgs/Vector3 -# This represents a vector in free space. -# It is only meant to represent a direction. Therefore, it does not -# make sense to apply a translation to it (e.g., when applying a -# generic rigid transformation to a Vector3, tf2 will only apply the -# rotation). If you want your data to be translatable too, use the -# geometry_msgs/Point message instead. - -float64 x -float64 y -float64 z -================================================================================ -MSG: sensor_msgs/PointCloud2 -# This message holds a collection of N-dimensional points, which may -# contain additional information such as normals, intensity, etc. The -# point data is stored as a binary blob, its layout described by the -# contents of the "fields" array. - -# The point cloud data may be organized 2d (image-like) or 1d -# (unordered). Point clouds organized as 2d images may be produced by -# camera depth sensors such as stereo or time-of-flight. - -# Time of sensor data acquisition, and the coordinate frame ID (for 3d -# points). -Header header - -# 2D structure of the point cloud. If the cloud is unordered, height is -# 1 and width is the length of the point cloud. -uint32 height -uint32 width - -# Describes the channels and their layout in the binary data blob. -PointField[] fields - -bool is_bigendian # Is this data bigendian? -uint32 point_step # Length of a point in bytes -uint32 row_step # Length of a row in bytes -uint8[] data # Actual point data, size is (row_step*height) - -bool is_dense # True if there are no invalid points - -================================================================================ -MSG: sensor_msgs/PointField -# This message holds the description of one point entry in the -# PointCloud2 message format. -uint8 INT8 = 1 -uint8 UINT8 = 2 -uint8 INT16 = 3 -uint8 UINT16 = 4 -uint8 INT32 = 5 -uint8 UINT32 = 6 -uint8 FLOAT32 = 7 -uint8 FLOAT64 = 8 - -string name # Name of field -uint32 offset # Offset from start of point struct -uint8 datatype # Datatype enumeration, see above -uint32 count # How many elements in the field - -"#; - let expected = "05c51d9aea1fb4cfdc8effb94f197b6f"; - let md5sum = crate::message_definition_to_md5sum(msg_type, def.into()).unwrap(); - println!("{msg_type}, computed {md5sum}, expected {expected}"); - assert_eq!(md5sum, expected, "{msg_type}"); - } - } - - // Basic test of clean_msg function - #[test] - fn clean_msg_test() { - let test_msg = r#" -# This message holds the description of one point entry in the -# PointCloud2 message format. -uint8 INT8 = 1 -uint8 UINT8 = 2 -uint8 INT16 = 3 -uint8 UINT16 = 4 -uint8 INT32 = 5 -uint8 UINT32 = 6 # Random Comment - -string name # Name of field -uint32 offset # Offset from start of point struct -uint8 datatype # Datatype enumeration, see above -uint32 count # How many elements in the field - - -uint8 FLOAT32 = 7 -uint8 FLOAT64 = 8 - -"#; - let result = crate::clean_msg(test_msg); - let expected = r#"uint8 INT8=1 -uint8 UINT8=2 -uint8 INT16=3 -uint8 UINT16=4 -uint8 INT32=5 -uint8 UINT32=6 -uint8 FLOAT32=7 -uint8 FLOAT64=8 -string name -uint32 offset -uint8 datatype -uint32 count"#; - assert_eq!(result, expected); - } } diff --git a/roslibrust_common/Cargo.toml b/roslibrust_common/Cargo.toml index 89c461ca..cb339b2f 100644 --- a/roslibrust_common/Cargo.toml +++ b/roslibrust_common/Cargo.toml @@ -7,6 +7,8 @@ edition = "2021" thiserror = "2.0" anyhow = "1.0" serde = { version = "1.0", features = ["derive"] } +# Used for md5sum calculation +md5 = "0.7" # THESE DEPENDENCIES WILL BE REMOVED # We're currently leaking these error types in the "generic error type" diff --git a/roslibrust_common/src/lib.rs b/roslibrust_common/src/lib.rs index 4a3dc7ab..ded48f48 100644 --- a/roslibrust_common/src/lib.rs +++ b/roslibrust_common/src/lib.rs @@ -105,3 +105,7 @@ impl RosMessageType for ShapeShifter { const MD5SUM: &'static str = "*"; const DEFINITION: &'static str = ""; } + +/// Contains functions for calculating md5sums of message definitions +/// These functions are needed both in roslibrust_ros1 and roslibrust_codegen so they're in this crate +pub mod md5sum; diff --git a/roslibrust_common/src/md5sum.rs b/roslibrust_common/src/md5sum.rs new file mode 100644 index 00000000..a7fdd4dd --- /dev/null +++ b/roslibrust_common/src/md5sum.rs @@ -0,0 +1,769 @@ +use anyhow::{anyhow, bail, Error}; +use std::collections::{HashMap, HashSet}; + +// TODO(lucasw) this deserves a lot of str vs String cleanup +/// This function will calculate the md5sum of an expanded message definition. +/// The expanded message definition is the output of `gendeps --cat` see: +/// This definition is typically sent in the connection header of a ros1 topic and is also stored in bag files. +/// This can be used to calculate the md5sum when message definitions aren't available at compile time. +pub fn message_definition_to_md5sum(msg_name: &str, full_def: &str) -> Result { + if full_def.is_empty() { + bail!("empty input definition"); + } + + // Split the full definition into sections per message + let sep: &str = + "================================================================================\n"; + let sections = full_def.split(sep).collect::>(); + if sections.is_empty() { + // Carter: this error is impossible, split only gives empty iterator when input string is empty + // which we've already checked for above + bail!("empty sections"); + } + + // Split the overall definition into separate sub-messages sorted by message type (including package name) + let mut sub_messages: HashMap<&str, String> = HashMap::new(); + // Note: the first section doesn't contain the "MSG: " line so we don't need to strip it here + let clean_root = clean_msg(sections[0]); + if clean_root.is_empty() { + bail!("empty cleaned root definition"); + } + sub_messages.insert(msg_name, clean_root); + + for section in §ions[1..] { + let line0 = section.lines().next().ok_or(anyhow!("empty section"))?; + if !line0.starts_with("MSG: ") { + bail!("bad section {section} -> {line0} doesn't start with 'MSG: '"); + } + // TODO(lucasw) the full text definition doesn't always have the full message types with + // the package name, + // but I think this is only when the message type is Header or the package of the message + // being define is the same as the message in the field + // Carter: I agree with this, we found the same when dealing with this previously + let section_type = line0.split_whitespace().collect::>()[1]; + let end_of_first_line = section + .find('\n') + .ok_or(anyhow!("No body found in section"))?; + let body = clean_msg(§ion[end_of_first_line + 1..]); + sub_messages.insert(section_type, body); + } + + // TODO MAJOR(carter): I'd like to convert this loop to a recursive function where we pass in the map of hashes + // and update them as we go, this tripple loop is stinky to my eye. + // TODO(carter) we should be able to do this in close to one pass if we iterate the full_def backwards + let mut hashed = HashMap::new(); + let hash = message_definition_to_md5sum_recursive(msg_name, &sub_messages, &mut hashed)?; + + Ok(hash) +} + +/// Calculates the hash of the specified message type by recursively calling itself on all dependencies +/// Uses defs as the list of message definitions available for it (expects them to already be cleaned) +/// Uses hashes as the cache of already calculated hashes so we don't redo work +fn message_definition_to_md5sum_recursive( + msg_type: &str, + defs: &HashMap<&str, String>, + hashes: &mut HashMap, +) -> Result { + let base_types: HashSet = HashSet::from_iter( + [ + "bool", "byte", "int8", "int16", "int32", "int64", "uint8", "uint16", "uint32", + "uint64", "float32", "float64", "time", "duration", "string", + ] + .map(|name| name.to_string()), + ); + let def = defs + .get(msg_type) + .ok_or(anyhow!("Couldn't find message type: {msg_type}"))?; + let pkg_name = msg_type.split('/').collect::>()[0]; + // We'll store the expanded hash definition in this string as we go + let mut field_def = "".to_string(); + for line_raw in def.lines() { + let line_split = line_raw.split_whitespace().collect::>(); + if line_split.len() < 2 { + bail!("bad line to split '{line_raw}'"); + } + let (raw_field_type, _field_name) = (line_split[0], line_split[1]); + // leave array characters alone, could be [] [C] where C is a constant + let field_type = raw_field_type.split('[').collect::>()[0].to_string(); + + let full_field_type; + let line; + if base_types.contains(&field_type) { + line = line_raw.to_string(); + } else { + // TODO(lucasw) are there other special message types besides header- or is it anything in std_msgs? + if field_type == "Header" { + full_field_type = "std_msgs/Header".to_string(); + } else if !field_type.contains('/') { + full_field_type = format!("{pkg_name}/{field_type}"); + } else { + full_field_type = field_type; + } + + match hashes.get(&full_field_type) { + Some(hash_value) => { + // Hash already exists in cache so we can use it + line = line_raw.replace(raw_field_type, hash_value).to_string(); + } + None => { + // Recurse! To calculate hash of this field type + let hash = + message_definition_to_md5sum_recursive(&full_field_type, defs, hashes)?; + line = line_raw.replace(raw_field_type, &hash).to_string(); + } + } + } + field_def += &format!("{line}\n"); + } + field_def = field_def.trim().to_string(); + let md5sum = md5::compute(field_def.trim_end().as_bytes()); + let md5sum_text = format!("{md5sum:x}"); + // Insert our hash into the cache before we return + hashes.insert(msg_type.to_string(), md5sum_text.clone()); + + Ok(md5sum_text) +} + +/// Taking in a message definition +/// reformat it according to the md5sum algorithm: +/// - Comments removed +/// - Extra whitespace removed +/// - package names of dependencies removed +/// - constants reordered to be at the front +fn clean_msg(msg: &str) -> String { + let mut result_params = vec![]; + let mut result_constants = vec![]; + for line in msg.lines() { + let line = line.trim(); + // Skip comment lines + if line.starts_with('#') { + continue; + } + // Strip comment from the end of the line (if present) + let line = line.split('#').collect::>()[0].trim(); + // Remove any extra whitespace from inside the line + let line = line.split_whitespace().collect::>().join(" "); + // Remove any whitespace on either side of the "=" for constants + let line = line.replace(" = ", "="); + // Skip any empty lines + if line.is_empty() { + continue; + } + // Determine if constant or not + if line.contains('=') { + result_constants.push(line); + } else { + result_params.push(line); + } + } + format!( + "{}\n{}", + result_constants.join("\n"), + result_params.join("\n") + ) + .trim() + .to_string() // Last trim here is lazy, but gets job done +} + +#[cfg(test)] +mod tests { + use super::*; + + /// Confirm md5sum from the connection header message definition matches normally + /// generated checksums + #[test] + fn msg_def_to_md5() { + { + let def = "byte DEBUG=1\nbyte INFO=2\nbyte WARN=4\nbyte ERROR=8\nbyte FATAL=16\n\ + 2176decaecbce78abc3b96ef049fabed header\n\ + byte level\nstring name\nstring msg\nstring file\nstring function\nuint32 line\nstring[] topics"; + let expected = "acffd30cd6b6de30f120938c17c593fb"; + let md5sum = format!("{:x}", md5::compute(def.trim_end().as_bytes())); + assert_eq!(md5sum, expected, "partially checksumed rosgraph_msgs/Log"); + } + + { + let msg_type = "bad_msgs/Empty"; + let def = ""; + let _md5sum = message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); + } + + { + let msg_type = "bad_msgs/CommentSpacesOnly"; + let def = + "# message with only comments and whitespace\n# another line comment\n\n \n"; + let _md5sum = message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); + } + + { + let msg_type = "fake_msgs/MissingSectionMsg"; + let def = "string name\nstring msg\n================================================================================\n# message with only comments and whitespace\n# another line comment\n\n \n"; + let _md5sum = message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); + } + + { + let msg_type = "bad_msgs/BadLog"; + let def = "## +## Severity level constants +byte DEUG=1 #debug level +byte FATAL=16 #fatal/critical level +## +## Fields +## +Header header +byte level +string name # name of the node +uint32 line # line the message came from +string[] topics # topic names that the node publishes + +================================================================================ +MSG: std_msgs/badHeader +# Standard metadata for higher-level stamped data types. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +time stamp +"; + let _md5sum = message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); + } + + { + // TODO(lucasw) not sure if this is an ok message, currently it passes + let expected = "96c44a027b586ee888fe95ac325151ae"; + let msg_type = "fake_msgs/CommentSpacesOnlySection"; + let def = "string name\nstring msg\n================================================================================\nMSG: foo/bar\n# message with only comments and whitespace\n# another line comment\n\n \n"; + let md5sum = message_definition_to_md5sum(msg_type.into(), def.into()).unwrap(); + println!("{msg_type}, computed {md5sum}, expected {expected}"); + assert_eq!(md5sum, expected, "{msg_type}"); + } + + { + let msg_type = "fake_msgs/Garbage"; + let def = r#" +fsdajklf + +== #fdjkl + +MSG: jklfd +# +================================================================================ +f + +vjk +"#; + let _md5sum = message_definition_to_md5sum(msg_type.into(), def.into()).unwrap_err(); + } + + // TODO(lucasw) it would be nice to pull these out of the real messages, but to avoid + // dependencies just storing expected definition and md5sum + // from roslib.message import get_message_class + // msg = get_message_class("std_msgs/Header") + // md5 = msg._md5sum + // def = msg._full_text + // + + { + let msg_type = "sensor_msgs/CameraInfo"; + // This definition contains double quotes, so representing it with r# and newlines which is nicer + // for limited width text editing anyhow + let def = r#" +# This message defines meta information for a camera. It should be in a +# camera namespace on topic "camera_info" and accompanied by up to five +# image topics named: +# +# image_raw - raw data from the camera driver, possibly Bayer encoded +# image - monochrome, distorted +# image_color - color, distorted +# image_rect - monochrome, rectified +# image_rect_color - color, rectified +# +# The image_pipeline contains packages (image_proc, stereo_image_proc) +# for producing the four processed image topics from image_raw and +# camera_info. The meaning of the camera parameters are described in +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. +# +# The image_geometry package provides a user-friendly interface to +# common operations using this meta information. If you want to, e.g., +# project a 3d point into image coordinates, we strongly recommend +# using image_geometry. +# +# If the camera is uncalibrated, the matrices D, K, R, P should be left +# zeroed out. In particular, clients may assume that K[0] == 0.0 +# indicates an uncalibrated camera. + +####################################################################### +# Image acquisition info # +####################################################################### + +# Time of image acquisition, camera coordinate frame ID +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into the plane of the image + + +####################################################################### +# Calibration Parameters # +####################################################################### +# These are fixed during camera calibration. Their values will be the # +# same in all messages until the camera is recalibrated. Note that # +# self-calibrating systems may "recalibrate" frequently. # +# # +# The internal parameters can be used to warp a raw (distorted) image # +# to: # +# 1. An undistorted image (requires D and K) # +# 2. A rectified image (requires D, K, R) # +# The projection matrix P projects 3D points into the rectified image.# +####################################################################### + +# The image dimensions with which the camera was calibrated. Normally +# this will be the full camera resolution in pixels. +uint32 height +uint32 width + +# The distortion model used. Supported models are listed in +# sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a +# simple model of radial and tangential distortion - is sufficient. +string distortion_model + +# The distortion parameters, size depending on the distortion model. +# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). +float64[] D + +# Intrinsic camera matrix for the raw (distorted) images. +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy). +float64[9] K # 3x3 row-major matrix + +# Rectification matrix (stereo cameras only) +# A rotation matrix aligning the camera coordinate system to the ideal +# stereo image plane so that epipolar lines in both stereo images are +# parallel. +float64[9] R # 3x3 row-major matrix + +# Projection/camera matrix +# [fx' 0 cx' Tx] +# P = [ 0 fy' cy' Ty] +# [ 0 0 1 0] +# By convention, this matrix specifies the intrinsic (camera) matrix +# of the processed (rectified) image. That is, the left 3x3 portion +# is the normal camera intrinsic matrix for the rectified image. +# It projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx', fy') and principal point +# (cx', cy') - these may differ from the values in K. +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will +# also have R = the identity and P[1:3,1:3] = K. +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the +# position of the optical center of the second camera in the first +# camera's frame. We assume Tz = 0 so both cameras are in the same +# stereo image plane. The first camera always has Tx = Ty = 0. For +# the right (second) camera of a horizontal stereo pair, Ty = 0 and +# Tx = -fx' * B, where B is the baseline between the cameras. +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto +# the rectified image is given by: +# [u v w]' = P * [X Y Z 1]' +# x = u / w +# y = v / w +# This holds for both images of a stereo pair. +float64[12] P # 3x4 row-major matrix + + +####################################################################### +# Operational Parameters # +####################################################################### +# These define the image region actually captured by the camera # +# driver. Although they affect the geometry of the output image, they # +# may be changed freely without recalibrating the camera. # +####################################################################### + +# Binning refers here to any camera setting which combines rectangular +# neighborhoods of pixels into larger "super-pixels." It reduces the +# resolution of the output image to +# (width / binning_x) x (height / binning_y). +# The default values binning_x = binning_y = 0 is considered the same +# as binning_x = binning_y = 1 (no subsampling). +uint32 binning_x +uint32 binning_y + +# Region of interest (subwindow of full camera resolution), given in +# full resolution (unbinned) image coordinates. A particular ROI +# always denotes the same window of pixels on the camera sensor, +# regardless of binning settings. +# The default setting of roi (all values 0) is considered the same as +# full resolution (roi.width = width, roi.height = height). +RegionOfInterest roi + +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id + +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify + +"#; + let expected = "c9a58c1b0b154e0e6da7578cb991d214"; + let md5sum = message_definition_to_md5sum(msg_type, def.into()).unwrap(); + println!("{msg_type}, computed {md5sum}, expected {expected}"); + assert_eq!(md5sum, expected, "{msg_type}"); + } + + { + let msg_type = "std_msgs/Header"; + let def = "# Standard metadata for higher-level stamped data types.\n# This is generally used to communicate timestamped data \n# in a particular coordinate frame.\n# \n# sequence ID: consecutively increasing ID \nuint32 seq\n#Two-integer timestamp that is expressed as:\n# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n# time-handling sugar is provided by the client library\ntime stamp\n#Frame this data is associated with\nstring frame_id\n"; + let expected = "2176decaecbce78abc3b96ef049fabed"; + let md5sum = message_definition_to_md5sum(msg_type, def.into()).unwrap(); + println!("{msg_type}, computed {md5sum}, expected {expected}"); + assert_eq!(md5sum, expected, "{msg_type}"); + } + + { + let msg_type = "rosgraph_msgs/Log"; + let def = "##\n## Severity level constants\n##\nbyte DEBUG=1 #debug level\nbyte INFO=2 #general level\nbyte WARN=4 #warning level\nbyte ERROR=8 #error level\nbyte FATAL=16 #fatal/critical level\n##\n## Fields\n##\nHeader header\nbyte level\nstring name # name of the node\nstring msg # message \nstring file # file the message came from\nstring function # function the message came from\nuint32 line # line the message came from\nstring[] topics # topic names that the node publishes\n\n================================================================================\nMSG: std_msgs/Header\n# Standard metadata for higher-level stamped data types.\n# This is generally used to communicate timestamped data \n# in a particular coordinate frame.\n# \n# sequence ID: consecutively increasing ID \nuint32 seq\n#Two-integer timestamp that is expressed as:\n# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n# time-handling sugar is provided by the client library\ntime stamp\n#Frame this data is associated with\nstring frame_id\n"; + let expected = "acffd30cd6b6de30f120938c17c593fb"; + let md5sum = message_definition_to_md5sum(msg_type, def.into()).unwrap(); + println!("{msg_type}, computed {md5sum}, expected {expected}"); + assert_eq!(md5sum, expected, "{msg_type}"); + } + + { + let msg_type = "nav_msgs/Odometry"; + let def = "# This represents an estimate of a position and velocity in free space. \n# The pose in this message should be specified in the coordinate frame given by header.frame_id.\n# The twist in this message should be specified in the coordinate frame given by the child_frame_id\nHeader header\nstring child_frame_id\ngeometry_msgs/PoseWithCovariance pose\ngeometry_msgs/TwistWithCovariance twist\n\n================================================================================\nMSG: std_msgs/Header\n# Standard metadata for higher-level stamped data types.\n# This is generally used to communicate timestamped data \n# in a particular coordinate frame.\n# \n# sequence ID: consecutively increasing ID \nuint32 seq\n#Two-integer timestamp that is expressed as:\n# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n# time-handling sugar is provided by the client library\ntime stamp\n#Frame this data is associated with\nstring frame_id\n\n================================================================================\nMSG: geometry_msgs/PoseWithCovariance\n# This represents a pose in free space with uncertainty.\n\nPose pose\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance\n\n================================================================================\nMSG: geometry_msgs/Pose\n# A representation of pose in free space, composed of position and orientation. \nPoint position\nQuaternion orientation\n\n================================================================================\nMSG: geometry_msgs/Point\n# This contains the position of a point in free space\nfloat64 x\nfloat64 y\nfloat64 z\n\n================================================================================\nMSG: geometry_msgs/Quaternion\n# This represents an orientation in free space in quaternion form.\n\nfloat64 x\nfloat64 y\nfloat64 z\nfloat64 w\n\n================================================================================\nMSG: geometry_msgs/TwistWithCovariance\n# This expresses velocity in free space with uncertainty.\n\nTwist twist\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance\n\n================================================================================\nMSG: geometry_msgs/Twist\n# This expresses velocity in free space broken into its linear and angular parts.\nVector3 linear\nVector3 angular\n\n================================================================================\nMSG: geometry_msgs/Vector3\n# This represents a vector in free space. \n# It is only meant to represent a direction. Therefore, it does not\n# make sense to apply a translation to it (e.g., when applying a \n# generic rigid transformation to a Vector3, tf2 will only apply the\n# rotation). If you want your data to be translatable too, use the\n# geometry_msgs/Point message instead.\n\nfloat64 x\nfloat64 y\nfloat64 z"; + let expected = "cd5e73d190d741a2f92e81eda573aca7"; + let md5sum = message_definition_to_md5sum(msg_type, def.into()).unwrap(); + println!("{msg_type}, computed {md5sum}, expected {expected}"); + assert_eq!(md5sum, expected); + } + + { + let msg_type = "tf2_msgs/TFMessage"; + let def = r#" +geometry_msgs/TransformStamped[] transforms + +================================================================================ +MSG: geometry_msgs/TransformStamped +# This expresses a transform from coordinate frame header.frame_id +# to the coordinate frame child_frame_id +# +# This message is mostly used by the +# tf package. +# See its documentation for more information. + +Header header +string child_frame_id # the frame id of the child frame +Transform transform + +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id + +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation + +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w + +"#; + let expected = "94810edda583a504dfda3829e70d7eec"; + let md5sum = message_definition_to_md5sum(msg_type, def.into()).unwrap(); + println!("{msg_type}, computed {md5sum}, expected {expected}"); + assert_eq!(md5sum, expected); + } + + { + let msg_type = "vision_msgs/Detection3DArray"; + let def = r#" +# A list of 3D detections, for a multi-object 3D detector. + +Header header + +# A list of the detected proposals. A multi-proposal detector might generate +# this list with many candidate detections generated from a single input. +Detection3D[] detections + +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id + +================================================================================ +MSG: vision_msgs/Detection3D +# Defines a 3D detection result. +# +# This extends a basic 3D classification by including position information, +# allowing a classification result for a specific position in an image to +# to be located in the larger image. + +Header header + +# Class probabilities. Does not have to include hypotheses for all possible +# object ids, the scores for any ids not listed are assumed to be 0. +ObjectHypothesisWithPose[] results + +# 3D bounding box surrounding the object. +BoundingBox3D bbox + +# The 3D data that generated these results (i.e. region proposal cropped out of +# the image). This information is not required for all detectors, so it may +# be empty. +sensor_msgs/PointCloud2 source_cloud + +================================================================================ +MSG: vision_msgs/ObjectHypothesisWithPose +# An object hypothesis that contains position information. + +# The unique numeric ID of object detected. To get additional information about +# this ID, such as its human-readable name, listeners should perform a lookup +# in a metadata database. See vision_msgs/VisionInfo.msg for more detail. +int64 id + +# The probability or confidence value of the detected object. By convention, +# this value should lie in the range [0-1]. +float64 score + +# The 6D pose of the object hypothesis. This pose should be +# defined as the pose of some fixed reference point on the object, such a +# the geometric center of the bounding box or the center of mass of the +# object. +# Note that this pose is not stamped; frame information can be defined by +# parent messages. +# Also note that different classes predicted for the same input data may have +# different predicted 6D poses. +geometry_msgs/PoseWithCovariance pose +================================================================================ +MSG: geometry_msgs/PoseWithCovariance +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance + +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation + +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z + +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w + +================================================================================ +MSG: vision_msgs/BoundingBox3D +# A 3D bounding box that can be positioned and rotated about its center (6 DOF) +# Dimensions of this box are in meters, and as such, it may be migrated to +# another package, such as geometry_msgs, in the future. + +# The 3D position and orientation of the bounding box center +geometry_msgs/Pose center + +# The size of the bounding box, in meters, surrounding the object's center +# pose. +geometry_msgs/Vector3 size + +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/PointCloud2 +# This message holds a collection of N-dimensional points, which may +# contain additional information such as normals, intensity, etc. The +# point data is stored as a binary blob, its layout described by the +# contents of the "fields" array. + +# The point cloud data may be organized 2d (image-like) or 1d +# (unordered). Point clouds organized as 2d images may be produced by +# camera depth sensors such as stereo or time-of-flight. + +# Time of sensor data acquisition, and the coordinate frame ID (for 3d +# points). +Header header + +# 2D structure of the point cloud. If the cloud is unordered, height is +# 1 and width is the length of the point cloud. +uint32 height +uint32 width + +# Describes the channels and their layout in the binary data blob. +PointField[] fields + +bool is_bigendian # Is this data bigendian? +uint32 point_step # Length of a point in bytes +uint32 row_step # Length of a row in bytes +uint8[] data # Actual point data, size is (row_step*height) + +bool is_dense # True if there are no invalid points + +================================================================================ +MSG: sensor_msgs/PointField +# This message holds the description of one point entry in the +# PointCloud2 message format. +uint8 INT8 = 1 +uint8 UINT8 = 2 +uint8 INT16 = 3 +uint8 UINT16 = 4 +uint8 INT32 = 5 +uint8 UINT32 = 6 +uint8 FLOAT32 = 7 +uint8 FLOAT64 = 8 + +string name # Name of field +uint32 offset # Offset from start of point struct +uint8 datatype # Datatype enumeration, see above +uint32 count # How many elements in the field + +"#; + let expected = "05c51d9aea1fb4cfdc8effb94f197b6f"; + let md5sum = message_definition_to_md5sum(msg_type, def.into()).unwrap(); + println!("{msg_type}, computed {md5sum}, expected {expected}"); + assert_eq!(md5sum, expected, "{msg_type}"); + } + } + + // Basic test of clean_msg function + #[test] + fn clean_msg_test() { + let test_msg = r#" +# This message holds the description of one point entry in the +# PointCloud2 message format. +uint8 INT8 = 1 +uint8 UINT8 = 2 +uint8 INT16 = 3 +uint8 UINT16 = 4 +uint8 INT32 = 5 +uint8 UINT32 = 6 # Random Comment + +string name # Name of field +uint32 offset # Offset from start of point struct +uint8 datatype # Datatype enumeration, see above +uint32 count # How many elements in the field + + +uint8 FLOAT32 = 7 +uint8 FLOAT64 = 8 + +"#; + let result = clean_msg(test_msg); + let expected = r#"uint8 INT8=1 +uint8 UINT8=2 +uint8 INT16=3 +uint8 UINT16=4 +uint8 INT32=5 +uint8 UINT32=6 +uint8 FLOAT32=7 +uint8 FLOAT64=8 +string name +uint32 offset +uint8 datatype +uint32 count"#; + assert_eq!(result, expected); + } +} diff --git a/roslibrust_ros1/Cargo.toml b/roslibrust_ros1/Cargo.toml index e10bbd1a..6855d570 100644 --- a/roslibrust_ros1/Cargo.toml +++ b/roslibrust_ros1/Cargo.toml @@ -6,8 +6,6 @@ edition = "2021" [dependencies] # Provides common types and traits used throughout the roslibrust ecosystem. roslibrust_common = { path = "../roslibrust_common" } -# TODO we'd like to remove this dependency? Don't love these are crosslinked -roslibrust_codegen = { path = "../roslibrust_codegen" } # Should probably become workspace members: tokio = { version = "1.41", features = ["rt-multi-thread", "sync", "macros"] } diff --git a/roslibrust_ros1/src/node/actor.rs b/roslibrust_ros1/src/node/actor.rs index f009855a..1c2a9104 100644 --- a/roslibrust_ros1/src/node/actor.rs +++ b/roslibrust_ros1/src/node/actor.rs @@ -194,7 +194,7 @@ impl NodeServerHandle { let md5sum; let md5sum_res = - roslibrust_codegen::message_definition_to_md5sum(topic_type, msg_definition); + roslibrust_common::md5sum::message_definition_to_md5sum(topic_type, msg_definition); match md5sum_res { // TODO(lucasw) make a new error type for this? Err(err) => { diff --git a/roslibrust_test/Cargo.toml b/roslibrust_test/Cargo.toml index 7f2a5943..e0b2ad8e 100644 --- a/roslibrust_test/Cargo.toml +++ b/roslibrust_test/Cargo.toml @@ -7,7 +7,8 @@ edition = "2021" env_logger = "0.10" roslibrust = { path = "../roslibrust", features = ["ros1"] } roslibrust_common = { path = "../roslibrust_common" } -# TODO this shouldn't need to be here! +# This crate does directly invoke codegen and does need to rely on it directly +# We can fix this by moving the generated types into a roslibrust_ros1_types crate roslibrust_codegen = { path = "../roslibrust_codegen" } lazy_static = "1.4" tokio = { version = "1.20", features = ["net", "sync"] } From 10792e4502a156c09bc515ccdbe099c9497ab322 Mon Sep 17 00:00:00 2001 From: carter Date: Tue, 10 Dec 2024 14:58:12 -0700 Subject: [PATCH 05/14] Moving topic provider up to common --- Cargo.lock | 3 +- roslibrust/src/lib.rs | 7 - roslibrust/src/rosbridge/mod.rs | 90 +++++- roslibrust/src/topic_provider.rs | 281 ------------------ roslibrust_common/Cargo.toml | 4 + roslibrust_common/src/lib.rs | 5 + roslibrust_common/src/topic_provider.rs | 87 ++++++ roslibrust_ros1/Cargo.toml | 4 +- roslibrust_ros1/src/lib.rs | 112 +++++++ .../tests/ros1_native_integration_tests.rs | 5 +- roslibrust_zenoh/Cargo.toml | 10 +- roslibrust_zenoh/examples/publisher.rs | 12 +- roslibrust_zenoh/examples/service_call.rs | 12 +- roslibrust_zenoh/examples/service_server.rs | 4 +- roslibrust_zenoh/examples/subscriber.rs | 12 +- roslibrust_zenoh/src/lib.rs | 11 +- 16 files changed, 329 insertions(+), 330 deletions(-) delete mode 100644 roslibrust/src/topic_provider.rs create mode 100644 roslibrust_common/src/topic_provider.rs diff --git a/Cargo.lock b/Cargo.lock index 8b7319ee..70894554 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -2637,6 +2637,7 @@ name = "roslibrust_common" version = "0.1.0" dependencies = [ "anyhow", + "futures", "md5", "serde", "serde_json", @@ -2687,7 +2688,7 @@ dependencies = [ "log", "regex", "reqwest", - "roslibrust", + "roslibrust_codegen", "roslibrust_codegen_macro", "roslibrust_common", "roslibrust_serde_rosmsg", diff --git a/roslibrust/src/lib.rs b/roslibrust/src/lib.rs index b29b46f6..3725c297 100644 --- a/roslibrust/src/lib.rs +++ b/roslibrust/src/lib.rs @@ -110,10 +110,3 @@ pub mod rosapi; // If the ros1 feature is enabled, export the roslibrust_ros1 crate under ros1 #[cfg(feature = "ros1")] pub use roslibrust_ros1 as ros1; - -// Topic provider is locked behind a feature until it is stabalized -// additionally because of its use of generic associated types, it requires rust >1.65 -#[cfg(feature = "topic_provider")] -/// Provides a generic trait for building clients / against either the rosbridge, -/// ros1, or a mock backend -pub mod topic_provider; diff --git a/roslibrust/src/rosbridge/mod.rs b/roslibrust/src/rosbridge/mod.rs index 17646064..e381b8fa 100644 --- a/roslibrust/src/rosbridge/mod.rs +++ b/roslibrust/src/rosbridge/mod.rs @@ -1,5 +1,4 @@ -use roslibrust_common::RosServiceType; - +use roslibrust_common::*; // Subscriber is a transparent module, we directly expose internal types // Module exists only to organize source code. mod subscriber; @@ -125,3 +124,90 @@ pub(crate) struct Subscription { pub(crate) struct PublisherHandle { pub(crate) topic_type: String, } + +// Implement the generic Service trait for our ServiceClient +impl Service for crate::ServiceClient { + async fn call(&self, request: &T::Request) -> RosLibRustResult { + // TODO sort out the reference vs clone stuff here + ServiceClient::call(&self, request.clone()).await + } +} + +impl ServiceProvider for crate::ClientHandle { + type ServiceClient = crate::ServiceClient; + type ServiceServer = crate::ServiceHandle; + + async fn service_client( + &self, + topic: &str, + ) -> RosLibRustResult> { + self.service_client::(topic).await + } + + fn advertise_service( + &self, + topic: &str, + server: F, + ) -> impl futures::Future> + Send + where + F: ServiceFn, + { + self.advertise_service(topic, server) + } +} + +// Implementation of TopicProvider trait for rosbridge client +impl TopicProvider for crate::ClientHandle { + type Publisher = crate::Publisher; + type Subscriber = crate::Subscriber; + + async fn advertise( + &self, + topic: &str, + ) -> RosLibRustResult> { + self.advertise::(topic.as_ref()).await + } + + async fn subscribe( + &self, + topic: &str, + ) -> RosLibRustResult> { + self.subscribe(topic).await + } +} + +impl Subscribe for crate::Subscriber { + async fn next(&mut self) -> RosLibRustResult { + // TODO: rosbridge subscribe really should emit errors... + Ok(crate::Subscriber::next(self).await) + } +} + +// Provide an implementation of publish for rosbridge backend +impl Publish for crate::Publisher { + async fn publish(&self, data: &T) -> RosLibRustResult<()> { + self.publish(data).await + } +} + +#[cfg(test)] +mod test { + use roslibrust_common::*; + + // Prove that we've implemented the topic provider trait fully for ClientHandle + #[test] + #[should_panic] + fn topic_provider_can_be_used_at_compile_time() { + struct MyClient { + _client: T, + } + + // Kinda a hack way to make the compiler prove it could construct a MyClient with out actually + // constructing one at runtime + let new_mock: Result = Err(anyhow::anyhow!("Expected error")); + + let _x = MyClient { + _client: new_mock.unwrap(), // panic + }; + } +} diff --git a/roslibrust/src/topic_provider.rs b/roslibrust/src/topic_provider.rs deleted file mode 100644 index b5b1ae63..00000000 --- a/roslibrust/src/topic_provider.rs +++ /dev/null @@ -1,281 +0,0 @@ -use roslibrust_common::{RosMessageType, RosServiceType, ServiceFn}; - -use crate::{RosLibRustResult, ServiceClient}; - -/// Indicates that something is a publisher and has our expected publish -/// Implementors of this trait are expected to auto-cleanup the publisher when dropped -pub trait Publish { - // Note: this is really just syntactic de-sugared `async fn` - // However see: https://blog.rust-lang.org/2023/12/21/async-fn-rpit-in-traits.html - // This generates a warning is rust as of writing due to ambiguity around the "Send-ness" of the return type - // We only plan to work with multi-threaded work stealing executors (e.g. tokio) so we're manually specifying Send - fn publish(&self, data: &T) -> impl futures::Future> + Send; -} - -// Provide an implementation of publish for rosbridge backend -impl Publish for crate::Publisher { - async fn publish(&self, data: &T) -> RosLibRustResult<()> { - self.publish(data).await - } -} - -// Provide an implementation of publish for ros1 backend -#[cfg(feature = "ros1")] -impl Publish for crate::ros1::Publisher { - async fn publish(&self, data: &T) -> RosLibRustResult<()> { - // TODO error type conversion here is terrible and we need to standardize error stuff badly - self.publish(data) - .await - .map_err(|e| crate::RosLibRustError::SerializationError(e.to_string())) - } -} - -/// Indicates that something is a subscriber and has our expected subscribe method -/// Implementors of this trait are expected to auto-cleanup the subscriber when dropped -pub trait Subscribe { - // TODO need to solidify how we want errors to work with subscribers... - // TODO ros1 currently requires mut for next, we should change that - fn next(&mut self) -> impl futures::Future> + Send; -} - -impl Subscribe for crate::Subscriber { - async fn next(&mut self) -> RosLibRustResult { - // TODO: rosbridge subscribe really should emit errors... - Ok(crate::Subscriber::next(self).await) - } -} - -#[cfg(feature = "ros1")] -impl Subscribe for crate::ros1::Subscriber { - async fn next(&mut self) -> RosLibRustResult { - let res = crate::ros1::Subscriber::next(self).await; - match res { - Some(Ok(msg)) => Ok(msg), - Some(Err(e)) => { - log::error!("Subscriber got error: {e:?}"); - // TODO gotta do better error conversion / error types here - Err(crate::RosLibRustError::Unexpected(anyhow::anyhow!( - "Subscriber got error: {e:?}" - ))) - } - None => { - log::error!("Subscriber hit dropped channel"); - Err(crate::RosLibRustError::Unexpected(anyhow::anyhow!( - "Channel closed, something was dropped?" - ))) - } - } - } -} - -/// This trait generically describes the capability of something to act as an async interface to a set of topics -/// -/// This trait is largely based on ROS concepts, but could be extended to other protocols / concepts. -/// Fundamentally, it assumes that topics are uniquely identified by a string name (likely an ASCII assumption is buried in here...). -/// It assumes topics only carry one data type, but is not expected to enforce that. -/// It assumes that all actions can fail due to a variety of causes, and by network interruption specifically. -pub trait TopicProvider { - // These associated types makeup the other half of the API - // They are expected to be "self-deregistering", where dropping them results in unadvertise or unsubscribe operations as appropriate - // We require Publisher and Subscriber types to be Send + 'static so they can be sent into different tokio tasks once created - type Publisher: Publish + Send + 'static; - type Subscriber: Subscribe + Send + 'static; - - /// Advertises a topic to be published to and returns a type specific publisher to use. - /// - /// The returned publisher is expected to be "self de-registering", where dropping the publisher results in the appropriate unadvertise operation. - fn advertise( - &self, - topic: &str, - ) -> impl futures::Future>> + Send; - - /// Subscribes to a topic and returns a type specific subscriber to use. - /// - /// The returned subscriber is expected to be "self de-registering", where dropping the subscriber results in the appropriate unsubscribe operation. - fn subscribe( - &self, - topic: &str, - ) -> impl futures::Future>> + Send; -} - -// Implementation of TopicProvider trait for rosbridge client -impl TopicProvider for crate::ClientHandle { - type Publisher = crate::Publisher; - type Subscriber = crate::Subscriber; - - async fn advertise( - &self, - topic: &str, - ) -> RosLibRustResult> { - self.advertise::(topic.as_ref()).await - } - - async fn subscribe( - &self, - topic: &str, - ) -> RosLibRustResult> { - self.subscribe(topic).await - } -} - -#[cfg(feature = "ros1")] -impl TopicProvider for crate::ros1::NodeHandle { - type Publisher = crate::ros1::Publisher; - type Subscriber = crate::ros1::Subscriber; - - async fn advertise( - &self, - topic: &str, - ) -> RosLibRustResult> { - // TODO MAJOR: consider promoting queue size, making unlimited default - self.advertise::(topic.as_ref(), 10, false) - .await - .map_err(|e| e.into()) - } - - async fn subscribe( - &self, - topic: &str, - ) -> RosLibRustResult> { - // TODO MAJOR: consider promoting queue size, making unlimited default - self.subscribe(topic, 10).await.map_err(|e| e.into()) - } -} - -/// Defines what it means to be something that is callable as a service -pub trait Service { - fn call( - &self, - request: &T::Request, - ) -> impl futures::Future> + Send; -} - -impl Service for crate::ServiceClient { - async fn call(&self, request: &T::Request) -> RosLibRustResult { - // TODO sort out the reference vs clone stuff here - ServiceClient::call(&self, request.clone()).await - } -} - -#[cfg(feature = "ros1")] -impl Service for crate::ros1::ServiceClient { - async fn call(&self, request: &T::Request) -> RosLibRustResult { - self.call(request).await - } -} - -/// This trait is analogous to TopicProvider, but instead provides the capability to create service servers and service clients -pub trait ServiceProvider { - type ServiceClient: Service + Send + 'static; - type ServiceServer; - - fn service_client( - &self, - topic: &str, - ) -> impl futures::Future>> + Send; - - fn advertise_service( - &self, - topic: &str, - server: F, - ) -> impl futures::Future> + Send - where - F: ServiceFn; -} - -impl ServiceProvider for crate::ClientHandle { - type ServiceClient = crate::ServiceClient; - type ServiceServer = crate::ServiceHandle; - - async fn service_client( - &self, - topic: &str, - ) -> RosLibRustResult> { - self.service_client::(topic).await - } - - fn advertise_service( - &self, - topic: &str, - server: F, - ) -> impl futures::Future> + Send - where - F: ServiceFn, - { - self.advertise_service(topic, server) - } -} - -#[cfg(feature = "ros1")] -impl ServiceProvider for crate::ros1::NodeHandle { - type ServiceClient = crate::ros1::ServiceClient; - type ServiceServer = crate::ros1::ServiceServer; - - async fn service_client( - &self, - topic: &str, - ) -> RosLibRustResult> { - // TODO bad error mapping here... - self.service_client::(topic).await.map_err(|e| e.into()) - } - - async fn advertise_service( - &self, - topic: &str, - server: F, - ) -> RosLibRustResult - where - F: ServiceFn, - { - self.advertise_service::(topic, server) - .await - .map_err(|e| e.into()) - } -} - -#[cfg(test)] -mod test { - use super::TopicProvider; - use crate::{ros1::NodeHandle, ClientHandle}; - - // This test specifically fails because TopicProvider is not object safe - // Traits that have methods with generic parameters cannot be object safe in rust (currently) - // #[test] - // fn topic_provider_can_be_constructed() -> TestResult { - // let x: Box = Box::new(ClientHandle::new("")); - // Ok(()) - // } - - // This tests proves that you could use topic provider in a compile time api, but not object safe... - #[test_log::test] - #[should_panic] - fn topic_provider_can_be_used_at_compile_time() { - struct MyClient { - _client: T, - } - - // Kinda a hack way to make the compiler prove it could construct a MyClient with out actually - // constructing one at runtime - let new_mock: Result = Err(anyhow::anyhow!("Expected error")); - - let _x = MyClient { - _client: new_mock.unwrap(), // panic - }; - } - - #[test_log::test] - #[should_panic] - fn topic_provider_can_be_used_with_ros1() { - struct MyClient { - _client: T, - } - - // Kinda a hack way to make the compiler prove it could construct a MyClient with out actually - // constructing one at runtime - let new_mock: Result = Err(anyhow::anyhow!("Expected error")); - - let _x = MyClient { - _client: new_mock.unwrap(), // panic - }; - } -} diff --git a/roslibrust_common/Cargo.toml b/roslibrust_common/Cargo.toml index cb339b2f..5cfc7e38 100644 --- a/roslibrust_common/Cargo.toml +++ b/roslibrust_common/Cargo.toml @@ -4,11 +4,15 @@ version = "0.1.0" edition = "2021" [dependencies] +# Used for error handling thiserror = "2.0" anyhow = "1.0" +# Used as basis for serialization serde = { version = "1.0", features = ["derive"] } # Used for md5sum calculation md5 = "0.7" +# Used for async trait definitions +futures = "0.3" # THESE DEPENDENCIES WILL BE REMOVED # We're currently leaking these error types in the "generic error type" diff --git a/roslibrust_common/src/lib.rs b/roslibrust_common/src/lib.rs index ded48f48..a6bfc3b9 100644 --- a/roslibrust_common/src/lib.rs +++ b/roslibrust_common/src/lib.rs @@ -109,3 +109,8 @@ impl RosMessageType for ShapeShifter { /// Contains functions for calculating md5sums of message definitions /// These functions are needed both in roslibrust_ros1 and roslibrust_codegen so they're in this crate pub mod md5sum; + +/// Contains the generic traits represent a pubsub system and service system +/// These traits will be implemented for specific backends to provides access to "ROS Like" functionality +pub mod topic_provider; +pub use topic_provider::*; // Bring topic provider traits into root namespace diff --git a/roslibrust_common/src/topic_provider.rs b/roslibrust_common/src/topic_provider.rs new file mode 100644 index 00000000..eaac6b9e --- /dev/null +++ b/roslibrust_common/src/topic_provider.rs @@ -0,0 +1,87 @@ +use crate::{RosLibRustResult, RosMessageType, RosServiceType, ServiceFn}; + +/// Indicates that something is a publisher and has our expected publish +/// Implementors of this trait are expected to auto-cleanup the publisher when dropped +pub trait Publish { + // Note: this is really just syntactic de-sugared `async fn` + // However see: https://blog.rust-lang.org/2023/12/21/async-fn-rpit-in-traits.html + // This generates a warning is rust as of writing due to ambiguity around the "Send-ness" of the return type + // We only plan to work with multi-threaded work stealing executors (e.g. tokio) so we're manually specifying Send + fn publish(&self, data: &T) -> impl futures::Future> + Send; +} + +/// Indicates that something is a subscriber and has our expected subscribe method +/// Implementors of this trait are expected to auto-cleanup the subscriber when dropped +pub trait Subscribe { + // TODO need to solidify how we want errors to work with subscribers... + // TODO ros1 currently requires mut for next, we should change that + fn next(&mut self) -> impl futures::Future> + Send; +} + +/// This trait generically describes the capability of something to act as an async interface to a set of topics +/// +/// This trait is largely based on ROS concepts, but could be extended to other protocols / concepts. +/// Fundamentally, it assumes that topics are uniquely identified by a string name (likely an ASCII assumption is buried in here...). +/// It assumes topics only carry one data type, but is not expected to enforce that. +/// It assumes that all actions can fail due to a variety of causes, and by network interruption specifically. +pub trait TopicProvider { + // These associated types makeup the other half of the API + // They are expected to be "self-deregistering", where dropping them results in unadvertise or unsubscribe operations as appropriate + // We require Publisher and Subscriber types to be Send + 'static so they can be sent into different tokio tasks once created + type Publisher: Publish + Send + 'static; + type Subscriber: Subscribe + Send + 'static; + + /// Advertises a topic to be published to and returns a type specific publisher to use. + /// + /// The returned publisher is expected to be "self de-registering", where dropping the publisher results in the appropriate unadvertise operation. + fn advertise( + &self, + topic: &str, + ) -> impl futures::Future>> + Send; + + /// Subscribes to a topic and returns a type specific subscriber to use. + /// + /// The returned subscriber is expected to be "self de-registering", where dropping the subscriber results in the appropriate unsubscribe operation. + fn subscribe( + &self, + topic: &str, + ) -> impl futures::Future>> + Send; +} + +/// Defines what it means to be something that is callable as a service +pub trait Service { + fn call( + &self, + request: &T::Request, + ) -> impl futures::Future> + Send; +} + +/// This trait is analogous to TopicProvider, but instead provides the capability to create service servers and service clients +pub trait ServiceProvider { + type ServiceClient: Service + Send + 'static; + type ServiceServer; + + fn service_client( + &self, + topic: &str, + ) -> impl futures::Future>> + Send; + + fn advertise_service( + &self, + topic: &str, + server: F, + ) -> impl futures::Future> + Send + where + F: ServiceFn; +} + +#[cfg(test)] +mod test { + // This test specifically fails because TopicProvider is not object safe + // Traits that have methods with generic parameters cannot be object safe in rust (currently) + // #[test] + // fn topic_provider_can_be_constructed() -> TestResult { + // let x: Box = Box::new(ClientHandle::new("")); + // Ok(()) + // } +} diff --git a/roslibrust_ros1/Cargo.toml b/roslibrust_ros1/Cargo.toml index 6855d570..545f0ca7 100644 --- a/roslibrust_ros1/Cargo.toml +++ b/roslibrust_ros1/Cargo.toml @@ -30,8 +30,8 @@ anyhow = "1.0" # Used to provide message types for the examples # TODO generate a roslibrust_std_msgs crate we can depend on instead of this roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } -# Used to test topic provider? Maybe move those tests to roslibrust directly? -roslibrust = { path = "../roslibrust"} +# Relied on by generate types in the macro this should be cleaned up +roslibrust_codegen = { path = "../roslibrust_codegen" } [features] # Used for enabling tests that rely on a running ros1 master diff --git a/roslibrust_ros1/src/lib.rs b/roslibrust_ros1/src/lib.rs index e82b4e18..4a94c6e4 100644 --- a/roslibrust_ros1/src/lib.rs +++ b/roslibrust_ros1/src/lib.rs @@ -1,5 +1,7 @@ //! This module holds all content for directly working with ROS1 natively +use roslibrust_common::*; + /// [master_client] module contains code for calling xmlrpc functions on the master mod master_client; pub use master_client::*; @@ -27,3 +29,113 @@ pub(crate) type TypeErasedCallback = dyn Fn(Vec) -> Result, Box = crate::Publisher; + type Subscriber = crate::Subscriber; + + async fn advertise( + &self, + topic: &str, + ) -> RosLibRustResult> { + // TODO MAJOR: consider promoting queue size, making unlimited default + self.advertise::(topic.as_ref(), 10, false) + .await + .map_err(|e| e.into()) + } + + async fn subscribe( + &self, + topic: &str, + ) -> RosLibRustResult> { + // TODO MAJOR: consider promoting queue size, making unlimited default + self.subscribe(topic, 10).await.map_err(|e| e.into()) + } +} + +impl Service for ServiceClient { + async fn call(&self, request: &T::Request) -> RosLibRustResult { + self.call(request).await + } +} + +impl ServiceProvider for crate::NodeHandle { + type ServiceClient = crate::ServiceClient; + type ServiceServer = crate::ServiceServer; + + async fn service_client( + &self, + topic: &str, + ) -> RosLibRustResult> { + // TODO bad error mapping here... + self.service_client::(topic).await.map_err(|e| e.into()) + } + + async fn advertise_service( + &self, + topic: &str, + server: F, + ) -> RosLibRustResult + where + F: ServiceFn, + { + self.advertise_service::(topic, server) + .await + .map_err(|e| e.into()) + } +} + +impl Subscribe for crate::Subscriber { + async fn next(&mut self) -> RosLibRustResult { + let res = crate::Subscriber::next(self).await; + match res { + Some(Ok(msg)) => Ok(msg), + Some(Err(e)) => { + log::error!("Subscriber got error: {e:?}"); + // TODO gotta do better error conversion / error types here + Err(crate::RosLibRustError::Unexpected(anyhow::anyhow!( + "Subscriber got error: {e:?}" + ))) + } + None => { + log::error!("Subscriber hit dropped channel"); + Err(crate::RosLibRustError::Unexpected(anyhow::anyhow!( + "Channel closed, something was dropped?" + ))) + } + } + } +} + +// Provide an implementation of publish for ros1 backend +impl Publish for Publisher { + async fn publish(&self, data: &T) -> RosLibRustResult<()> { + // TODO error type conversion here is terrible and we need to standardize error stuff badly + self.publish(data) + .await + .map_err(|e| RosLibRustError::SerializationError(e.to_string())) + } +} + +#[cfg(test)] +mod test { + use roslibrust_common::*; + + // Prove that we've implemented the topic provider trait fully for NodeHandle + #[test] + #[should_panic] + fn topic_provider_can_be_used_with_ros1() { + struct MyClient { + _client: T, + } + + // Kinda a hack way to make the compiler prove it could construct a MyClient with out actually + // constructing one at runtime + let new_mock: Result = Err(anyhow::anyhow!("Expected error")); + + let _x = MyClient { + _client: new_mock.unwrap(), // panic + }; + } +} diff --git a/roslibrust_ros1/tests/ros1_native_integration_tests.rs b/roslibrust_ros1/tests/ros1_native_integration_tests.rs index 1db573d7..980ba5f6 100644 --- a/roslibrust_ros1/tests/ros1_native_integration_tests.rs +++ b/roslibrust_ros1/tests/ros1_native_integration_tests.rs @@ -467,10 +467,9 @@ mod tests { } #[test_log::test(tokio::test)] - #[cfg(all(feature = "ros1_test"))] + #[cfg(feature = "ros1_test")] async fn topic_provider_publish_functionality_test() { - use roslibrust::topic_provider::*; - use roslibrust::ClientHandle; + use roslibrust_common::*; // Dropping watchdog at end of function cancels watchdog // This test can hang which gives crappy debug output diff --git a/roslibrust_zenoh/Cargo.toml b/roslibrust_zenoh/Cargo.toml index 2a8818fc..49b233e6 100644 --- a/roslibrust_zenoh/Cargo.toml +++ b/roslibrust_zenoh/Cargo.toml @@ -7,11 +7,7 @@ edition = "2021" [dependencies] tokio = { version = "1.41", features = ["rt-multi-thread", "sync", "macros"] } -# We currently need to depend on these crates for trait information -# I think we should move topic_provider and the generic message traits into their own crate -# Then more things can work with them generically with less compile time dependencies -roslibrust = { path = "../roslibrust", features = ["topic_provider"] } -roslibrust_codegen = { path = "../roslibrust_codegen" } +roslibrust_common = { path = "../roslibrust_common" } zenoh = "1.0" hex = "0.4" anyhow = "1.0" @@ -20,7 +16,9 @@ log = "0.4" [dev-dependencies] env_logger = "0.11" +# Used to access traits for examples +roslibrust = { path = "../roslibrust" } # Used to generate message types for the examples roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } # Relied on by generate types in the macro this should be cleaned up -roslibrust_common = { path = "../roslibrust_common" } +roslibrust_codegen = { path = "../roslibrust_codegen" } diff --git a/roslibrust_zenoh/examples/publisher.rs b/roslibrust_zenoh/examples/publisher.rs index 781b8903..53fc23d2 100644 --- a/roslibrust_zenoh/examples/publisher.rs +++ b/roslibrust_zenoh/examples/publisher.rs @@ -1,11 +1,11 @@ use roslibrust_zenoh::ZenohClient; -// IMPORTANT to bring this trait into scope so we can access the functions it provides -// This trait provides the [subscribe] and [advertise] functions on ZenohCilent -use roslibrust::topic_provider::TopicProvider; -// IMPORTANT to bring this trait into scope so we can access the functions it provides -// This trait provides the [next] function on ZenohSubscriber -use roslibrust::topic_provider::Publish; +/// IMPORTANT to bring this trait into scope so we can access the functions it provides +/// This trait provides the [next][roslibrust::Subscribe::next] function on ZenohSubscriber +use roslibrust::Publish; +/// IMPORTANT to bring this trait into scope so we can access the functions it provides +/// This trait provides the [subscribe][roslibrust::TopicProvider::subscribe] and [advertise][roslibrust::TopicProvider::advertise] functions on ZenohCilent +use roslibrust::TopicProvider; // Generate rust definitions for our messages roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); diff --git a/roslibrust_zenoh/examples/service_call.rs b/roslibrust_zenoh/examples/service_call.rs index e40b97e6..214f47c5 100644 --- a/roslibrust_zenoh/examples/service_call.rs +++ b/roslibrust_zenoh/examples/service_call.rs @@ -1,12 +1,12 @@ //! Purpose of this example is to show how to call a ROS1 service from a Zenoh client. -// IMPORTANT to bring this trait into scope so we can access the functions it provides -// [Service] is what allows us to actually access [call] -use roslibrust::topic_provider::Service; +/// IMPORTANT to bring this trait into scope so we can access the functions it provides +/// [roslibrust::Service] is what allows us to actually access [call] +use roslibrust::Service; -// IMPORTANT to bring this trait into scope so we can access the functions it provides -// [ServiceProvider] is what allows us to actually access .service_client() -use roslibrust::topic_provider::ServiceProvider; +/// IMPORTANT to bring this trait into scope so we can access the functions it provides +/// [roslibrust::ServiceProvider] is what allows us to actually access .service_client() +use roslibrust::ServiceProvider; // Bring our client type into scope use roslibrust_zenoh::ZenohClient; diff --git a/roslibrust_zenoh/examples/service_server.rs b/roslibrust_zenoh/examples/service_server.rs index f0879036..52d20719 100644 --- a/roslibrust_zenoh/examples/service_server.rs +++ b/roslibrust_zenoh/examples/service_server.rs @@ -1,8 +1,8 @@ //! Purpose of this example is to show how to host service visible to ROS1 from a Zenoh client. // IMPORTANT to bring this trait into scope so we can access the functions it provides -// [ServiceProvider] is what allows us to actually access .service_client() -use roslibrust::topic_provider::ServiceProvider; +// [roslibrust::ServiceProvider] is what allows us to actually access .service_client() +use roslibrust::ServiceProvider; use roslibrust_zenoh::ZenohClient; // IMPORTANT this example will not work with the default zenoh-ros1-bridge settings! diff --git a/roslibrust_zenoh/examples/subscriber.rs b/roslibrust_zenoh/examples/subscriber.rs index b2d8b900..fba700db 100644 --- a/roslibrust_zenoh/examples/subscriber.rs +++ b/roslibrust_zenoh/examples/subscriber.rs @@ -1,11 +1,11 @@ use roslibrust_zenoh::ZenohClient; -// IMPORTANT to bring this trait into scope so we can access the functions it provides -// This trait provides the [subscribe] and [advertise] functions on ZenohCilent -use roslibrust::topic_provider::TopicProvider; -// IMPORTANT to bring this trait into scope so we can access the functions it provides -// This trait provides the [next] function on ZenohSubscriber -use roslibrust::topic_provider::Subscribe; +/// IMPORTANT to bring this trait into scope so we can access the functions it provides +/// This trait provides the [next][roslibrust::Subscribe::next] function on ZenohSubscriber +use roslibrust::Subscribe; +/// IMPORTANT to bring this trait into scope so we can access the functions it provides +/// This trait provides the [subscribe][roslibrust::TopicProvider::subscribe] and [advertise][roslibrust::TopicProvider::advertise] functions on ZenohCilent +use roslibrust::TopicProvider; // Generate rust definitions for our messages roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); diff --git a/roslibrust_zenoh/src/lib.rs b/roslibrust_zenoh/src/lib.rs index 64ad1ac0..e1bb8e77 100644 --- a/roslibrust_zenoh/src/lib.rs +++ b/roslibrust_zenoh/src/lib.rs @@ -1,8 +1,6 @@ //! A crate for interfacing to ROS1 via the [zenoh-ros1-plugin / zenoh-ros1-bridge](https://github.com/eclipse-zenoh/zenoh-plugin-ros1). -use roslibrust::topic_provider::{Publish, Service, ServiceProvider, Subscribe, TopicProvider}; -use roslibrust::{RosLibRustError, RosLibRustResult}; -use roslibrust_codegen::{RosMessageType, RosServiceType}; +use roslibrust_common::*; use log::*; use zenoh::bytes::ZBytes; @@ -215,7 +213,7 @@ impl ServiceProvider for ZenohClient { type ServiceClient = ZenohServiceClient; type ServiceServer = ZenohServiceServer; - async fn service_client( + async fn service_client( &self, topic: &str, ) -> RosLibRustResult> { @@ -228,10 +226,7 @@ impl ServiceProvider for ZenohClient { }) } - async fn advertise_service< - T: roslibrust_codegen::RosServiceType + 'static, - F: roslibrust::ServiceFn, - >( + async fn advertise_service>( &self, topic: &str, server: F, From b4e87ee299c0ec520764fdcf7cc7cf06eb8f5295 Mon Sep 17 00:00:00 2001 From: carter Date: Tue, 10 Dec 2024 16:23:06 -0700 Subject: [PATCH 06/14] REORG ALL THE THINGS --- Cargo.lock | 88 ++++++------------- Cargo.toml | 11 ++- roslibrust/Cargo.toml | 55 ++++-------- roslibrust/examples/basic_publisher.rs | 20 +++-- roslibrust/examples/calling_service.rs | 23 ++--- roslibrust/examples/generic_client.rs | 24 ++--- .../examples/generic_client_services.rs | 26 +++--- roslibrust/examples/generic_message.rs | 24 ++--- roslibrust/examples/native_ros1.rs | 31 ------- roslibrust/examples/ros1_listener.rs | 9 +- roslibrust/examples/ros1_publish_any.rs | 3 +- .../examples/ros1_ros2_bridge_example.rs | 20 ++--- roslibrust/examples/ros1_service_client.rs | 9 +- roslibrust/examples/ros1_service_server.rs | 9 +- roslibrust/examples/ros1_talker.rs | 9 +- roslibrust/examples/service_server.rs | 21 ++--- roslibrust/examples/subscribe_and_log.rs | 21 ++--- roslibrust/src/lib.rs | 15 +++- .../tests/ros1_native_integration_tests.rs | 0 roslibrust_mock/Cargo.toml | 5 +- roslibrust_mock/src/lib.rs | 7 +- roslibrust_rosbridge/Cargo.toml | 36 ++++++++ .../src}/client.rs | 32 ++++--- .../src}/comm.rs | 2 +- .../src}/integration_tests.rs | 9 +- .../mod.rs => roslibrust_rosbridge/src/lib.rs | 11 +-- .../src}/publisher.rs | 0 .../src}/subscriber.rs | 2 +- ...{service_call.rs => zenoh_service_call.rs} | 0 ...vice_server.rs => zenoh_service_server.rs} | 0 30 files changed, 232 insertions(+), 290 deletions(-) delete mode 100644 roslibrust/examples/native_ros1.rs rename {roslibrust_ros1 => roslibrust/src}/tests/ros1_native_integration_tests.rs (100%) create mode 100644 roslibrust_rosbridge/Cargo.toml rename {roslibrust/src/rosbridge => roslibrust_rosbridge/src}/client.rs (96%) rename {roslibrust/src/rosbridge => roslibrust_rosbridge/src}/comm.rs (99%) rename {roslibrust/src/rosbridge => roslibrust_rosbridge/src}/integration_tests.rs (98%) rename roslibrust/src/rosbridge/mod.rs => roslibrust_rosbridge/src/lib.rs (95%) rename {roslibrust/src/rosbridge => roslibrust_rosbridge/src}/publisher.rs (100%) rename {roslibrust/src/rosbridge => roslibrust_rosbridge/src}/subscriber.rs (98%) rename roslibrust_zenoh/examples/{service_call.rs => zenoh_service_call.rs} (100%) rename roslibrust_zenoh/examples/{service_server.rs => zenoh_service_server.rs} (100%) diff --git a/Cargo.lock b/Cargo.lock index 70894554..971199e0 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -450,16 +450,6 @@ version = "1.0.3" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "5b63caa9aa9397e2d9480a9b13673856c78d8ac123288526c37d7839f2a86990" -[[package]] -name = "colored" -version = "2.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "cbf2150cce219b664a8a70df7a1f933836724b503f8a413af9365b4dcc4d90b8" -dependencies = [ - "lazy_static", - "windows-sys 0.48.0", -] - [[package]] name = "combine" version = "4.6.7" @@ -1894,15 +1884,6 @@ dependencies = [ "libc", ] -[[package]] -name = "num_threads" -version = "0.1.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5c7398b9c8b70908f6371f47ed36737907c87c52af34c268fed0bf0ceb92ead9" -dependencies = [ - "libc", -] - [[package]] name = "object" version = "0.36.5" @@ -2571,31 +2552,18 @@ dependencies = [ name = "roslibrust" version = "0.11.1" dependencies = [ - "abort-on-drop", - "anyhow", - "dashmap", - "deadqueue", - "env_logger 0.10.2", - "futures", - "futures-util", - "lazy_static", + "env_logger 0.11.5", "log", - "proc-macro2", - "rand", "roslibrust_codegen", "roslibrust_codegen_macro", "roslibrust_common", + "roslibrust_mock", "roslibrust_ros1", + "roslibrust_rosbridge", + "roslibrust_zenoh", "serde", - "serde-big-array", - "serde_json", - "simple_logger", - "smart-default 0.6.0", "test-log", - "thiserror 1.0.69", "tokio", - "tokio-tungstenite 0.17.2", - "uuid", ] [[package]] @@ -2614,7 +2582,7 @@ dependencies = [ "serde_bytes", "serde_json", "simple-error", - "smart-default 0.7.1", + "smart-default", "syn 1.0.109", "test-log", "tokio", @@ -2668,7 +2636,6 @@ version = "0.1.0" dependencies = [ "bincode", "log", - "roslibrust", "roslibrust_codegen", "roslibrust_codegen_macro", "roslibrust_common", @@ -2699,6 +2666,26 @@ dependencies = [ "tokio", ] +[[package]] +name = "roslibrust_rosbridge" +version = "0.1.0" +dependencies = [ + "anyhow", + "dashmap", + "deadqueue", + "futures", + "futures-util", + "log", + "roslibrust_codegen", + "roslibrust_codegen_macro", + "roslibrust_common", + "serde_json", + "test-log", + "tokio", + "tokio-tungstenite 0.17.2", + "uuid", +] + [[package]] name = "roslibrust_serde_rosmsg" version = "0.4.0" @@ -3196,18 +3183,6 @@ version = "0.3.1" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "7e2accd2c41a0e920d2abd91b2badcfa1da784662f54fbc47e0e3a51f1e2e1cf" -[[package]] -name = "simple_logger" -version = "5.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e8c5dfa5e08767553704aa0ffd9d9794d527103c736aba9854773851fd7497eb" -dependencies = [ - "colored", - "log", - "time", - "windows-sys 0.48.0", -] - [[package]] name = "siphasher" version = "0.3.11" @@ -3229,17 +3204,6 @@ version = "1.13.2" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "3c5e1a9a646d36c3599cd173a41282daf47c44583ad367b8e6837255952e5c67" -[[package]] -name = "smart-default" -version = "0.6.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "133659a15339456eeeb07572eb02a91c91e9815e9cbc89566944d2c8d3efdbf6" -dependencies = [ - "proc-macro2", - "quote", - "syn 1.0.109", -] - [[package]] name = "smart-default" version = "0.7.1" @@ -3501,9 +3465,7 @@ checksum = "35e7868883861bd0e56d9ac6efcaaca0d6d5d82a2a7ec8209ff492c07cf37b21" dependencies = [ "deranged", "itoa", - "libc", "num-conv", - "num_threads", "powerfmt", "serde", "time-core", diff --git a/Cargo.toml b/Cargo.toml index 03ceda15..d182b7c6 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -3,12 +3,15 @@ members = [ "example_package", "example_package_macro", - "roslibrust", - "roslibrust_codegen", "roslibrust_codegen_macro", + "roslibrust_codegen", + "roslibrust_common", "roslibrust_genmsg", - "roslibrust_test", "roslibrust_mock", - "roslibrust_zenoh", "roslibrust_ros1", "roslibrust_common", + "roslibrust_ros1", + "roslibrust_rosbridge", + "roslibrust_test", + "roslibrust_zenoh", + "roslibrust", ] resolver = "2" diff --git a/roslibrust/Cargo.toml b/roslibrust/Cargo.toml index 61cdc8a2..99f8f8fd 100644 --- a/roslibrust/Cargo.toml +++ b/roslibrust/Cargo.toml @@ -6,66 +6,49 @@ edition = "2021" license = "MIT" readme = "../README.md" description = "An library for interfacing with the ROS's rosbridge_server" -repository = "https://github.com/Carter12s/roslibrust" +repository = "https://github.com/roslibrust/roslibrust" keywords = ["ROS", "robotics", "websocket", "json", "async"] categories = ["science::robotics"] [dependencies] -abort-on-drop = "0.2" -anyhow = "1.0" -dashmap = "5.3" -deadqueue = "0.2.4" # .4+ is required to fix bug with missing tokio dep -futures = "0.3" -futures-util = "0.3" -lazy_static = "1.4" -log = "0.4" -proc-macro2 = "1.0" -rand = "0.8" -serde = { version = "1.0", features = ["derive"] } -serde_json = "1.0" -smart-default = "0.6" -thiserror = "1.0" -tokio = { version = "1.20", features = [ - "net", - "macros", - "time", - "rt-multi-thread", -] } -tokio-tungstenite = { version = "0.17" } -uuid = { version = "1.1", features = ["v4"] } -# TODO this crate shouldn't depend on codegen or codege_macro directly -roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro", version = "0.11.1" } -roslibrust_codegen = { path = "../roslibrust_codegen", version = "0.11.1" } - # TODO version here roslibrust_common = { path = "../roslibrust_common" } -# TODO I think we should move rosapi into its own crate... -serde-big-array = { version = "0.5", optional = true } # Only used with rosapi -# TODO REAL VERSION HERE roslibrust_ros1 = { path = "../roslibrust_ros1", optional = true } +roslibrust_rosbridge = { path = "../roslibrust_rosbridge", optional = true } +roslibrust_zenoh = { path = "../roslibrust_zenoh", optional = true } +roslibrust_mock = { path = "../roslibrust_mock", optional = true } [dev-dependencies] -env_logger = "0.10" +env_logger = "0.11" test-log = "0.2" -simple_logger = "5.0" -serde-big-array = "0.5" +log = "0.4" +tokio = { version = "1.20", features = ["macros", "rt-multi-thread"] } +serde = { version = "1.0", features = ["derive"] } +# Used to generate messages for the examples +roslibrust_codegen = { path = "../roslibrust_codegen" } +roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } [features] default = [] # Note: all does not include running_bridge as that is only intended for CI all = [] # Provides a rosapi rust interface -rosapi = ["serde-big-array"] +# TODO MAJOR remove this feature +rosapi = [] # Intended for use with tests, includes tests that rely on a locally running rosbridge running_bridge = [] # For use with integration tests, indicating we are testing integration with a ros1 bridge ros1_test = ["running_bridge", "ros1"] # For use with integration tests, indicates we are testing integration with a ros2 bridge ros2_test = ["running_bridge"] -# Provides access to experimental abstract trait topic_provider -topic_provider = [] # Provides a ros1 xmlrpc / TCPROS client ros1 = ["roslibrust_ros1"] +# Provides a backend using the rosbridge websocket protocol +rosbridge = ["roslibrust_rosbridge"] +# Provides a backend using zenoh's ros1 format from zenoh-bridge-ros1 +zenoh = ["roslibrust_zenoh"] +# Provides a mock backend useful for writing tests around nodes +mock = ["roslibrust_mock"] [package.metadata.docs.rs] features = ["ros1"] diff --git a/roslibrust/examples/basic_publisher.rs b/roslibrust/examples/basic_publisher.rs index 1ec002a6..4981a06a 100644 --- a/roslibrust/examples/basic_publisher.rs +++ b/roslibrust/examples/basic_publisher.rs @@ -1,19 +1,16 @@ -use log::*; -use roslibrust::ClientHandle; - +#[cfg(feature = "rosbridge")] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces/std_msgs"); /// This example creates a client, and publishes a message to the topic "talker" /// Running this example at the same time as subscribe_and_log will have the two examples /// pass messages between each other. /// To run this example a rosbridge websocket server should be running at the deafult port (9090). +#[cfg(feature = "rosbridge")] #[tokio::main(flavor = "multi_thread")] -async fn main() -> Result<(), anyhow::Error> { - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // required for running wsl2 - .init() - .unwrap(); +async fn main() -> Result<(), Box> { + use log::*; + use roslibrust::rosbridge::ClientHandle; + env_logger::init(); let client = ClientHandle::new("ws://localhost:9090").await?; let publisher = client.advertise::("talker").await?; @@ -33,3 +30,8 @@ async fn main() -> Result<(), anyhow::Error> { tokio::time::sleep(tokio::time::Duration::from_secs(1)).await; } } + +#[cfg(not(feature = "rosbridge"))] +fn main() { + eprintln!("This example does nothing without compiling with the feature 'rosbridge'"); +} diff --git a/roslibrust/examples/calling_service.rs b/roslibrust/examples/calling_service.rs index 2128ac7e..6793db2d 100644 --- a/roslibrust/examples/calling_service.rs +++ b/roslibrust/examples/calling_service.rs @@ -1,19 +1,17 @@ -use log::*; -use roslibrust::ClientHandle; - -roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces",); +#[cfg(feature = "rosbridge")] +roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces/rosapi"); /// This example shows calling a service /// To run this example rosbridge and a roscore should be running /// As well as the rosapi node. /// This node calls a service on the rosapi node to get the current ros time. +#[cfg(feature = "rosbridge")] #[tokio::main(flavor = "multi_thread")] -async fn main() -> Result<(), anyhow::Error> { - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // Required for running in wsl2 - .init() - .unwrap(); +async fn main() -> Result<(), Box> { + use log::*; + use roslibrust::rosbridge::ClientHandle; + + env_logger::init(); let client = ClientHandle::new("ws://localhost:9090").await?; @@ -25,3 +23,8 @@ async fn main() -> Result<(), anyhow::Error> { info!("Got time: {:?}", result); Ok(()) } + +#[cfg(not(feature = "rosbridge"))] +fn main() { + eprintln!("This example does nothing without compiling with the feature 'rosbridge'"); +} diff --git a/roslibrust/examples/generic_client.rs b/roslibrust/examples/generic_client.rs index c3c79d78..f86c334e 100644 --- a/roslibrust/examples/generic_client.rs +++ b/roslibrust/examples/generic_client.rs @@ -1,18 +1,16 @@ //! Purpose of this example is to show how the TopicProvider trait can be use //! to create code that is generic of which communication backend it will use. -#[cfg(feature = "topic_provider")] -use roslibrust::topic_provider::*; +// Important to bring these traits into scope so we can use them + +#[cfg(all(feature = "rosbridge", feature = "ros1"))] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces/std_msgs"); -#[cfg(feature = "topic_provider")] +#[cfg(all(feature = "rosbridge", feature = "ros1"))] #[tokio::main] async fn main() { - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // required for running wsl2 - .init() - .unwrap(); + use roslibrust::{Publish, Subscribe, TopicProvider}; + env_logger::init(); // TopicProvider cannot be an "Object Safe Trait" due to its generic parameters // This means we can't do: @@ -61,7 +59,7 @@ async fn main() { } // create a rosbridge handle and start node - let ros = roslibrust::ClientHandle::new("ws://localhost:9090") + let ros = roslibrust::rosbridge::ClientHandle::new("ws://localhost:9090") .await .unwrap(); let node = MyNode { @@ -91,5 +89,9 @@ async fn main() { // Note: this will not run without rosbridge running } -#[cfg(not(feature = "topic_provider"))] -fn main() {} +#[cfg(not(all(feature = "rosbridge", feature = "ros1")))] +fn main() { + eprintln!( + "This example does nothing without compiling with the feature 'rosbridge' and 'ros1'" + ); +} diff --git a/roslibrust/examples/generic_client_services.rs b/roslibrust/examples/generic_client_services.rs index a4d57f11..f755e863 100644 --- a/roslibrust/examples/generic_client_services.rs +++ b/roslibrust/examples/generic_client_services.rs @@ -1,18 +1,15 @@ //! Purpose of this example is to show how the ServiceProvider trait can be use //! to create code that is generic of which communication backend it will use. -#[cfg(feature = "topic_provider")] -use roslibrust::topic_provider::*; +#[cfg(all(feature = "rosbridge", feature = "ros1"))] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); -#[cfg(feature = "topic_provider")] +#[cfg(all(feature = "rosbridge", feature = "ros1"))] #[tokio::main] async fn main() { - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // required for running wsl2 - .init() - .unwrap(); + // Important to bring these traits into scope so we can use them + use roslibrust::{Service, ServiceProvider}; + env_logger::init(); // TopicProvider cannot be an "Object Safe Trait" due to its generic parameters // This means we can't do: @@ -57,16 +54,17 @@ async fn main() { tokio::time::sleep(std::time::Duration::from_millis(500)).await; println!("sleeping"); - client + let response = client .call(&std_srvs::SetBoolRequest { data: true }) .await .unwrap(); + println!("Got response: {response:?}"); } } } // create a rosbridge handle and start node - let ros = roslibrust::ClientHandle::new("ws://localhost:9090") + let ros = roslibrust::rosbridge::ClientHandle::new("ws://localhost:9090") .await .unwrap(); let node = MyNode { ros }; @@ -89,5 +87,9 @@ async fn main() { // You should see log output from both nodes } -#[cfg(not(feature = "topic_provider"))] -fn main() {} +#[cfg(not(all(feature = "rosbridge", feature = "ros1")))] +fn main() { + eprintln!( + "This example does nothing without compiling with the feature 'rosbridge' and 'ros1'" + ); +} diff --git a/roslibrust/examples/generic_message.rs b/roslibrust/examples/generic_message.rs index 14b88ce6..612dbf56 100644 --- a/roslibrust/examples/generic_message.rs +++ b/roslibrust/examples/generic_message.rs @@ -1,7 +1,5 @@ //! This example shows off creating a custom generic message, and leveraging serde_json's parsing resolution //! to decode to the right type. -use log::*; -use roslibrust::ClientHandle; use roslibrust_common::RosMessageType; /// We place the ros1 generate code into a module to prevent name collisions with the identically @@ -34,23 +32,20 @@ impl RosMessageType for GenericHeader { /// the same ROS type name. const ROS_TYPE_NAME: &'static str = "std_msgs/Header"; - // TODO these fields should be removed and not required for this example see - // https://github.com/Carter12s/roslibrust/issues/124 - const MD5SUM: &'static str = ""; + // "*" is used as a wildcard to match any md5sum + const MD5SUM: &'static str = "*"; const DEFINITION: &'static str = ""; } /// Sets up a subscriber that could get either of two versions of a message +#[cfg(feature = "rosbridge")] #[tokio::main] -async fn main() -> Result<(), anyhow::Error> { - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // required for running in wsl2 - .init() - .unwrap(); +async fn main() -> Result<(), Box> { + use log::*; + env_logger::init(); // An instance of rosbridge needs to be running at this address for the example to work - let client = ClientHandle::new("ws://localhost:9090").await?; + let client = roslibrust::rosbridge::ClientHandle::new("ws://localhost:9090").await?; info!("ClientHandle connected"); let rx = client.subscribe::("talker").await?; @@ -70,3 +65,8 @@ async fn main() -> Result<(), anyhow::Error> { } } } + +#[cfg(not(feature = "rosbridge"))] +fn main() { + eprintln!("This example does nothing without compiling with the feature 'rosbridge'"); +} diff --git a/roslibrust/examples/native_ros1.rs b/roslibrust/examples/native_ros1.rs deleted file mode 100644 index 7a9518be..00000000 --- a/roslibrust/examples/native_ros1.rs +++ /dev/null @@ -1,31 +0,0 @@ -/** - * Testing ground for hitting on rosmaster directly - */ - -#[cfg(feature = "ros1")] -#[tokio::main] -async fn main() -> Result<(), anyhow::Error> { - use roslibrust::ros1::NodeHandle; - - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // required for running wsl2 - .init() - .unwrap(); - - let _nh = NodeHandle::new("http://localhost:11311", "native_ros1").await?; - - // Work to do: - // * [DONE] Take the ros MasterApi and create valid in/out types for each api call - // * [DONE] Build out a test suite for the materapi - // * Build out a host for the slaveapi (maybe skip some features if we can? stats?) - // * Build out a test against our own slaveapi (maybe skip some features if we can? stats?) - // * Actually make a connection with TCPROS - - Ok(()) -} - -#[cfg(not(feature = "ros1"))] -fn main() { - // Provide a dummy main for this example when ros1 is disabled -} diff --git a/roslibrust/examples/ros1_listener.rs b/roslibrust/examples/ros1_listener.rs index 08e92fdb..75e279bc 100644 --- a/roslibrust/examples/ros1_listener.rs +++ b/roslibrust/examples/ros1_listener.rs @@ -1,15 +1,12 @@ +#[cfg(feature = "ros1")] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces/std_msgs"); #[cfg(feature = "ros1")] #[tokio::main] -async fn main() -> Result<(), anyhow::Error> { +async fn main() -> Result<(), Box> { use roslibrust::ros1::NodeHandle; - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() - .init() - .unwrap(); + env_logger::init(); let nh = NodeHandle::new("http://localhost:11311", "listener_rs").await?; let mut subscriber = nh.subscribe::("/chatter", 1).await?; diff --git a/roslibrust/examples/ros1_publish_any.rs b/roslibrust/examples/ros1_publish_any.rs index cc5db23a..5915de2d 100644 --- a/roslibrust/examples/ros1_publish_any.rs +++ b/roslibrust/examples/ros1_publish_any.rs @@ -1,3 +1,4 @@ +#[cfg(feature = "ros1")] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); /// This example demonstrates ths usage of the .advertise_any() function @@ -8,7 +9,7 @@ roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_in #[cfg(feature = "ros1")] #[tokio::main] -async fn main() -> Result<(), anyhow::Error> { +async fn main() -> Result<(), Box> { // Note: this example needs a ros master running to work let node = roslibrust::ros1::NodeHandle::new("http://localhost:11311", "/ros1_publish_any").await?; diff --git a/roslibrust/examples/ros1_ros2_bridge_example.rs b/roslibrust/examples/ros1_ros2_bridge_example.rs index d2c5232a..48634147 100644 --- a/roslibrust/examples/ros1_ros2_bridge_example.rs +++ b/roslibrust/examples/ros1_ros2_bridge_example.rs @@ -2,9 +2,6 @@ //! both ROS1 types and ROS2 types, can use two clients to communicate //! with both versions of ROS at the same time. -use log::*; -use roslibrust::ClientHandle; - /// We place the ros1 generate code into a module to prevent name collisions with the identically /// named ros2 types. mod ros1 { @@ -52,14 +49,12 @@ mod ros2 { /// After both bridges are up and running, run this example. /// With this example running you should then be able to use the ros1 command line tools to publish a message, /// and see them appear in ros2 with its command line tools +#[cfg(feature = "rosbridge")] #[tokio::main(flavor = "multi_thread")] -async fn main() -> Result<(), anyhow::Error> { - // Initialize a basic logger useful if anything goes wrong while running the example - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // Required for running in wsl2 - .init() - .unwrap(); +async fn main() -> Result<(), Box> { + use log::*; + use roslibrust::rosbridge::ClientHandle; + env_logger::init(); info!("Attempting to connect to ros1..."); let ros1_client = ClientHandle::new("ws://localhost:9090").await?; @@ -101,3 +96,8 @@ async fn main() -> Result<(), anyhow::Error> { Ok(()) } + +#[cfg(not(feature = "rosbridge"))] +fn main() { + eprintln!("This example does nothing without compiling with the feature 'rosbridge'"); +} diff --git a/roslibrust/examples/ros1_service_client.rs b/roslibrust/examples/ros1_service_client.rs index 27074fbe..f13fdd24 100644 --- a/roslibrust/examples/ros1_service_client.rs +++ b/roslibrust/examples/ros1_service_client.rs @@ -1,15 +1,12 @@ +#[cfg(feature = "ros1")] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); #[cfg(feature = "ros1")] #[tokio::main] -async fn main() -> Result<(), anyhow::Error> { +async fn main() -> Result<(), Box> { use roslibrust::ros1::NodeHandle; - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() - .init() - .unwrap(); + env_logger::init(); let nh = NodeHandle::new("http://localhost:11311", "service_client_rs").await?; log::info!("Connected!"); diff --git a/roslibrust/examples/ros1_service_server.rs b/roslibrust/examples/ros1_service_server.rs index 016f826f..0b658dbd 100644 --- a/roslibrust/examples/ros1_service_server.rs +++ b/roslibrust/examples/ros1_service_server.rs @@ -1,17 +1,14 @@ +#[cfg(feature = "ros1")] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); #[cfg(feature = "ros1")] #[tokio::main] -async fn main() -> Result<(), anyhow::Error> { +async fn main() -> Result<(), Box> { use log::*; use roslibrust::ros1::NodeHandle; use std::sync::{Arc, Mutex}; - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() - .init() - .unwrap(); + env_logger::init(); let nh = NodeHandle::new("http://localhost:11311", "service_server_rs").await?; log::info!("Connected!"); diff --git a/roslibrust/examples/ros1_talker.rs b/roslibrust/examples/ros1_talker.rs index b57613e4..800055af 100644 --- a/roslibrust/examples/ros1_talker.rs +++ b/roslibrust/examples/ros1_talker.rs @@ -1,15 +1,12 @@ +#[cfg(feature = "ros1")] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); #[cfg(feature = "ros1")] #[tokio::main] -async fn main() -> Result<(), anyhow::Error> { +async fn main() -> Result<(), Box> { use roslibrust::ros1::NodeHandle; - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // required for running wsl2 - .init() - .unwrap(); + env_logger::init(); let nh = NodeHandle::new("http://localhost:11311", "talker_rs") .await diff --git a/roslibrust/examples/service_server.rs b/roslibrust/examples/service_server.rs index aa3ad45c..cb3fc5ef 100644 --- a/roslibrust/examples/service_server.rs +++ b/roslibrust/examples/service_server.rs @@ -1,10 +1,10 @@ -use roslibrust::ClientHandle; - // One way to import message definitions: +#[cfg(feature = "rosbridge")] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); // A basic service server exampple, that logs the request is recieves and returns // a canned response. +#[cfg(feature = "rosbridge")] fn my_service( request: std_srvs::SetBoolRequest, my_string: &str, @@ -39,17 +39,13 @@ fn my_service( /// /// To actually exercise our service we need to call it with something. /// One option would be to use a ros commaline tool: `rosservice call /my_set_bool "data: false"` or `ros2 service call /my_set_bool std_srvs/srv/SetBool data:\ false\ `. +#[cfg(feature = "rosbridge")] #[tokio::main(flavor = "multi_thread")] -async fn main() -> Result<(), anyhow::Error> { - // Initialize a basic logger useful if anything goes wrong while running the example - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // Required for running in wsl2 - .init() - .unwrap(); +async fn main() -> Result<(), Box> { + env_logger::init(); // Create a new client - let client = ClientHandle::new("ws://localhost:9090").await?; + let client = roslibrust::rosbridge::ClientHandle::new("ws://localhost:9090").await?; // The string you want to pass in to the closure let my_string = "Some string"; @@ -71,3 +67,8 @@ async fn main() -> Result<(), anyhow::Error> { tokio::signal::ctrl_c().await?; Ok(()) } + +#[cfg(not(feature = "rosbridge"))] +fn main() { + eprintln!("This example does nothing without compiling with the feature 'rosbridge'"); +} diff --git a/roslibrust/examples/subscribe_and_log.rs b/roslibrust/examples/subscribe_and_log.rs index 35296bd3..d2651037 100644 --- a/roslibrust/examples/subscribe_and_log.rs +++ b/roslibrust/examples/subscribe_and_log.rs @@ -1,20 +1,16 @@ -use log::*; -use roslibrust::ClientHandle; - +#[cfg(feature = "rosbridge")] roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); /// A basic example of connecting and subscribing to data. /// This example will log received messages if run at the same time as "basic_publisher". /// A running rosbridge websocket server at the default port (9090) is required to run this example. +#[cfg(feature = "rosbridge")] #[tokio::main] -async fn main() -> Result<(), anyhow::Error> { - simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() // required for running in wsl2 - .init() - .unwrap(); +async fn main() -> Result<(), Box> { + use log::*; + env_logger::init(); - let client = ClientHandle::new("ws://localhost:9090").await?; + let client = roslibrust::rosbridge::ClientHandle::new("ws://localhost:9090").await?; info!("ClientHandle connected"); let rx = client.subscribe::("talker").await?; @@ -25,3 +21,8 @@ async fn main() -> Result<(), anyhow::Error> { info!("Got msg: {:?}", msg); } } + +#[cfg(not(feature = "rosbridge"))] +fn main() { + eprintln!("This example does nothing without compiling with the feature 'rosbridge'"); +} diff --git a/roslibrust/src/lib.rs b/roslibrust/src/lib.rs index 3725c297..f2b48e18 100644 --- a/roslibrust/src/lib.rs +++ b/roslibrust/src/lib.rs @@ -98,9 +98,6 @@ //! Specifically, roslibrust attempts to follow "good" ros error handling convention and be as compatible as possible //! with various error types; however, due to the async nature of the crate `Box` is needed. -mod rosbridge; -pub use rosbridge::*; - // Re-export common types and traits under the roslibrust namespace pub use roslibrust_common::*; @@ -110,3 +107,15 @@ pub mod rosapi; // If the ros1 feature is enabled, export the roslibrust_ros1 crate under ros1 #[cfg(feature = "ros1")] pub use roslibrust_ros1 as ros1; + +// If the rosbridge feature is enabled, export the roslibrust_rosbridge crate under rosbridge +#[cfg(feature = "rosbridge")] +pub use roslibrust_rosbridge as rosbridge; + +// If the zenoh feature is enabled, export the roslibrust_zenoh crate under zenoh +#[cfg(feature = "zenoh")] +pub use roslibrust_zenoh as zenoh; + +// If the mock feature is enabled, export the roslibrust_mock crate under mock +#[cfg(feature = "mock")] +pub use roslibrust_mock as mock; diff --git a/roslibrust_ros1/tests/ros1_native_integration_tests.rs b/roslibrust/src/tests/ros1_native_integration_tests.rs similarity index 100% rename from roslibrust_ros1/tests/ros1_native_integration_tests.rs rename to roslibrust/src/tests/ros1_native_integration_tests.rs diff --git a/roslibrust_mock/Cargo.toml b/roslibrust_mock/Cargo.toml index 61b241d7..d37457f7 100644 --- a/roslibrust_mock/Cargo.toml +++ b/roslibrust_mock/Cargo.toml @@ -4,7 +4,7 @@ version = "0.1.0" edition = "2021" [dependencies] -roslibrust = { path = "../roslibrust", features = ["topic_provider"] } +roslibrust_common = { path = "../roslibrust_common" } tokio = { version = "1.41", features = ["sync", "rt-multi-thread", "macros"] } # Used for serializing messages bincode = "1.3" @@ -12,8 +12,5 @@ bincode = "1.3" log = "0.4" [dev-dependencies] -# Ideally this shouldn't need to be here -roslibrust_common = { path = "../roslibrust_common" } -# Neither should this... roslibrust_codegen = { path = "../roslibrust_codegen" } roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } diff --git a/roslibrust_mock/src/lib.rs b/roslibrust_mock/src/lib.rs index b8f2ba4c..5342a663 100644 --- a/roslibrust_mock/src/lib.rs +++ b/roslibrust_mock/src/lib.rs @@ -1,13 +1,8 @@ use std::collections::BTreeMap; use std::sync::Arc; -use roslibrust::topic_provider::*; -use roslibrust::RosLibRustError; -use roslibrust::RosLibRustResult; -use roslibrust::RosMessageType; +use roslibrust_common::*; -use roslibrust::RosServiceType; -use roslibrust::ServiceFn; use tokio::sync::broadcast as Channel; use tokio::sync::RwLock; diff --git a/roslibrust_rosbridge/Cargo.toml b/roslibrust_rosbridge/Cargo.toml new file mode 100644 index 00000000..23c633d2 --- /dev/null +++ b/roslibrust_rosbridge/Cargo.toml @@ -0,0 +1,36 @@ +[package] +name = "roslibrust_rosbridge" +version = "0.1.0" +edition = "2021" + +[dependencies] +roslibrust_common = { path = "../roslibrust_common" } +tokio = { version = "1.20", features = [ + "net", + "macros", + "time", + "rt-multi-thread", + "sync", +] } +tokio-tungstenite = { version = "0.17" } +uuid = { version = "1.1", features = ["v4"] } +log = "0.4" +serde_json = "1.0" +anyhow = "1.0" +futures = "0.3" +futures-util = "0.3" +dashmap = "5.3" +deadqueue = "0.2.4" # .4+ is required to fix bug with missing tokio dep + +[dev-dependencies] +test-log = "0.2" +roslibrust_codegen = { path = "../roslibrust_codegen" } +roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } + +[features] +# Used to enable tests that rely on a locally running rosbridge +running_bridge = [] +# Indicates we're testing with running ROS1 bridge +ros1_test = ["running_bridge"] +# Indicates we're testing with running ROS2 bridge +ros2_test = ["running_bridge"] diff --git a/roslibrust/src/rosbridge/client.rs b/roslibrust_rosbridge/src/client.rs similarity index 96% rename from roslibrust/src/rosbridge/client.rs rename to roslibrust_rosbridge/src/client.rs index a4e4b43e..f629b688 100644 --- a/roslibrust/src/rosbridge/client.rs +++ b/roslibrust_rosbridge/src/client.rs @@ -1,13 +1,11 @@ -use crate::{ - rosbridge::comm::{self, RosBridgeComm}, - Publisher, RosLibRustError, RosLibRustResult, ServiceHandle, Subscriber, -}; +use crate::comm::Ops; +use crate::comm::RosBridgeComm; +use crate::{Publisher, ServiceHandle, Subscriber}; use anyhow::anyhow; use dashmap::DashMap; use futures::StreamExt; use log::*; -use roslibrust_common::ServiceFn; -use roslibrust_common::{RosMessageType, RosServiceType}; +use roslibrust_common::*; use serde_json::Value; use std::collections::HashMap; use std::str::FromStr; @@ -60,7 +58,7 @@ impl ClientHandleOptions { /// # #[tokio::main] /// # async fn main() -> Result<(), Box> { /// // Create a new client -/// let mut handle = roslibrust::ClientHandle::new("ws://localhost:9090").await?; +/// let mut handle = roslibrust_rosbridge::ClientHandle::new("ws://localhost:9090").await?; /// // Create a copy of the handle (does not create a seperate connection) /// let mut handle2 = handle.clone(); /// tokio::spawn(async move { @@ -206,11 +204,11 @@ impl ClientHandle { /// # #[tokio::main] /// # async fn main() -> Result<(), Box> { /// // Create a new client - /// let mut handle = roslibrust::ClientHandle::new("ws://localhost:9090").await?; + /// let mut handle = roslibrust_rosbridge::ClientHandle::new("ws://localhost:9090").await?; /// // Subscribe using :: style /// let subscriber1 = handle.subscribe::("/topic").await?; /// // Subscribe using explicit type style - /// let subscriber2: roslibrust::Subscriber = handle.subscribe::("/topic").await?; + /// let subscriber2: roslibrust_rosbridge::Subscriber = handle.subscribe("/topic").await?; /// # Ok(()) /// # } /// ``` @@ -239,7 +237,7 @@ impl ClientHandle { /// # #[tokio::main] /// # async fn main() -> Result<(), Box> { /// // Create a new client - /// let mut handle = roslibrust::ClientHandle::new("ws://localhost:9090").await?; + /// let mut handle = roslibrust_rosbridge::ClientHandle::new("ws://localhost:9090").await?; /// // Subscribe to the same topic with two different types /// let ros1_subscriber = handle.subscribe::("/topic").await?; /// let ros2_subscriber = handle.subscribe::("/topic").await?; @@ -297,11 +295,11 @@ impl ClientHandle { /// # #[tokio::main] /// # async fn main() -> Result<(), Box> { /// // Create a new client - /// let mut handle = roslibrust::ClientHandle::new("ws://localhost:9090").await?; + /// let mut handle = roslibrust_rosbridge::ClientHandle::new("ws://localhost:9090").await?; /// // Advertise using :: style /// let mut publisher = handle.advertise::("/topic").await?; /// // Advertise using explicit type - /// let mut publisher2: roslibrust::Publisher = handle.advertise("/other_topic").await?; + /// let mut publisher2: roslibrust_rosbridge::Publisher = handle.advertise("/other_topic").await?; /// # Ok(()) /// # } /// ``` @@ -349,7 +347,7 @@ impl ClientHandle { /// # #[tokio::main] /// # async fn main() -> Result<(), Box> { /// // Create a new client - /// let mut handle = roslibrust::ClientHandle::new("ws://localhost:9090").await?; + /// let mut handle = roslibrust_rosbridge::ClientHandle::new("ws://localhost:9090").await?; /// // Call service, type of response will be rosapi::GetTimeResponse (alternatively named rosapi::GetTime::Response) /// let response = handle.call_service::("/rosapi/get_time", rosapi::GetTimeRequest{}).await?; /// # Ok(()) @@ -615,17 +613,17 @@ impl Client { .expect("Op field not present on returned object.") .as_str() .expect("Op field was not of string type."); - let op = comm::Ops::from_str(op)?; + let op = Ops::from_str(op)?; match op { - comm::Ops::Publish => { + Ops::Publish => { trace!("handling publish for {:?}", &parsed); self.handle_publish(parsed).await; } - comm::Ops::ServiceResponse => { + Ops::ServiceResponse => { trace!("handling service response for {:?}", &parsed); self.handle_response(parsed).await; } - comm::Ops::CallService => { + Ops::CallService => { trace!("handling call_service for {:?}", &parsed); self.handle_service(parsed).await; } diff --git a/roslibrust/src/rosbridge/comm.rs b/roslibrust_rosbridge/src/comm.rs similarity index 99% rename from roslibrust/src/rosbridge/comm.rs rename to roslibrust_rosbridge/src/comm.rs index 8a52c470..d5826f11 100644 --- a/roslibrust/src/rosbridge/comm.rs +++ b/roslibrust_rosbridge/src/comm.rs @@ -1,4 +1,4 @@ -use crate::{rosbridge::Writer, RosLibRustResult}; +use crate::{RosLibRustResult, Writer}; use anyhow::bail; use futures_util::SinkExt; use log::debug; diff --git a/roslibrust/src/rosbridge/integration_tests.rs b/roslibrust_rosbridge/src/integration_tests.rs similarity index 98% rename from roslibrust/src/rosbridge/integration_tests.rs rename to roslibrust_rosbridge/src/integration_tests.rs index df06d94c..80857911 100644 --- a/roslibrust/src/rosbridge/integration_tests.rs +++ b/roslibrust_rosbridge/src/integration_tests.rs @@ -11,9 +11,7 @@ mod integration_tests { use std::sync::Arc; - use crate::{ - rosbridge::TestResult, ClientHandle, ClientHandleOptions, RosLibRustError, Subscriber, - }; + use crate::{ClientHandle, ClientHandleOptions, RosLibRustError, Subscriber, TestResult}; use log::debug; use tokio::time::{timeout, Duration}; // On my laptop test was ~90% reliable at 10ms @@ -177,11 +175,6 @@ mod integration_tests { // of advertise / unadvertise status. Unclear how to confirm whether unadvertise was sent or not #[ignore] async fn unadvertise() -> TestResult { - let _ = simple_logger::SimpleLogger::new() - .with_level(log::LevelFilter::Debug) - .without_timestamps() - .init(); - // Flow: // 1. Create a publisher and subscriber // 2. Send a message and confirm connection works (topic was advertised) diff --git a/roslibrust/src/rosbridge/mod.rs b/roslibrust_rosbridge/src/lib.rs similarity index 95% rename from roslibrust/src/rosbridge/mod.rs rename to roslibrust_rosbridge/src/lib.rs index e381b8fa..302b1e9d 100644 --- a/roslibrust/src/rosbridge/mod.rs +++ b/roslibrust_rosbridge/src/lib.rs @@ -1,4 +1,5 @@ use roslibrust_common::*; + // Subscriber is a transparent module, we directly expose internal types // Module exists only to organize source code. mod subscriber; @@ -31,10 +32,6 @@ use tokio::net::TcpStream; use tokio_tungstenite::*; use tungstenite::Message; -// Doing this to maintain backwards compatibilities like `use roslibrust::rosbridge::RosLibRustError` -#[allow(unused)] -pub use roslibrust_common::{RosLibRustError, RosLibRustResult}; - /// Used for type erasure of message type so that we can store arbitrary handles type Callback = Box; @@ -144,15 +141,15 @@ impl ServiceProvider for crate::ClientHandle { self.service_client::(topic).await } - fn advertise_service( + async fn advertise_service( &self, topic: &str, server: F, - ) -> impl futures::Future> + Send + ) -> RosLibRustResult where F: ServiceFn, { - self.advertise_service(topic, server) + self.advertise_service(topic, server).await } } diff --git a/roslibrust/src/rosbridge/publisher.rs b/roslibrust_rosbridge/src/publisher.rs similarity index 100% rename from roslibrust/src/rosbridge/publisher.rs rename to roslibrust_rosbridge/src/publisher.rs diff --git a/roslibrust/src/rosbridge/subscriber.rs b/roslibrust_rosbridge/src/subscriber.rs similarity index 98% rename from roslibrust/src/rosbridge/subscriber.rs rename to roslibrust_rosbridge/src/subscriber.rs index 791b6b54..f0172fda 100644 --- a/roslibrust/src/rosbridge/subscriber.rs +++ b/roslibrust_rosbridge/src/subscriber.rs @@ -5,7 +5,7 @@ use log::error; use std::sync::Arc; -use crate::{rosbridge::MessageQueue, ClientHandle}; +use crate::{ClientHandle, MessageQueue}; use roslibrust_common::RosMessageType; /// Represents a single instance of listening to a topic, and provides the ability to extract messages diff --git a/roslibrust_zenoh/examples/service_call.rs b/roslibrust_zenoh/examples/zenoh_service_call.rs similarity index 100% rename from roslibrust_zenoh/examples/service_call.rs rename to roslibrust_zenoh/examples/zenoh_service_call.rs diff --git a/roslibrust_zenoh/examples/service_server.rs b/roslibrust_zenoh/examples/zenoh_service_server.rs similarity index 100% rename from roslibrust_zenoh/examples/service_server.rs rename to roslibrust_zenoh/examples/zenoh_service_server.rs From 0769b61e755d01beca7915f0ded3a92b10c3bd18 Mon Sep 17 00:00:00 2001 From: carter Date: Tue, 17 Dec 2024 11:39:07 -0700 Subject: [PATCH 07/14] Rosapi moved to own crate --- Cargo.lock | 12 + Cargo.toml | 1 + roslibrust/src/rosapi/mod.rs | 544 ----------------------- roslibrust_common/src/topic_provider.rs | 15 + roslibrust_ros1/src/lib.rs | 10 + roslibrust_rosapi/Cargo.toml | 22 + roslibrust_rosapi/README.md | 7 + roslibrust_rosapi/src/lib.rs | 555 ++++++++++++++++++++++++ roslibrust_rosbridge/src/lib.rs | 8 + 9 files changed, 630 insertions(+), 544 deletions(-) create mode 100644 roslibrust_rosapi/Cargo.toml create mode 100644 roslibrust_rosapi/README.md create mode 100644 roslibrust_rosapi/src/lib.rs diff --git a/Cargo.lock b/Cargo.lock index 971199e0..e68240fa 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -2666,6 +2666,18 @@ dependencies = [ "tokio", ] +[[package]] +name = "roslibrust_rosapi" +version = "0.1.0" +dependencies = [ + "roslibrust_codegen", + "roslibrust_codegen_macro", + "roslibrust_common", + "roslibrust_rosbridge", + "test-log", + "tokio", +] + [[package]] name = "roslibrust_rosbridge" version = "0.1.0" diff --git a/Cargo.toml b/Cargo.toml index d182b7c6..30516368 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -13,5 +13,6 @@ members = [ "roslibrust_test", "roslibrust_zenoh", "roslibrust", + "roslibrust_rosapi", ] resolver = "2" diff --git a/roslibrust/src/rosapi/mod.rs b/roslibrust/src/rosapi/mod.rs index d7d078d3..8b137891 100644 --- a/roslibrust/src/rosapi/mod.rs +++ b/roslibrust/src/rosapi/mod.rs @@ -1,545 +1 @@ -//! This module is intended to provide a convenience wrapper around the capabilities -//! provided by the [rosapi](http://wiki.ros.org/rosapi) node. -//! -//! Ensure rosapi is running on your target system before attempting to utilize these features! -use crate::{ClientHandle, RosLibRustResult}; - -// TODO major issue here for folks who actually try to use rosapi in their project -// This macro isn't going to expand correctly when not used from this crate's workspace -// We almost certainly need to generate and commit the resulting messages, or -// do some include_str!() hax to be able to ship these types with the crate... -roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces/rosapi"); - -/// Represents the ability to interact with the interfaces provided by the rosapi node. -/// This trait is implemented for ClientHandle when the `rosapi` feature is enabled. -trait RosApi { - async fn get_time(&self) -> RosLibRustResult; - async fn topics(&self) -> RosLibRustResult; - async fn get_topic_type( - &self, - topic: impl Into + Send, - ) -> RosLibRustResult; - async fn get_topics_for_type( - &self, - topic_type: impl Into + Send, - ) -> RosLibRustResult; - async fn get_nodes(&self) -> RosLibRustResult; - - async fn get_node_details( - &self, - node: impl Into + Send, - ) -> RosLibRustResult; - - async fn get_node_for_service( - &self, - service: impl Into + Send, - ) -> RosLibRustResult; - - async fn set_param( - &self, - param_name: impl Into + Send, - param_value: impl Into + Send, - ) -> RosLibRustResult; - - async fn get_param( - &self, - param_name: impl Into + Send, - ) -> RosLibRustResult; - - async fn get_param_names(&self) -> RosLibRustResult; - - async fn has_param( - &self, - param: impl Into + Send, - ) -> RosLibRustResult; - - async fn delete_param( - &self, - name: impl Into + Send, - ) -> RosLibRustResult; - - async fn message_details( - &self, - message_name: impl Into + Send, - ) -> RosLibRustResult; - - async fn publishers( - &self, - topic: impl Into + Send, - ) -> RosLibRustResult; - - async fn service_host( - &self, - service: impl Into + Send, - ) -> RosLibRustResult; - - async fn service_providers( - &self, - service_type: impl Into + Send, - ) -> RosLibRustResult; - - async fn get_service_request_details( - &self, - service_type: impl Into + Send, - ) -> RosLibRustResult; - - async fn get_service_response_details( - &self, - service_type: impl Into + Send, - ) -> RosLibRustResult; - - async fn get_service_type( - &self, - service_name: impl Into + Send, - ) -> RosLibRustResult; - - async fn get_services(&self) -> RosLibRustResult; -} - -impl RosApi for ClientHandle { - /// Get the current time - async fn get_time(&self) -> RosLibRustResult { - self.call_service::("/rosapi/get_time", rosapi::GetTimeRequest {}) - .await - } - - /// Get the list of topics active - async fn topics(&self) -> RosLibRustResult { - self.call_service::("/rosapi/topics", rosapi::TopicsRequest {}) - .await - } - - /// Get the type of a given topic - async fn get_topic_type( - &self, - topic: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/topic_type", - rosapi::TopicTypeRequest { - topic: topic.into(), - }, - ) - .await - } - - /// Returns a list of the topics active in the system that are of the type provided - async fn get_topics_for_type( - &self, - topic_type: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/topics_for_type", - rosapi::TopicsForTypeRequest { - r#type: topic_type.into(), - }, - ) - .await - } - - /// Returns list of nodes active in a system - async fn get_nodes(&self) -> RosLibRustResult { - self.call_service::("/rosapi/nodes", rosapi::NodesRequest {}) - .await - } - - /// Returns the subscriptions, publishers, and service servers for a given node - /// @param node Fully resolved ros node name e.g. "/rosapi", should match the names given by `rosnode list` - async fn get_node_details( - &self, - node: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/node_details", - rosapi::NodeDetailsRequest { node: node.into() }, - ) - .await - } - - /// Given the name of service, get the name of the node that is providing that service - async fn get_node_for_service( - &self, - service: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/service_node", - rosapi::ServiceNodeRequest { - service: service.into(), - }, - ) - .await - } - - /// Sets a parameter. Unclear exactly how 'types' of parameters will be handled here. - /// For now we're simply converting into a string. - async fn set_param( - &self, - param_name: impl Into + Send, - param_value: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/set_param", - rosapi::SetParamRequest { - name: param_name.into(), - value: param_value.into(), - }, - ) - .await - } - - /// Gets the current value for a parameter. - /// Not handling any type safety or conversion. - async fn get_param( - &self, - param_name: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/get_param", - rosapi::GetParamRequest { - name: param_name.into(), - default: "".to_string(), - }, - ) - .await - } - - /// Gets the list of currently known parameters. - async fn get_param_names(&self) -> RosLibRustResult { - self.call_service::( - "/rosapi/get_param_names", - rosapi::GetParamNamesRequest {}, - ) - .await - } - - /// Checks whether the given parameter is defined. - async fn has_param( - &self, - param: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/has_param", - rosapi::HasParamRequest { name: param.into() }, - ) - .await - } - - /// Deletes a parameter by name. - async fn delete_param( - &self, - name: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/delete_param", - rosapi::DeleteParamRequest { name: name.into() }, - ) - .await - } - - /// Returns detailed information about a given message type e.g. 'std_msgs/Header' - async fn message_details( - &self, - message_name: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/message_details", - rosapi::MessageDetailsRequest { - r#type: message_name.into(), - }, - ) - .await - } - - /// Gets a list of all nodes that are publishing to a given topic. - async fn publishers( - &self, - topic: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/publishers", - rosapi::PublishersRequest { - topic: topic.into(), - }, - ) - .await - } - - /// Give the name of a service, returns the name of the machine on which that service is being hosted - async fn service_host( - &self, - service: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/service_host", - rosapi::ServiceHostRequest { - service: service.into(), - }, - ) - .await - } - - /// Given the type of a service, returns a list of nodes which are providing services with that type - async fn service_providers( - &self, - service_type: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/service_providers", - rosapi::ServiceProvidersRequest { - service: service_type.into(), - }, - ) - .await - } - - /// Given the type of a service (e.g. 'rosapi/SetParam'), returns details about the message format of the request - async fn get_service_request_details( - &self, - service_type: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/service_request_details", - rosapi::ServiceRequestDetailsRequest { - r#type: service_type.into(), - }, - ) - .await - } - - /// Given the type of a service (e.g. 'rosapi/SetParam'), returns details about the message format of the response - async fn get_service_response_details( - &self, - service_type: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/service_response_details", - rosapi::ServiceRequestDetailsRequest { - r#type: service_type.into(), - }, - ) - .await - } - - /// Given the name of a service (e.g. '/rosapi/publishers'), returns the type of the service ('rosapi/Publishers') - async fn get_service_type( - &self, - service_name: impl Into + Send, - ) -> RosLibRustResult { - self.call_service::( - "/rosapi/service_type", - rosapi::ServiceTypeRequest { - service: service_name.into(), - }, - ) - .await - } - - /// Get the list of services active on the system - async fn get_services(&self) -> RosLibRustResult { - self.call_service::("/rosapi/services", rosapi::ServicesRequest {}) - .await - } - - /* - List of rosapi services pulled from `rosservice list` - /rosapi/action_servers - Probably won't support - /rosapi/delete_param - Done - /rosapi/get_loggers - ?? - /rosapi/get_param - Done - /rosapi/get_param_names - Done - /rosapi/get_time - Done - /rosapi/has_param - Done - /rosapi/message_details - Done - /rosapi/node_details - Done - /rosapi/nodes - Done - /rosapi/publishers - Done - /rosapi/search_param - ?? What does this do and why? - /rosapi/service_host - Done - /rosapi/service_node - Done - /rosapi/service_providers - Done - /rosapi/service_request_details - Done - /rosapi/service_response_details - Done - /rosapi/service_type - Done - /rosapi/services - TODO - /rosapi/services_for_type - Done - /rosapi/set_logger_level - ?? - /rosapi/set_param - Done - /rosapi/subscribers - Done - /rosapi/topic_type - Done - /rosapi/topics - Done - /rosapi/topics_and_raw_types - ?? - /rosapi/topics_for_type - Done - */ -} - -#[cfg(test)] -#[cfg(feature = "running_bridge")] -// TODO currently rosapi only supports ros1, we should try to figure out a way to fix that -// ros1api and ros2api may make sense as their own crates? -#[cfg(feature = "ros1_test")] -mod test { - use super::RosApi; - use crate::{ClientHandle, ClientHandleOptions}; - - async fn fixture_client() -> ClientHandle { - // Tiny sleep to throttle rate at which tests are run to try to make CI more consistent - tokio::time::sleep(std::time::Duration::from_millis(50)).await; - let opts = ClientHandleOptions::new("ws://localhost:9090") - // 200 ms failed CI - .timeout(std::time::Duration::from_millis(500)); - ClientHandle::new_with_options(opts).await.unwrap() - } - - #[test_log::test(tokio::test)] - async fn rosapi_get_time() { - let api = fixture_client().await; - api.get_time().await.unwrap(); - } - - #[test_log::test(tokio::test)] - async fn rosapi_get_topic_type() { - let api = fixture_client().await; - let res = api - .get_topic_type("/rosout") - .await - .expect("Failed to get topic type for rosout"); - assert_eq!(res.r#type, "rosgraph_msgs/Log"); - } - - #[test_log::test(tokio::test)] - async fn rosapi_get_topics_for_type() { - let api = fixture_client().await; - let res = api - .get_topics_for_type("rosgraph_msgs/Log") - .await - .expect("Failed to get topics for type Log"); - assert!(res.topics.iter().any(|f| f == "/rosout")); - } - - #[test_log::test(tokio::test)] - async fn rosapi_get_nodes() { - let api = fixture_client().await; - let nodes = api.get_nodes().await.expect("Failed to get nodes"); - assert!(nodes.nodes.iter().any(|f| f == "/rosapi")); - } - - #[test_log::test(tokio::test)] - async fn rosapi_get_node_details() { - let api = fixture_client().await; - assert!( - api.get_node_details("/rosapi") - .await - .expect("Failed to get node details for rosapi") - .services - .len() - > 0 - ); - } - - #[test_log::test(tokio::test)] - async fn rosapi_get_node_for_service() { - let api = fixture_client().await; - assert_eq!( - api.get_node_for_service("/rosapi/service_node") - .await - .expect("Failed to call service_node") - .node, - "/rosapi" - ); - } - - #[test_log::test(tokio::test)] - async fn rosapi_param_roundtrip() { - let api = fixture_client().await; - const PARAM_NAME: &'static str = "/rosapi_param_roundtrip"; - // Set the parameter - api.set_param(PARAM_NAME, 1.0.to_string()) - .await - .expect("Failed to set"); - - // read back the value we set - let response = api - .get_param(PARAM_NAME) - .await - .expect("Failed to read param back"); - assert_eq!(1.0, response.value.parse::().unwrap()); - - // Confirm the parameter is in the list of parameters - let param_names = api - .get_param_names() - .await - .expect("Failed to get param names"); - assert!(param_names.names.contains(&PARAM_NAME.to_string())); - - // Confirm has_param sees it - assert!(api.has_param(PARAM_NAME).await.unwrap().exists); - - // Delete it! - api.delete_param(PARAM_NAME).await.unwrap(); - - // Confirm it is gone - assert!(!api.has_param(PARAM_NAME).await.unwrap().exists); - } - - #[test_log::test(tokio::test)] - async fn rosapi_message_details() { - let api = fixture_client().await; - let response = api.message_details("std_msgs/Header").await.unwrap(); - // Spot check we actually got some data back - assert!(response - .typedefs - .iter() - .any(|t| t.fieldtypes.contains(&"time".to_string()))); - } - - #[test_log::test(tokio::test)] - async fn rosapi_publishers() { - let api = fixture_client().await; - let response = api.publishers("/rosout").await.unwrap(); - assert!(response.publishers.iter().any(|p| p == "/rosapi")); - } - - #[test_log::test(tokio::test)] - async fn rosapi_service_providers() { - let api = fixture_client().await; - let response = api.service_providers("rosapi/ServiceHost").await.unwrap(); - assert!(response.providers.iter().any(|p| p == "/rosapi")); - } - - #[test_log::test(tokio::test)] - async fn rosapi_service_request_details() { - let api = fixture_client().await; - let response = api - .get_service_request_details("rosapi/SetParam") - .await - .unwrap(); - // Spot check we got some data back - assert!(response.typedefs[0].fieldnames.len() == 2); - } - - #[test_log::test(tokio::test)] - async fn rosapi_service_response_details() { - let api = fixture_client().await; - let response = api - .get_service_response_details("rosapi/GetParam") - .await - .unwrap(); - // Spot check we got some data back - assert_eq!(response.typedefs[0].fieldnames[0], "value"); - } - - #[test_log::test(tokio::test)] - async fn rosapi_get_service_type() { - let api = fixture_client().await; - let response = api.get_service_type("/rosapi/node_details").await.unwrap(); - assert_eq!(response.r#type, "rosapi/NodeDetails"); - } - - #[test_log::test(tokio::test)] - async fn rosapi_services() { - let api = fixture_client().await; - let response = api.get_services().await.unwrap(); - assert!(!response.services.is_empty()); - } -} diff --git a/roslibrust_common/src/topic_provider.rs b/roslibrust_common/src/topic_provider.rs index eaac6b9e..aa6058eb 100644 --- a/roslibrust_common/src/topic_provider.rs +++ b/roslibrust_common/src/topic_provider.rs @@ -61,11 +61,26 @@ pub trait ServiceProvider { type ServiceClient: Service + Send + 'static; type ServiceServer; + /// A "oneshot" service call good for low frequency calls or where the service_provider may not always be available. + fn call_service( + &self, + topic: &str, + request: T::Request, + ) -> impl futures::Future> + Send; + + /// An optimized version of call_service that returns a persistent client that can be used to repeatedly call a service. + /// Depending on backend this may provide a performance benefit over call_service. + /// Dropping the returned client will perform all needed cleanup. fn service_client( &self, topic: &str, ) -> impl futures::Future>> + Send; + /// Advertise a service function to be available for clients to call. + /// A handle is returned that manages the lifetime of the service. + /// Dropping the handle will perform all needed cleanup. + /// The service will be active until the handle is dropped. + /// Currently this function only accepts non-async functions, but with the stabilization of async closures this may change. fn advertise_service( &self, topic: &str, diff --git a/roslibrust_ros1/src/lib.rs b/roslibrust_ros1/src/lib.rs index 4a94c6e4..66d2dfea 100644 --- a/roslibrust_ros1/src/lib.rs +++ b/roslibrust_ros1/src/lib.rs @@ -64,6 +64,16 @@ impl ServiceProvider for crate::NodeHandle { type ServiceClient = crate::ServiceClient; type ServiceServer = crate::ServiceServer; + async fn call_service( + &self, + topic: &str, + request: T::Request, + ) -> RosLibRustResult { + // TODO should have a more optimized version of this... + let client = self.service_client::(topic).await?; + client.call(&request).await + } + async fn service_client( &self, topic: &str, diff --git a/roslibrust_rosapi/Cargo.toml b/roslibrust_rosapi/Cargo.toml new file mode 100644 index 00000000..db92d830 --- /dev/null +++ b/roslibrust_rosapi/Cargo.toml @@ -0,0 +1,22 @@ +[package] +name = "roslibrust_rosapi" +version = "0.1.0" +edition = "2021" + +[dependencies] +# TODO shouldn't need to depend on codegen should be able to use _macro directly +roslibrust_codegen = { path = "../roslibrust_codegen" } +roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } +roslibrust_common = { path = "../roslibrust_common" } +# Note: this crate doesn't depend on any specific backend implementations +# but can work with any backend that implements the ServiceProvider trait and has a RosApi node running + +[dev-dependencies] +tokio = { version = "1.41" } +test-log = "0.2" +# Only backend we're currently testing with +roslibrust_rosbridge = { path = "../roslibrust_rosbridge" } + +[features] +# Used to indicate we're executing tests with a running ros1 rosapi node +ros1_test = [] \ No newline at end of file diff --git a/roslibrust_rosapi/README.md b/roslibrust_rosapi/README.md new file mode 100644 index 00000000..bc2bea0f --- /dev/null +++ b/roslibrust_rosapi/README.md @@ -0,0 +1,7 @@ +# roslibrust_rosapi + +Provides a trait representing the capabilities of the rosapi node. + +And provides implementations of that trait for roslibrust_ros1::NodeHandle and roslibrust_rosbridge::ClientHandle + +The future of this crate is a little uncertain given direction of the roslibrust project. diff --git a/roslibrust_rosapi/src/lib.rs b/roslibrust_rosapi/src/lib.rs new file mode 100644 index 00000000..409fd10a --- /dev/null +++ b/roslibrust_rosapi/src/lib.rs @@ -0,0 +1,555 @@ +//! This crate provides a convenience wrapper around the capabilities +//! provided by the [rosapi](http://wiki.ros.org/rosapi) node. +//! +//! Ensure rosapi is running on your target system before attempting to utilize these features! + +use roslibrust_common::topic_provider::ServiceProvider; +use roslibrust_common::RosLibRustResult; + +// TODO major issue here for folks who actually try to use rosapi in their project +// This macro isn't going to expand correctly when not used from this crate's workspace +// We almost certainly need to generate and commit the resulting messages, or +// do some include_str!() hax to be able to ship these types with the crate... +roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces/rosapi"); + +/// Represents the ability to interact with the interfaces provided by the rosapi node. +/// This trait is implemented for ClientHandle when the `rosapi` feature is enabled. +pub trait RosApi { + fn get_time( + &self, + ) -> impl std::future::Future> + Send; + fn topics( + &self, + ) -> impl std::future::Future> + Send; + fn get_topic_type( + &self, + topic: impl Into + Send, + ) -> impl std::future::Future> + Send; + fn get_topics_for_type( + &self, + topic_type: impl Into + Send, + ) -> impl std::future::Future> + Send; + fn get_nodes( + &self, + ) -> impl std::future::Future> + Send; + + fn get_node_details( + &self, + node: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn get_node_for_service( + &self, + service: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn set_param( + &self, + param_name: impl Into + Send, + param_value: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn get_param( + &self, + param_name: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn get_param_names( + &self, + ) -> impl std::future::Future> + Send; + + fn has_param( + &self, + param: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn delete_param( + &self, + name: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn message_details( + &self, + message_name: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn publishers( + &self, + topic: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn service_host( + &self, + service: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn service_providers( + &self, + service_type: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn get_service_request_details( + &self, + service_type: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn get_service_response_details( + &self, + service_type: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn get_service_type( + &self, + service_name: impl Into + Send, + ) -> impl std::future::Future> + Send; + + fn get_services( + &self, + ) -> impl std::future::Future> + Send; +} + +/// A Generic implementation of the RosApi trait for any type that implements ServiceProvider +/// Note, this will not work on ROS2 systems or systems without the rosapi node running. +impl RosApi for T { + /// Get the current time + async fn get_time(&self) -> RosLibRustResult { + self.call_service::("/rosapi/get_time", rosapi::GetTimeRequest {}) + .await + } + + /// Get the list of topics active + async fn topics(&self) -> RosLibRustResult { + self.call_service::("/rosapi/topics", rosapi::TopicsRequest {}) + .await + } + + /// Get the type of a given topic + async fn get_topic_type( + &self, + topic: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/topic_type", + rosapi::TopicTypeRequest { + topic: topic.into(), + }, + ) + .await + } + + /// Returns a list of the topics active in the system that are of the type provided + async fn get_topics_for_type( + &self, + topic_type: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/topics_for_type", + rosapi::TopicsForTypeRequest { + r#type: topic_type.into(), + }, + ) + .await + } + + /// Returns list of nodes active in a system + async fn get_nodes(&self) -> RosLibRustResult { + self.call_service::("/rosapi/nodes", rosapi::NodesRequest {}) + .await + } + + /// Returns the subscriptions, publishers, and service servers for a given node + /// @param node Fully resolved ros node name e.g. "/rosapi", should match the names given by `rosnode list` + async fn get_node_details( + &self, + node: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/node_details", + rosapi::NodeDetailsRequest { node: node.into() }, + ) + .await + } + + /// Given the name of service, get the name of the node that is providing that service + async fn get_node_for_service( + &self, + service: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/service_node", + rosapi::ServiceNodeRequest { + service: service.into(), + }, + ) + .await + } + + /// Sets a parameter. Unclear exactly how 'types' of parameters will be handled here. + /// For now we're simply converting into a string. + async fn set_param( + &self, + param_name: impl Into + Send, + param_value: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/set_param", + rosapi::SetParamRequest { + name: param_name.into(), + value: param_value.into(), + }, + ) + .await + } + + /// Gets the current value for a parameter. + /// Not handling any type safety or conversion. + async fn get_param( + &self, + param_name: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/get_param", + rosapi::GetParamRequest { + name: param_name.into(), + default: "".to_string(), + }, + ) + .await + } + + /// Gets the list of currently known parameters. + async fn get_param_names(&self) -> RosLibRustResult { + self.call_service::( + "/rosapi/get_param_names", + rosapi::GetParamNamesRequest {}, + ) + .await + } + + /// Checks whether the given parameter is defined. + async fn has_param( + &self, + param: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/has_param", + rosapi::HasParamRequest { name: param.into() }, + ) + .await + } + + /// Deletes a parameter by name. + async fn delete_param( + &self, + name: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/delete_param", + rosapi::DeleteParamRequest { name: name.into() }, + ) + .await + } + + /// Returns detailed information about a given message type e.g. 'std_msgs/Header' + async fn message_details( + &self, + message_name: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/message_details", + rosapi::MessageDetailsRequest { + r#type: message_name.into(), + }, + ) + .await + } + + /// Gets a list of all nodes that are publishing to a given topic. + async fn publishers( + &self, + topic: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/publishers", + rosapi::PublishersRequest { + topic: topic.into(), + }, + ) + .await + } + + /// Give the name of a service, returns the name of the machine on which that service is being hosted + async fn service_host( + &self, + service: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/service_host", + rosapi::ServiceHostRequest { + service: service.into(), + }, + ) + .await + } + + /// Given the type of a service, returns a list of nodes which are providing services with that type + async fn service_providers( + &self, + service_type: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/service_providers", + rosapi::ServiceProvidersRequest { + service: service_type.into(), + }, + ) + .await + } + + /// Given the type of a service (e.g. 'rosapi/SetParam'), returns details about the message format of the request + async fn get_service_request_details( + &self, + service_type: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/service_request_details", + rosapi::ServiceRequestDetailsRequest { + r#type: service_type.into(), + }, + ) + .await + } + + /// Given the type of a service (e.g. 'rosapi/SetParam'), returns details about the message format of the response + async fn get_service_response_details( + &self, + service_type: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/service_response_details", + rosapi::ServiceRequestDetailsRequest { + r#type: service_type.into(), + }, + ) + .await + } + + /// Given the name of a service (e.g. '/rosapi/publishers'), returns the type of the service ('rosapi/Publishers') + async fn get_service_type( + &self, + service_name: impl Into + Send, + ) -> RosLibRustResult { + self.call_service::( + "/rosapi/service_type", + rosapi::ServiceTypeRequest { + service: service_name.into(), + }, + ) + .await + } + + /// Get the list of services active on the system + async fn get_services(&self) -> RosLibRustResult { + self.call_service::("/rosapi/services", rosapi::ServicesRequest {}) + .await + } + + /* + List of rosapi services pulled from `rosservice list` + /rosapi/action_servers - Probably won't support + /rosapi/delete_param - Done + /rosapi/get_loggers - ?? + /rosapi/get_param - Done + /rosapi/get_param_names - Done + /rosapi/get_time - Done + /rosapi/has_param - Done + /rosapi/message_details - Done + /rosapi/node_details - Done + /rosapi/nodes - Done + /rosapi/publishers - Done + /rosapi/search_param - ?? What does this do and why? + /rosapi/service_host - Done + /rosapi/service_node - Done + /rosapi/service_providers - Done + /rosapi/service_request_details - Done + /rosapi/service_response_details - Done + /rosapi/service_type - Done + /rosapi/services - TODO + /rosapi/services_for_type - Done + /rosapi/set_logger_level - ?? + /rosapi/set_param - Done + /rosapi/subscribers - Done + /rosapi/topic_type - Done + /rosapi/topics - Done + /rosapi/topics_and_raw_types - ?? + /rosapi/topics_for_type - Done + */ +} + +#[cfg(test)] +#[cfg(feature = "ros1_test")] +mod test { + use super::RosApi; + use roslibrust_rosbridge::{ClientHandle, ClientHandleOptions}; + + async fn fixture_client() -> ClientHandle { + // Tiny sleep to throttle rate at which tests are run to try to make CI more consistent + tokio::time::sleep(std::time::Duration::from_millis(50)).await; + let opts = ClientHandleOptions::new("ws://localhost:9090") + // 200 ms failed CI + .timeout(std::time::Duration::from_millis(500)); + ClientHandle::new_with_options(opts).await.unwrap() + } + + #[test_log::test(tokio::test)] + async fn rosapi_get_time() { + let api = fixture_client().await; + api.get_time().await.unwrap(); + } + + #[test_log::test(tokio::test)] + async fn rosapi_get_topic_type() { + let api = fixture_client().await; + let res = api + .get_topic_type("/rosout") + .await + .expect("Failed to get topic type for rosout"); + assert_eq!(res.r#type, "rosgraph_msgs/Log"); + } + + #[test_log::test(tokio::test)] + async fn rosapi_get_topics_for_type() { + let api = fixture_client().await; + let res = api + .get_topics_for_type("rosgraph_msgs/Log") + .await + .expect("Failed to get topics for type Log"); + assert!(res.topics.iter().any(|f| f == "/rosout")); + } + + #[test_log::test(tokio::test)] + async fn rosapi_get_nodes() { + let api = fixture_client().await; + let nodes = api.get_nodes().await.expect("Failed to get nodes"); + assert!(nodes.nodes.iter().any(|f| f == "/rosapi")); + } + + #[test_log::test(tokio::test)] + async fn rosapi_get_node_details() { + let api = fixture_client().await; + assert!( + api.get_node_details("/rosapi") + .await + .expect("Failed to get node details for rosapi") + .services + .len() + > 0 + ); + } + + #[test_log::test(tokio::test)] + async fn rosapi_get_node_for_service() { + let api = fixture_client().await; + assert_eq!( + api.get_node_for_service("/rosapi/service_node") + .await + .expect("Failed to call service_node") + .node, + "/rosapi" + ); + } + + #[test_log::test(tokio::test)] + async fn rosapi_param_roundtrip() { + let api = fixture_client().await; + const PARAM_NAME: &'static str = "/rosapi_param_roundtrip"; + // Set the parameter + api.set_param(PARAM_NAME, 1.0.to_string()) + .await + .expect("Failed to set"); + + // read back the value we set + let response = api + .get_param(PARAM_NAME) + .await + .expect("Failed to read param back"); + assert_eq!(1.0, response.value.parse::().unwrap()); + + // Confirm the parameter is in the list of parameters + let param_names = api + .get_param_names() + .await + .expect("Failed to get param names"); + assert!(param_names.names.contains(&PARAM_NAME.to_string())); + + // Confirm has_param sees it + assert!(api.has_param(PARAM_NAME).await.unwrap().exists); + + // Delete it! + api.delete_param(PARAM_NAME).await.unwrap(); + + // Confirm it is gone + assert!(!api.has_param(PARAM_NAME).await.unwrap().exists); + } + + #[test_log::test(tokio::test)] + async fn rosapi_message_details() { + let api = fixture_client().await; + let response = api.message_details("std_msgs/Header").await.unwrap(); + // Spot check we actually got some data back + assert!(response + .typedefs + .iter() + .any(|t| t.fieldtypes.contains(&"time".to_string()))); + } + + #[test_log::test(tokio::test)] + async fn rosapi_publishers() { + let api = fixture_client().await; + let response = api.publishers("/rosout").await.unwrap(); + assert!(response.publishers.iter().any(|p| p == "/rosapi")); + } + + #[test_log::test(tokio::test)] + async fn rosapi_service_providers() { + let api = fixture_client().await; + let response = api.service_providers("rosapi/ServiceHost").await.unwrap(); + assert!(response.providers.iter().any(|p| p == "/rosapi")); + } + + #[test_log::test(tokio::test)] + async fn rosapi_service_request_details() { + let api = fixture_client().await; + let response = api + .get_service_request_details("rosapi/SetParam") + .await + .unwrap(); + // Spot check we got some data back + assert!(response.typedefs[0].fieldnames.len() == 2); + } + + #[test_log::test(tokio::test)] + async fn rosapi_service_response_details() { + let api = fixture_client().await; + let response = api + .get_service_response_details("rosapi/GetParam") + .await + .unwrap(); + // Spot check we got some data back + assert_eq!(response.typedefs[0].fieldnames[0], "value"); + } + + #[test_log::test(tokio::test)] + async fn rosapi_get_service_type() { + let api = fixture_client().await; + let response = api.get_service_type("/rosapi/node_details").await.unwrap(); + assert_eq!(response.r#type, "rosapi/NodeDetails"); + } + + #[test_log::test(tokio::test)] + async fn rosapi_services() { + let api = fixture_client().await; + let response = api.get_services().await.unwrap(); + assert!(!response.services.is_empty()); + } +} diff --git a/roslibrust_rosbridge/src/lib.rs b/roslibrust_rosbridge/src/lib.rs index 302b1e9d..0ec506a9 100644 --- a/roslibrust_rosbridge/src/lib.rs +++ b/roslibrust_rosbridge/src/lib.rs @@ -134,6 +134,14 @@ impl ServiceProvider for crate::ClientHandle { type ServiceClient = crate::ServiceClient; type ServiceServer = crate::ServiceHandle; + async fn call_service( + &self, + topic: &str, + request: T::Request, + ) -> RosLibRustResult { + self.call_service::(topic, request).await + } + async fn service_client( &self, topic: &str, From d022e78b776aa123c59754e3014ce63013342525 Mon Sep 17 00:00:00 2001 From: carter Date: Tue, 17 Dec 2024 11:40:54 -0700 Subject: [PATCH 08/14] missed impls for call_service --- roslibrust_mock/src/lib.rs | 9 +++++++++ roslibrust_zenoh/src/lib.rs | 10 ++++++++++ 2 files changed, 19 insertions(+) diff --git a/roslibrust_mock/src/lib.rs b/roslibrust_mock/src/lib.rs index 5342a663..a9cccc41 100644 --- a/roslibrust_mock/src/lib.rs +++ b/roslibrust_mock/src/lib.rs @@ -113,6 +113,15 @@ impl ServiceProvider for MockRos { type ServiceClient = MockServiceClient; type ServiceServer = (); + async fn call_service( + &self, + topic: &str, + request: T::Request, + ) -> RosLibRustResult { + let client = self.service_client::(topic).await?; + client.call(&request).await + } + async fn service_client( &self, topic: &str, diff --git a/roslibrust_zenoh/src/lib.rs b/roslibrust_zenoh/src/lib.rs index e1bb8e77..130c11af 100644 --- a/roslibrust_zenoh/src/lib.rs +++ b/roslibrust_zenoh/src/lib.rs @@ -213,6 +213,16 @@ impl ServiceProvider for ZenohClient { type ServiceClient = ZenohServiceClient; type ServiceServer = ZenohServiceServer; + async fn call_service( + &self, + topic: &str, + request: T::Request, + ) -> RosLibRustResult { + // TODO should be able to optimize this... + let client = self.service_client::(topic).await?; + client.call(&request).await + } + async fn service_client( &self, topic: &str, From b20b101d01b4033aca52998402a80be6b9e51bbc Mon Sep 17 00:00:00 2001 From: carter Date: Tue, 17 Dec 2024 11:57:47 -0700 Subject: [PATCH 09/14] Update changelog --- CHANGELOG.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 0f7b52a0..957df061 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -25,6 +25,9 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 - roslibrust_mock now provides a basic mock implementation of roslibrust's generic traits for use in building automated testing of nodes. - roslibrust_zenoh now proivides a Zenoh client that is compatible with the zenoh-ros1-plugin / zenoh-ros1-bridge +- roslibrust_ros1 now provides a ROS1 native client as a standalone crate +- roslibrust_rosbridge now provides a rosbridge client as a standalone crate +- roslibrust_rosapi now provides a generic interface for the rosapi node compatible with both rosbridge and ros1 backends ### Fixed @@ -36,6 +39,9 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 ### Changed +- A major reorganization of the internals of roslibrust was done to improve our ability to support multiple backends. + As part of the organization the rosbridge backend has been moved under the the `rosbridge` module, so + `roslibrust::ClientHandle` now becomes `roslibrust::rosbridge::ClientHandle`. - Internal integral type Time changed from u32 to i32 representation to better align with ROS1 - Conversions between ROS Time and Duration to std::time::Time and std::time::Duration switched to TryFrom as they can be fallible. From 4a472bb34d761ba9f367aefbbafae26daa1772f1 Mon Sep 17 00:00:00 2001 From: carter Date: Wed, 18 Dec 2024 10:00:59 -0700 Subject: [PATCH 10/14] Update a lot of dependencies to be more generic workspace dependencies --- Cargo.toml | 9 ++++++++- roslibrust/Cargo.toml | 6 +++--- roslibrust_codegen/Cargo.toml | 6 +++--- roslibrust_common/Cargo.toml | 4 ++-- roslibrust_genmsg/Cargo.toml | 6 +++--- roslibrust_mock/Cargo.toml | 4 ++-- roslibrust_ros1/Cargo.toml | 8 +++++--- roslibrust_rosapi/Cargo.toml | 2 +- roslibrust_rosbridge/Cargo.toml | 10 ++-------- roslibrust_test/Cargo.toml | 6 +++--- roslibrust_zenoh/Cargo.toml | 6 +++--- 11 files changed, 35 insertions(+), 32 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index 30516368..c665a45a 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,5 +1,4 @@ [workspace] - members = [ "example_package", "example_package_macro", @@ -16,3 +15,11 @@ members = [ "roslibrust_rosapi", ] resolver = "2" + +[workspace.dependencies] +log = "0.4" +tokio = {version = "1", features = ["full"] } +serde = { version = "1.0", features = ["derive"] } +# Someday we may move this crate into this workspace +# For now this is how we keep from repeating the verison everywhere +roslibrust_serde_rosmsg = "0.4" diff --git a/roslibrust/Cargo.toml b/roslibrust/Cargo.toml index 99f8f8fd..2e2146b7 100644 --- a/roslibrust/Cargo.toml +++ b/roslibrust/Cargo.toml @@ -21,9 +21,9 @@ roslibrust_mock = { path = "../roslibrust_mock", optional = true } [dev-dependencies] env_logger = "0.11" test-log = "0.2" -log = "0.4" -tokio = { version = "1.20", features = ["macros", "rt-multi-thread"] } -serde = { version = "1.0", features = ["derive"] } +log = { workspace = true } +tokio = { workspace = true } +serde = { workspace = true } # Used to generate messages for the examples roslibrust_codegen = { path = "../roslibrust_codegen" } roslibrust_codegen_macro = { path = "../roslibrust_codegen_macro" } diff --git a/roslibrust_codegen/Cargo.toml b/roslibrust_codegen/Cargo.toml index 0851e3c8..370f8396 100644 --- a/roslibrust_codegen/Cargo.toml +++ b/roslibrust_codegen/Cargo.toml @@ -13,17 +13,17 @@ categories = ["science::robotics"] # See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html [dependencies] +tokio = { workspace = true, optional = true} +log = { workspace = true } +serde = { workspace = true } roslibrust_common = { path = "../roslibrust_common" } lazy_static = "1.4" -log = "0.4" md5 = "0.7" proc-macro2 = "1.0" quote = "1.0" -serde = { version = "1.0", features = ["derive"] } serde_json = "1.0" simple-error = "0.3" syn = "1.0" -tokio = { version = "1.0", features = ["time", "signal"], optional = true} walkdir = "2.3" xml-rs = "0.8" # Not a direct dependencies of the crate, but something generated code uses diff --git a/roslibrust_common/Cargo.toml b/roslibrust_common/Cargo.toml index 5cfc7e38..f2aed082 100644 --- a/roslibrust_common/Cargo.toml +++ b/roslibrust_common/Cargo.toml @@ -8,7 +8,7 @@ edition = "2021" thiserror = "2.0" anyhow = "1.0" # Used as basis for serialization -serde = { version = "1.0", features = ["derive"] } +serde = { workspace = true } # Used for md5sum calculation md5 = "0.7" # Used for async trait definitions @@ -17,6 +17,6 @@ futures = "0.3" # THESE DEPENDENCIES WILL BE REMOVED # We're currently leaking these error types in the "generic error type" # We'll clean this up -tokio = { version = "1.41", features = ["time"] } +tokio = { workspace = true } tokio-tungstenite = { version = "0.17" } serde_json = "1.0" diff --git a/roslibrust_genmsg/Cargo.toml b/roslibrust_genmsg/Cargo.toml index db8dc53d..bbc81284 100644 --- a/roslibrust_genmsg/Cargo.toml +++ b/roslibrust_genmsg/Cargo.toml @@ -18,14 +18,14 @@ name = "gencpp" path = "src/main.rs" [dependencies] +log = { workspace = true } +serde = { workspace = true } +roslibrust_codegen = { path = "../roslibrust_codegen", version = "0.11.0" } clap = { version = "4.1", features = ["derive"] } env_logger = "0.11" itertools = "0.12" lazy_static = "1.4" -log = "0.4" minijinja = "2.0" -roslibrust_codegen = { path = "../roslibrust_codegen", version = "0.11.0" } -serde = { version = "1", features = ["derive"] } serde_json = "1" [dev-dependencies] diff --git a/roslibrust_mock/Cargo.toml b/roslibrust_mock/Cargo.toml index d37457f7..5c882c56 100644 --- a/roslibrust_mock/Cargo.toml +++ b/roslibrust_mock/Cargo.toml @@ -5,11 +5,11 @@ edition = "2021" [dependencies] roslibrust_common = { path = "../roslibrust_common" } -tokio = { version = "1.41", features = ["sync", "rt-multi-thread", "macros"] } +tokio = { workspace = true } # Used for serializing messages bincode = "1.3" # We add logging to aid in debugging tests -log = "0.4" +log = { workspace = true } [dev-dependencies] roslibrust_codegen = { path = "../roslibrust_codegen" } diff --git a/roslibrust_ros1/Cargo.toml b/roslibrust_ros1/Cargo.toml index 545f0ca7..defcc53d 100644 --- a/roslibrust_ros1/Cargo.toml +++ b/roslibrust_ros1/Cargo.toml @@ -7,13 +7,15 @@ edition = "2021" # Provides common types and traits used throughout the roslibrust ecosystem. roslibrust_common = { path = "../roslibrust_common" } +# Standard dependencies: +tokio = { workspace = true } +log = { workspace = true } +serde = { workspace = true } + # Should probably become workspace members: -tokio = { version = "1.41", features = ["rt-multi-thread", "sync", "macros"] } -log = "0.4" lazy_static = "1.4" abort-on-drop = "0.2" test-log = "0.2" -serde = { version = "1.0" } # These are definitely needed by this crate: reqwest = { version = "0.11" } diff --git a/roslibrust_rosapi/Cargo.toml b/roslibrust_rosapi/Cargo.toml index db92d830..1f79160b 100644 --- a/roslibrust_rosapi/Cargo.toml +++ b/roslibrust_rosapi/Cargo.toml @@ -12,7 +12,7 @@ roslibrust_common = { path = "../roslibrust_common" } # but can work with any backend that implements the ServiceProvider trait and has a RosApi node running [dev-dependencies] -tokio = { version = "1.41" } +tokio = { workspace = true } test-log = "0.2" # Only backend we're currently testing with roslibrust_rosbridge = { path = "../roslibrust_rosbridge" } diff --git a/roslibrust_rosbridge/Cargo.toml b/roslibrust_rosbridge/Cargo.toml index 23c633d2..877a18b0 100644 --- a/roslibrust_rosbridge/Cargo.toml +++ b/roslibrust_rosbridge/Cargo.toml @@ -5,16 +5,10 @@ edition = "2021" [dependencies] roslibrust_common = { path = "../roslibrust_common" } -tokio = { version = "1.20", features = [ - "net", - "macros", - "time", - "rt-multi-thread", - "sync", -] } +tokio = { workspace = true } +log = { workspace = true } tokio-tungstenite = { version = "0.17" } uuid = { version = "1.1", features = ["v4"] } -log = "0.4" serde_json = "1.0" anyhow = "1.0" futures = "0.3" diff --git a/roslibrust_test/Cargo.toml b/roslibrust_test/Cargo.toml index e0b2ad8e..b4b47bc0 100644 --- a/roslibrust_test/Cargo.toml +++ b/roslibrust_test/Cargo.toml @@ -11,14 +11,14 @@ roslibrust_common = { path = "../roslibrust_common" } # We can fix this by moving the generated types into a roslibrust_ros1_types crate roslibrust_codegen = { path = "../roslibrust_codegen" } lazy_static = "1.4" -tokio = { version = "1.20", features = ["net", "sync"] } -log = "0.4" +tokio = { workspace = true } +log = { workspace = true } [dev-dependencies] diffy = "0.3.0" criterion = { version = "0.4", features = ["html_reports", "async_tokio"] } pprof = { version = "0.11", features = ["flamegraph", "criterion"] } -tokio = { version = "1.24", features = ["full"] } +tokio = { workspace = true } [[bin]] path = "src/performance_ramp.rs" diff --git a/roslibrust_zenoh/Cargo.toml b/roslibrust_zenoh/Cargo.toml index 49b233e6..300bc978 100644 --- a/roslibrust_zenoh/Cargo.toml +++ b/roslibrust_zenoh/Cargo.toml @@ -6,13 +6,13 @@ edition = "2021" # See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html [dependencies] -tokio = { version = "1.41", features = ["rt-multi-thread", "sync", "macros"] } +roslibrust_serde_rosmsg = { workspace = true } +log = { workspace = true } +tokio = { workspace = true } roslibrust_common = { path = "../roslibrust_common" } zenoh = "1.0" hex = "0.4" anyhow = "1.0" -roslibrust_serde_rosmsg = "0.4" -log = "0.4" [dev-dependencies] env_logger = "0.11" From 4ea7676ee90b89c0375097b0a65c28704b8b219f Mon Sep 17 00:00:00 2001 From: carter Date: Wed, 18 Dec 2024 12:42:32 -0700 Subject: [PATCH 11/14] Refactor of RosLibRustError and RosLibRustResult --- roslibrust_codegen/src/lib.rs | 2 +- roslibrust_common/src/lib.rs | 13 ++- roslibrust_common/src/topic_provider.rs | 18 ++-- roslibrust_mock/src/lib.rs | 65 +++++++------- roslibrust_ros1/src/lib.rs | 31 ++++--- roslibrust_ros1/src/node/actor.rs | 6 +- roslibrust_ros1/src/node/mod.rs | 14 +-- roslibrust_ros1/src/service_client.rs | 20 ++--- roslibrust_rosapi/src/lib.rs | 87 ++++++++++--------- roslibrust_rosbridge/src/client.rs | 58 ++++++------- roslibrust_rosbridge/src/comm.rs | 46 +++++----- roslibrust_rosbridge/src/integration_tests.rs | 8 +- roslibrust_rosbridge/src/lib.rs | 31 +++---- roslibrust_rosbridge/src/publisher.rs | 4 +- roslibrust_test/tests/ros1_codegen_tests.rs | 2 +- roslibrust_zenoh/src/lib.rs | 48 +++++----- 16 files changed, 223 insertions(+), 230 deletions(-) diff --git a/roslibrust_codegen/src/lib.rs b/roslibrust_codegen/src/lib.rs index 7eaec728..eda36396 100644 --- a/roslibrust_codegen/src/lib.rs +++ b/roslibrust_codegen/src/lib.rs @@ -28,7 +28,7 @@ pub use serde_bytes; pub use smart_default::SmartDefault; // Used in generated code for default values // Used in generated code for faster Vec serialization // Export the common types so they can be found under this namespace for backwards compatibility reasons -pub use roslibrust_common::*; +// pub use roslibrust_common::*; #[derive(Clone, Debug)] pub struct MessageFile { diff --git a/roslibrust_common/src/lib.rs b/roslibrust_common/src/lib.rs index a6bfc3b9..085190df 100644 --- a/roslibrust_common/src/lib.rs +++ b/roslibrust_common/src/lib.rs @@ -3,7 +3,7 @@ /// For now starting with a central error type, may break this up more in future #[derive(thiserror::Error, Debug)] -pub enum RosLibRustError { +pub enum Error { #[error("Not currently connected to ros master / bridge")] Disconnected, // TODO we probably want to eliminate tungstenite from this and hide our @@ -32,7 +32,7 @@ pub enum RosLibRustError { /// Generic result type used as standard throughout library. /// Note: many functions which currently return this will be updated to provide specific error /// types in the future instead of the generic error here. -pub type RosLibRustResult = Result; +pub type Result = std::result::Result; /// Fundamental traits for message types this crate works with /// This trait will be satisfied for any types generated with this crate's message_gen functionality @@ -77,7 +77,9 @@ pub trait RosServiceType: 'static + Send + Sync { /// server with roslibrust. We're really just using this as a trait alias /// as the full definition is overly verbose and trait aliases are unstable. pub trait ServiceFn: - Fn(T::Request) -> Result> + Fn( + T::Request, + ) -> std::result::Result> + Send + Sync + 'static @@ -88,7 +90,10 @@ pub trait ServiceFn: impl ServiceFn for F where T: RosServiceType, - F: Fn(T::Request) -> Result> + F: Fn( + T::Request, + ) + -> std::result::Result> + Send + Sync + 'static, diff --git a/roslibrust_common/src/topic_provider.rs b/roslibrust_common/src/topic_provider.rs index aa6058eb..add41e80 100644 --- a/roslibrust_common/src/topic_provider.rs +++ b/roslibrust_common/src/topic_provider.rs @@ -1,4 +1,4 @@ -use crate::{RosLibRustResult, RosMessageType, RosServiceType, ServiceFn}; +use crate::{Result, RosMessageType, RosServiceType, ServiceFn}; /// Indicates that something is a publisher and has our expected publish /// Implementors of this trait are expected to auto-cleanup the publisher when dropped @@ -7,7 +7,7 @@ pub trait Publish { // However see: https://blog.rust-lang.org/2023/12/21/async-fn-rpit-in-traits.html // This generates a warning is rust as of writing due to ambiguity around the "Send-ness" of the return type // We only plan to work with multi-threaded work stealing executors (e.g. tokio) so we're manually specifying Send - fn publish(&self, data: &T) -> impl futures::Future> + Send; + fn publish(&self, data: &T) -> impl futures::Future> + Send; } /// Indicates that something is a subscriber and has our expected subscribe method @@ -15,7 +15,7 @@ pub trait Publish { pub trait Subscribe { // TODO need to solidify how we want errors to work with subscribers... // TODO ros1 currently requires mut for next, we should change that - fn next(&mut self) -> impl futures::Future> + Send; + fn next(&mut self) -> impl futures::Future> + Send; } /// This trait generically describes the capability of something to act as an async interface to a set of topics @@ -37,7 +37,7 @@ pub trait TopicProvider { fn advertise( &self, topic: &str, - ) -> impl futures::Future>> + Send; + ) -> impl futures::Future>> + Send; /// Subscribes to a topic and returns a type specific subscriber to use. /// @@ -45,7 +45,7 @@ pub trait TopicProvider { fn subscribe( &self, topic: &str, - ) -> impl futures::Future>> + Send; + ) -> impl futures::Future>> + Send; } /// Defines what it means to be something that is callable as a service @@ -53,7 +53,7 @@ pub trait Service { fn call( &self, request: &T::Request, - ) -> impl futures::Future> + Send; + ) -> impl futures::Future> + Send; } /// This trait is analogous to TopicProvider, but instead provides the capability to create service servers and service clients @@ -66,7 +66,7 @@ pub trait ServiceProvider { &self, topic: &str, request: T::Request, - ) -> impl futures::Future> + Send; + ) -> impl futures::Future> + Send; /// An optimized version of call_service that returns a persistent client that can be used to repeatedly call a service. /// Depending on backend this may provide a performance benefit over call_service. @@ -74,7 +74,7 @@ pub trait ServiceProvider { fn service_client( &self, topic: &str, - ) -> impl futures::Future>> + Send; + ) -> impl futures::Future>> + Send; /// Advertise a service function to be available for clients to call. /// A handle is returned that manages the lifetime of the service. @@ -85,7 +85,7 @@ pub trait ServiceProvider { &self, topic: &str, server: F, - ) -> impl futures::Future> + Send + ) -> impl futures::Future> + Send where F: ServiceFn; } diff --git a/roslibrust_mock/src/lib.rs b/roslibrust_mock/src/lib.rs index a9cccc41..9430b17c 100644 --- a/roslibrust_mock/src/lib.rs +++ b/roslibrust_mock/src/lib.rs @@ -9,7 +9,7 @@ use tokio::sync::RwLock; use log::*; type TypeErasedCallback = Arc< - dyn Fn(Vec) -> Result, Box> + dyn Fn(Vec) -> std::result::Result, Box> + Send + Sync + 'static, @@ -37,10 +37,7 @@ impl TopicProvider for MockRos { type Publisher = MockPublisher; type Subscriber = MockSubscriber; - async fn advertise( - &self, - topic: &str, - ) -> RosLibRustResult> { + async fn advertise(&self, topic: &str) -> Result> { // Check if we already have this channel { let topics = self.topics.read().await; @@ -67,7 +64,7 @@ impl TopicProvider for MockRos { async fn subscribe( &self, topic: &str, - ) -> RosLibRustResult> { + ) -> roslibrust_common::Result> { // Check if we already have this channel { let topics = self.topics.read().await; @@ -98,13 +95,13 @@ pub struct MockServiceClient { } impl Service for MockServiceClient { - async fn call(&self, request: &T::Request) -> RosLibRustResult { - let data = bincode::serialize(request) - .map_err(|e| RosLibRustError::SerializationError(e.to_string()))?; - let response = (self.callback)(data) - .map_err(|e| RosLibRustError::SerializationError(e.to_string()))?; + async fn call(&self, request: &T::Request) -> roslibrust_common::Result { + let data = + bincode::serialize(request).map_err(|e| Error::SerializationError(e.to_string()))?; + let response = + (self.callback)(data).map_err(|e| Error::SerializationError(e.to_string()))?; let response = bincode::deserialize(&response[..]) - .map_err(|e| RosLibRustError::SerializationError(e.to_string()))?; + .map_err(|e| Error::SerializationError(e.to_string()))?; Ok(response) } } @@ -117,7 +114,7 @@ impl ServiceProvider for MockRos { &self, topic: &str, request: T::Request, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { let client = self.service_client::(topic).await?; client.call(&request).await } @@ -125,7 +122,7 @@ impl ServiceProvider for MockRos { async fn service_client( &self, topic: &str, - ) -> RosLibRustResult> { + ) -> roslibrust_common::Result> { let services = self.services.read().await; if let Some(callback) = services.get(topic) { return Ok(MockServiceClient { @@ -133,27 +130,29 @@ impl ServiceProvider for MockRos { _marker: Default::default(), }); } - Err(RosLibRustError::Disconnected) + Err(Error::Disconnected) } async fn advertise_service( &self, topic: &str, server: F, - ) -> RosLibRustResult + ) -> roslibrust_common::Result where F: ServiceFn, { // Type erase the service function here - let erased_closure = - move |message: Vec| -> Result, Box> { - let request = bincode::deserialize(&message[..]) - .map_err(|e| RosLibRustError::SerializationError(e.to_string()))?; - let response = server(request)?; - let bytes = bincode::serialize(&response) - .map_err(|e| RosLibRustError::SerializationError(e.to_string()))?; - Ok(bytes) - }; + let erased_closure = move |message: Vec| -> std::result::Result< + Vec, + Box, + > { + let request = bincode::deserialize(&message[..]) + .map_err(|e| Error::SerializationError(e.to_string()))?; + let response = server(request)?; + let bytes = bincode::serialize(&response) + .map_err(|e| Error::SerializationError(e.to_string()))?; + Ok(bytes) + }; let erased_closure = Arc::new(erased_closure); let mut services = self.services.write().await; services.insert(topic.to_string(), erased_closure); @@ -170,12 +169,10 @@ pub struct MockPublisher { } impl Publish for MockPublisher { - async fn publish(&self, data: &T) -> RosLibRustResult<()> { - let data = bincode::serialize(data) - .map_err(|e| RosLibRustError::SerializationError(e.to_string()))?; - self.sender - .send(data) - .map_err(|_e| RosLibRustError::Disconnected)?; + async fn publish(&self, data: &T) -> roslibrust_common::Result<()> { + let data = + bincode::serialize(data).map_err(|e| Error::SerializationError(e.to_string()))?; + self.sender.send(data).map_err(|_e| Error::Disconnected)?; debug!("Sent data on topic {}", T::ROS_TYPE_NAME); Ok(()) } @@ -187,14 +184,14 @@ pub struct MockSubscriber { } impl Subscribe for MockSubscriber { - async fn next(&mut self) -> RosLibRustResult { + async fn next(&mut self) -> roslibrust_common::Result { let data = self .receiver .recv() .await - .map_err(|_| RosLibRustError::Disconnected)?; + .map_err(|_| Error::Disconnected)?; let msg = bincode::deserialize(&data[..]) - .map_err(|e| RosLibRustError::SerializationError(e.to_string()))?; + .map_err(|e| Error::SerializationError(e.to_string()))?; debug!("Received data on topic {}", T::ROS_TYPE_NAME); Ok(msg) } diff --git a/roslibrust_ros1/src/lib.rs b/roslibrust_ros1/src/lib.rs index 66d2dfea..acaf3ea3 100644 --- a/roslibrust_ros1/src/lib.rs +++ b/roslibrust_ros1/src/lib.rs @@ -1,6 +1,9 @@ //! This module holds all content for directly working with ROS1 natively - -use roslibrust_common::*; +use roslibrust_common::Error; +use roslibrust_common::{ + Publish, RosMessageType, RosServiceType, Service, ServiceFn, ServiceProvider, Subscribe, + TopicProvider, +}; /// [master_client] module contains code for calling xmlrpc functions on the master mod master_client; @@ -38,7 +41,7 @@ impl TopicProvider for NodeHandle { async fn advertise( &self, topic: &str, - ) -> RosLibRustResult> { + ) -> roslibrust_common::Result> { // TODO MAJOR: consider promoting queue size, making unlimited default self.advertise::(topic.as_ref(), 10, false) .await @@ -48,14 +51,14 @@ impl TopicProvider for NodeHandle { async fn subscribe( &self, topic: &str, - ) -> RosLibRustResult> { + ) -> roslibrust_common::Result> { // TODO MAJOR: consider promoting queue size, making unlimited default self.subscribe(topic, 10).await.map_err(|e| e.into()) } } impl Service for ServiceClient { - async fn call(&self, request: &T::Request) -> RosLibRustResult { + async fn call(&self, request: &T::Request) -> roslibrust_common::Result { self.call(request).await } } @@ -68,7 +71,7 @@ impl ServiceProvider for crate::NodeHandle { &self, topic: &str, request: T::Request, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { // TODO should have a more optimized version of this... let client = self.service_client::(topic).await?; client.call(&request).await @@ -77,7 +80,7 @@ impl ServiceProvider for crate::NodeHandle { async fn service_client( &self, topic: &str, - ) -> RosLibRustResult> { + ) -> roslibrust_common::Result> { // TODO bad error mapping here... self.service_client::(topic).await.map_err(|e| e.into()) } @@ -86,7 +89,7 @@ impl ServiceProvider for crate::NodeHandle { &self, topic: &str, server: F, - ) -> RosLibRustResult + ) -> roslibrust_common::Result where F: ServiceFn, { @@ -97,20 +100,20 @@ impl ServiceProvider for crate::NodeHandle { } impl Subscribe for crate::Subscriber { - async fn next(&mut self) -> RosLibRustResult { + async fn next(&mut self) -> roslibrust_common::Result { let res = crate::Subscriber::next(self).await; match res { Some(Ok(msg)) => Ok(msg), Some(Err(e)) => { log::error!("Subscriber got error: {e:?}"); // TODO gotta do better error conversion / error types here - Err(crate::RosLibRustError::Unexpected(anyhow::anyhow!( + Err(Error::Unexpected(anyhow::anyhow!( "Subscriber got error: {e:?}" ))) } None => { log::error!("Subscriber hit dropped channel"); - Err(crate::RosLibRustError::Unexpected(anyhow::anyhow!( + Err(Error::Unexpected(anyhow::anyhow!( "Channel closed, something was dropped?" ))) } @@ -120,17 +123,17 @@ impl Subscribe for crate::Subscriber { // Provide an implementation of publish for ros1 backend impl Publish for Publisher { - async fn publish(&self, data: &T) -> RosLibRustResult<()> { + async fn publish(&self, data: &T) -> roslibrust_common::Result<()> { // TODO error type conversion here is terrible and we need to standardize error stuff badly self.publish(data) .await - .map_err(|e| RosLibRustError::SerializationError(e.to_string())) + .map_err(|e| Error::SerializationError(e.to_string())) } } #[cfg(test)] mod test { - use roslibrust_common::*; + use roslibrust_common::TopicProvider; // Prove that we've implemented the topic provider trait fully for NodeHandle #[test] diff --git a/roslibrust_ros1/src/node/actor.rs b/roslibrust_ros1/src/node/actor.rs index 1c2a9104..e13ba63d 100644 --- a/roslibrust_ros1/src/node/actor.rs +++ b/roslibrust_ros1/src/node/actor.rs @@ -9,7 +9,7 @@ use crate::{ }; use abort_on_drop::ChildTask; use log::*; -use roslibrust_common::{RosLibRustError, RosMessageType, RosServiceType, ServiceFn}; +use roslibrust_common::{Error, RosMessageType, RosServiceType, ServiceFn}; use std::{collections::HashMap, io, net::Ipv4Addr, sync::Arc}; use tokio::sync::{broadcast, mpsc, oneshot}; @@ -285,10 +285,10 @@ impl NodeServerHandle { let server_typeless = move |message: Vec| -> Result, Box> { let request = roslibrust_serde_rosmsg::from_slice::(&message) - .map_err(|err| RosLibRustError::SerializationError(err.to_string()))?; + .map_err(|err| Error::SerializationError(err.to_string()))?; let response = server(request)?; Ok(roslibrust_serde_rosmsg::to_vec(&response) - .map_err(|err| RosLibRustError::SerializationError(err.to_string()))?) + .map_err(|err| Error::SerializationError(err.to_string()))?) }; let server_typeless = Box::new(server_typeless); diff --git a/roslibrust_ros1/src/node/mod.rs b/roslibrust_ros1/src/node/mod.rs index aa0d0535..7cbdf09e 100644 --- a/roslibrust_ros1/src/node/mod.rs +++ b/roslibrust_ros1/src/node/mod.rs @@ -1,7 +1,7 @@ //! This module contains the top level Node and NodeHandle classes. //! These wrap the lower level management of a ROS Node connection into a higher level and thread safe API. -use roslibrust_common::RosLibRustError; +use roslibrust_common::Error; use super::{names::InvalidNameError, RosMasterError}; use std::{ @@ -107,16 +107,16 @@ impl From> for NodeError { // we produced two different error types for the two different impls (ros1, rosbridge) // This allows fusing the two error types together so that TopicProider can work // but we should just better design all the error handling -impl From for RosLibRustError { +impl From for Error { fn from(value: NodeError) -> Self { match value { - NodeError::RosMasterError(e) => RosLibRustError::ServerError(e.to_string()), + NodeError::RosMasterError(e) => Error::ServerError(e.to_string()), NodeError::ChannelClosedError => { - RosLibRustError::Unexpected(anyhow!("Channel closed, something was dropped?")) + Error::Unexpected(anyhow!("Channel closed, something was dropped?")) } - NodeError::InvalidName(e) => RosLibRustError::InvalidName(e.to_string()), - NodeError::XmlRpcError(e) => RosLibRustError::SerializationError(e.to_string().into()), - NodeError::IoError(e) => RosLibRustError::IoError(e), + NodeError::InvalidName(e) => Error::InvalidName(e.to_string()), + NodeError::XmlRpcError(e) => Error::SerializationError(e.to_string().into()), + NodeError::IoError(e) => Error::IoError(e), } } } diff --git a/roslibrust_ros1/src/service_client.rs b/roslibrust_ros1/src/service_client.rs index 2d3aa30d..9def9099 100644 --- a/roslibrust_ros1/src/service_client.rs +++ b/roslibrust_ros1/src/service_client.rs @@ -3,7 +3,7 @@ use crate::{ tcpros::{establish_connection, ConnectionHeader}, }; use abort_on_drop::ChildTask; -use roslibrust_common::{RosLibRustError, RosLibRustResult, RosServiceType}; +use roslibrust_common::{Error, RosServiceType}; use std::{marker::PhantomData, sync::Arc}; use tokio::{ io::{AsyncReadExt, AsyncWriteExt}, @@ -17,7 +17,7 @@ use tokio::{ use super::tcpros; pub type CallServiceRequest = (Vec, oneshot::Sender); -pub type CallServiceResponse = RosLibRustResult>; +pub type CallServiceResponse = roslibrust_common::Result>; // Note: ServiceClient is clone, and this is expressly different behavior than calling .service_client() twice on NodeHandle // clonning a ServiceClient does not create a new connection to the service, but instead creates a second handle to the @@ -50,14 +50,14 @@ impl ServiceClient { &self.service_name } - pub async fn call(&self, request: &T::Request) -> RosLibRustResult { + pub async fn call(&self, request: &T::Request) -> std::result::Result { let request_payload = roslibrust_serde_rosmsg::to_vec(request) - .map_err(|err| RosLibRustError::SerializationError(err.to_string()))?; + .map_err(|err| Error::SerializationError(err.to_string()))?; let (response_tx, response_rx) = oneshot::channel(); self.sender .send((request_payload, response_tx)) - .map_err(|_err| RosLibRustError::Disconnected)?; + .map_err(|_err| Error::Disconnected)?; match response_rx.await { Ok(Ok(result_payload)) => { @@ -67,14 +67,14 @@ impl ServiceClient { result_payload ); let response: T::Response = roslibrust_serde_rosmsg::from_slice(&result_payload) - .map_err(|err| RosLibRustError::SerializationError(err.to_string()))?; + .map_err(|err| Error::SerializationError(err.to_string()))?; return Ok(response); } Ok(Err(err)) => { return Err(err); } Err(_err) => { - return Err(RosLibRustError::Disconnected); + return Err(Error::Disconnected); } } } @@ -93,7 +93,7 @@ impl ServiceClientLink { service_uri: &str, srv_definition: &str, md5sum: &str, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { let header = ConnectionHeader { caller_id: node_name.to_string(), latching: false, @@ -113,7 +113,7 @@ impl ServiceClientLink { let stream = establish_connection(&node_name, &service_name, &service_uri, header).await.map_err(|err| { log::error!("Failed to establish connection to service URI {service_uri} for service {service_name}: {err}"); - RosLibRustError::from(err) + Error::from(err) })?; let actor_context = Self::actor_context(stream, service_name.to_owned(), call_rx); @@ -161,7 +161,7 @@ impl ServiceClientLink { log::error!( "Failed to send and receive service call for service {service_name}: {err:?}" ); - RosLibRustError::from(err) + Error::from(err) }); let send_result = response_sender.send(response); if let Err(_err) = send_result { diff --git a/roslibrust_rosapi/src/lib.rs b/roslibrust_rosapi/src/lib.rs index 409fd10a..45471e06 100644 --- a/roslibrust_rosapi/src/lib.rs +++ b/roslibrust_rosapi/src/lib.rs @@ -4,7 +4,6 @@ //! Ensure rosapi is running on your target system before attempting to utilize these features! use roslibrust_common::topic_provider::ServiceProvider; -use roslibrust_common::RosLibRustResult; // TODO major issue here for folks who actually try to use rosapi in their project // This macro isn't going to expand correctly when not used from this crate's workspace @@ -17,108 +16,114 @@ roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_in pub trait RosApi { fn get_time( &self, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn topics( &self, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn get_topic_type( &self, topic: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn get_topics_for_type( &self, topic_type: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn get_nodes( &self, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn get_node_details( &self, node: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn get_node_for_service( &self, service: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn set_param( &self, param_name: impl Into + Send, param_value: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn get_param( &self, param_name: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn get_param_names( &self, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn has_param( &self, param: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn delete_param( &self, name: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn message_details( &self, message_name: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + + Send; fn publishers( &self, topic: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn service_host( &self, service: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn service_providers( &self, service_type: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + + Send; fn get_service_request_details( &self, service_type: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future< + Output = roslibrust_common::Result, + > + Send; fn get_service_response_details( &self, service_type: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future< + Output = roslibrust_common::Result, + > + Send; fn get_service_type( &self, service_name: impl Into + Send, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; fn get_services( &self, - ) -> impl std::future::Future> + Send; + ) -> impl std::future::Future> + Send; } /// A Generic implementation of the RosApi trait for any type that implements ServiceProvider /// Note, this will not work on ROS2 systems or systems without the rosapi node running. impl RosApi for T { /// Get the current time - async fn get_time(&self) -> RosLibRustResult { + async fn get_time(&self) -> roslibrust_common::Result { self.call_service::("/rosapi/get_time", rosapi::GetTimeRequest {}) .await } /// Get the list of topics active - async fn topics(&self) -> RosLibRustResult { + async fn topics(&self) -> roslibrust_common::Result { self.call_service::("/rosapi/topics", rosapi::TopicsRequest {}) .await } @@ -127,7 +132,7 @@ impl RosApi for T { async fn get_topic_type( &self, topic: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/topic_type", rosapi::TopicTypeRequest { @@ -141,7 +146,7 @@ impl RosApi for T { async fn get_topics_for_type( &self, topic_type: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/topics_for_type", rosapi::TopicsForTypeRequest { @@ -152,7 +157,7 @@ impl RosApi for T { } /// Returns list of nodes active in a system - async fn get_nodes(&self) -> RosLibRustResult { + async fn get_nodes(&self) -> roslibrust_common::Result { self.call_service::("/rosapi/nodes", rosapi::NodesRequest {}) .await } @@ -162,7 +167,7 @@ impl RosApi for T { async fn get_node_details( &self, node: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/node_details", rosapi::NodeDetailsRequest { node: node.into() }, @@ -174,7 +179,7 @@ impl RosApi for T { async fn get_node_for_service( &self, service: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/service_node", rosapi::ServiceNodeRequest { @@ -190,7 +195,7 @@ impl RosApi for T { &self, param_name: impl Into + Send, param_value: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/set_param", rosapi::SetParamRequest { @@ -206,7 +211,7 @@ impl RosApi for T { async fn get_param( &self, param_name: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/get_param", rosapi::GetParamRequest { @@ -218,7 +223,7 @@ impl RosApi for T { } /// Gets the list of currently known parameters. - async fn get_param_names(&self) -> RosLibRustResult { + async fn get_param_names(&self) -> roslibrust_common::Result { self.call_service::( "/rosapi/get_param_names", rosapi::GetParamNamesRequest {}, @@ -230,7 +235,7 @@ impl RosApi for T { async fn has_param( &self, param: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/has_param", rosapi::HasParamRequest { name: param.into() }, @@ -242,7 +247,7 @@ impl RosApi for T { async fn delete_param( &self, name: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/delete_param", rosapi::DeleteParamRequest { name: name.into() }, @@ -254,7 +259,7 @@ impl RosApi for T { async fn message_details( &self, message_name: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/message_details", rosapi::MessageDetailsRequest { @@ -268,7 +273,7 @@ impl RosApi for T { async fn publishers( &self, topic: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/publishers", rosapi::PublishersRequest { @@ -282,7 +287,7 @@ impl RosApi for T { async fn service_host( &self, service: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/service_host", rosapi::ServiceHostRequest { @@ -296,7 +301,7 @@ impl RosApi for T { async fn service_providers( &self, service_type: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/service_providers", rosapi::ServiceProvidersRequest { @@ -310,7 +315,7 @@ impl RosApi for T { async fn get_service_request_details( &self, service_type: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/service_request_details", rosapi::ServiceRequestDetailsRequest { @@ -324,7 +329,7 @@ impl RosApi for T { async fn get_service_response_details( &self, service_type: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/service_response_details", rosapi::ServiceRequestDetailsRequest { @@ -338,7 +343,7 @@ impl RosApi for T { async fn get_service_type( &self, service_name: impl Into + Send, - ) -> RosLibRustResult { + ) -> roslibrust_common::Result { self.call_service::( "/rosapi/service_type", rosapi::ServiceTypeRequest { @@ -349,7 +354,7 @@ impl RosApi for T { } /// Get the list of services active on the system - async fn get_services(&self) -> RosLibRustResult { + async fn get_services(&self) -> roslibrust_common::Result { self.call_service::("/rosapi/services", rosapi::ServicesRequest {}) .await } diff --git a/roslibrust_rosbridge/src/client.rs b/roslibrust_rosbridge/src/client.rs index f629b688..d1c90f8d 100644 --- a/roslibrust_rosbridge/src/client.rs +++ b/roslibrust_rosbridge/src/client.rs @@ -85,7 +85,7 @@ impl ClientHandle { /// Like [ClientHandle::new] this function does not resolve until the connection is established for the first time. /// This function respects the [ClientHandleOptions] timeout and will return with an error if a connection is not /// established within the timeout. - pub async fn new_with_options(opts: ClientHandleOptions) -> RosLibRustResult { + pub async fn new_with_options(opts: ClientHandleOptions) -> Result { let inner = Arc::new(RwLock::new(timeout(opts.timeout, Client::new(opts)).await?)); let inner_weak = Arc::downgrade(&inner); @@ -105,19 +105,19 @@ impl ClientHandle { /// Connects a rosbridge instance at the given url /// Expects a fully describe websocket url, e.g. 'ws://localhost:9090' /// When awaited will not resolve until connection is successfully made. - pub async fn new>(url: S) -> RosLibRustResult { + pub async fn new>(url: S) -> Result { Self::new_with_options(ClientHandleOptions::new(url)).await } - fn check_for_disconnect(&self) -> RosLibRustResult<()> { + fn check_for_disconnect(&self) -> Result<()> { match self.is_disconnected.load(Ordering::Relaxed) { false => Ok(()), - true => Err(RosLibRustError::Disconnected), + true => Err(Error::Disconnected), } } // Internal implementation of subscribe - async fn _subscribe(&self, topic_name: &str) -> RosLibRustResult> + async fn _subscribe(&self, topic_name: &str) -> Result> where Msg: RosMessageType, { @@ -249,7 +249,7 @@ impl ClientHandle { /// # Ok(()) /// # } /// ``` - pub async fn subscribe(&self, topic_name: &str) -> RosLibRustResult> + pub async fn subscribe(&self, topic_name: &str) -> Result> where Msg: RosMessageType, { @@ -264,7 +264,7 @@ impl ClientHandle { // Publishes a message // Fails immediately(ish) if disconnected // Returns success when message is put on websocket (no confirmation of receipt) - pub(crate) async fn publish(&self, topic: &str, msg: &T) -> RosLibRustResult<()> + pub(crate) async fn publish(&self, topic: &str, msg: &T) -> Result<()> where T: RosMessageType, { @@ -303,7 +303,7 @@ impl ClientHandle { /// # Ok(()) /// # } /// ``` - pub async fn advertise(&self, topic: &str) -> RosLibRustResult> + pub async fn advertise(&self, topic: &str) -> Result> where T: RosMessageType, { @@ -311,7 +311,7 @@ impl ClientHandle { let client = self.inner.read().await; if client.publishers.contains_key(topic) { // TODO if we ever remove this restriction we should still check types match - return Err(RosLibRustError::Unexpected(anyhow!( + return Err(Error::Unexpected(anyhow!( "Attempted to create two publisher to same topic, this is not supported" ))); } else { @@ -357,7 +357,7 @@ impl ClientHandle { &self, service: &str, req: S::Request, - ) -> RosLibRustResult { + ) -> Result { self.check_for_disconnect()?; let (tx, rx) = tokio::sync::oneshot::channel(); let rand_string: String = uuid::Uuid::new_v4().to_string(); @@ -402,10 +402,10 @@ impl ClientHandle { // We failed to parse the value as an expected type, before just giving up, try to parse as string // if we got a string it indicates a server side error, otherwise we got the wrong datatype back match serde_json::from_value(msg) { - Ok(s) => return Err(RosLibRustError::ServerError(s)), + Ok(s) => return Err(Error::ServerError(s)), Err(_) => { // Return the error from the origional parse - return Err(RosLibRustError::InvalidMessage(e)); + return Err(Error::InvalidMessage(e)); } } } @@ -416,11 +416,7 @@ impl ClientHandle { /// Service will be active until the handle is dropped! /// /// See examples/service_server.rs for usage. - pub async fn advertise_service( - &self, - topic: &str, - server: F, - ) -> RosLibRustResult + pub async fn advertise_service(&self, topic: &str, server: F) -> Result where T: RosServiceType, F: ServiceFn, @@ -434,11 +430,11 @@ impl ClientHandle { error!( "Re-registering a server for the pre-existing topic: {topic} This will fail!" ); - return Err(RosLibRustError::Unexpected(anyhow!("roslibrust does not support re-advertising a service without first dropping the previous Service"))); + return Err(Error::Unexpected(anyhow!("roslibrust does not support re-advertising a service without first dropping the previous Service"))); } // We need to do type erasure and hide the request by wrapping their closure in a generic closure - let erased_closure = move |message: &str| -> Result< + let erased_closure = move |message: &str| -> std::result::Result< serde_json::Value, Box, > { @@ -470,7 +466,7 @@ impl ClientHandle { /// /// Note: Unlike with ROS1 native service, this provides no performance benefit over call_service, /// and is just a thin wrapper around call_service. - pub async fn service_client(&self, topic: &str) -> RosLibRustResult> + pub async fn service_client(&self, topic: &str) -> Result> where T: RosServiceType, { @@ -531,7 +527,7 @@ impl ClientHandle { // This function removes the entry for a subscriber in from the client, and if it is the last // subscriber for a given topic then dispatches an unsubscribe message to the master/bridge - pub(crate) fn unsubscribe(&self, topic_name: &str, id: &uuid::Uuid) -> RosLibRustResult<()> { + pub(crate) fn unsubscribe(&self, topic_name: &str, id: &uuid::Uuid) -> Result<()> { // Copy so we can move into closure let client = self.clone(); let topic_name = topic_name.to_string(); @@ -584,7 +580,7 @@ pub(crate) struct Client { impl Client { // internal implementation of new - async fn new(opts: ClientHandleOptions) -> RosLibRustResult { + async fn new(opts: ClientHandleOptions) -> Result { let (writer, reader) = stubborn_connect(&opts.url).await; let client = Self { reader: RwLock::new(reader), @@ -599,7 +595,7 @@ impl Client { Ok(client) } - async fn handle_message(&self, msg: Message) -> RosLibRustResult<()> { + async fn handle_message(&self, msg: Message) -> Result<()> { match msg { Message::Text(text) => { debug!("got message: {}", text); @@ -693,7 +689,7 @@ impl Client { // Now we need to send the service_response back } - async fn spin_once(&self) -> RosLibRustResult<()> { + async fn spin_once(&self) -> Result<()> { let read = { let mut stream = self.reader.write().await; match stream.next().await { @@ -702,9 +698,7 @@ impl Client { return Err(e.into()); } None => { - return Err(RosLibRustError::Unexpected(anyhow!( - "Wtf does none mean here?" - ))); + return Err(Error::Unexpected(anyhow!("Wtf does none mean here?"))); } } }; @@ -734,7 +728,7 @@ impl Client { } } - async fn reconnect(&mut self) -> RosLibRustResult<()> { + async fn reconnect(&mut self) -> Result<()> { // Reconnect stream let (writer, reader) = stubborn_connect(&self.opts.url).await; self.reader = RwLock::new(reader); @@ -771,7 +765,7 @@ impl Client { async fn stubborn_spin( client: std::sync::Weak>, is_disconnected: Arc, -) -> RosLibRustResult<()> { +) -> Result<()> { debug!("Starting stubborn_spin"); while let Some(client) = client.upgrade() { const SPIN_DURATION: Duration = Duration::from_millis(10); @@ -800,9 +794,9 @@ async fn stubborn_spin( // Implementation of timeout that is a no-op if timeout is 0 or un-configured // Only works on functions that already return our result type // This might not be needed but reading tokio::timeout docs I couldn't confirm this -async fn timeout(timeout: Option, future: F) -> RosLibRustResult +async fn timeout(timeout: Option, future: F) -> Result where - F: futures::Future>, + F: futures::Future>, { if let Some(t) = timeout { tokio::time::timeout(t, future).await? @@ -831,7 +825,7 @@ async fn stubborn_connect(url: &str) -> (Writer, Reader) { } // Basic connection attempt and error wrapping -async fn connect(url: &str) -> RosLibRustResult { +async fn connect(url: &str) -> Result { let attempt = tokio_tungstenite::connect_async(url).await; match attempt { Ok((stream, _response)) => Ok(stream), diff --git a/roslibrust_rosbridge/src/comm.rs b/roslibrust_rosbridge/src/comm.rs index d5826f11..6792521b 100644 --- a/roslibrust_rosbridge/src/comm.rs +++ b/roslibrust_rosbridge/src/comm.rs @@ -1,8 +1,8 @@ -use crate::{RosLibRustResult, Writer}; +use crate::Writer; use anyhow::bail; use futures_util::SinkExt; use log::debug; -use roslibrust_common::RosMessageType; +use roslibrust_common::{Result, RosMessageType}; use serde_json::json; use std::{fmt::Display, str::FromStr, string::ToString}; use tokio_tungstenite::tungstenite::Message; @@ -64,7 +64,7 @@ impl Into<&str> for &Ops { // TODO should replace this with deserialize impl FromStr for Ops { type Err = anyhow::Error; - fn from_str(s: &str) -> Result { + fn from_str(s: &str) -> std::result::Result { Ok(match s { "advertise" => Ops::Advertise, "unadvertise" => Ops::Unadvertise, @@ -88,31 +88,31 @@ impl FromStr for Ops { /// using this trait for mocking. I'm inclined to replace it, and move the /// impls directly into some wrapper around [Writer] pub(crate) trait RosBridgeComm { - async fn subscribe(&mut self, topic: &str, msg_type: &str) -> RosLibRustResult<()>; - async fn unsubscribe(&mut self, topic: &str) -> RosLibRustResult<()>; - async fn publish(&mut self, topic: &str, msg: &T) -> RosLibRustResult<()>; - async fn advertise(&mut self, topic: &str) -> RosLibRustResult<()>; - async fn advertise_str(&mut self, topic: &str, msg_type: &str) -> RosLibRustResult<()>; + async fn subscribe(&mut self, topic: &str, msg_type: &str) -> Result<()>; + async fn unsubscribe(&mut self, topic: &str) -> Result<()>; + async fn publish(&mut self, topic: &str, msg: &T) -> Result<()>; + async fn advertise(&mut self, topic: &str) -> Result<()>; + async fn advertise_str(&mut self, topic: &str, msg_type: &str) -> Result<()>; async fn call_service( &mut self, service: &str, id: &str, req: Req, - ) -> RosLibRustResult<()>; - async fn unadvertise(&mut self, topic: &str) -> RosLibRustResult<()>; - async fn advertise_service(&mut self, topic: &str, srv_type: &str) -> RosLibRustResult<()>; - async fn unadvertise_service(&mut self, topic: &str) -> RosLibRustResult<()>; + ) -> Result<()>; + async fn unadvertise(&mut self, topic: &str) -> Result<()>; + async fn advertise_service(&mut self, topic: &str, srv_type: &str) -> Result<()>; + async fn unadvertise_service(&mut self, topic: &str) -> Result<()>; async fn service_response( &mut self, topic: &str, id: Option, is_success: bool, response: serde_json::Value, - ) -> RosLibRustResult<()>; + ) -> Result<()>; } impl RosBridgeComm for Writer { - async fn subscribe(&mut self, topic: &str, msg_type: &str) -> RosLibRustResult<()> { + async fn subscribe(&mut self, topic: &str, msg_type: &str) -> Result<()> { let msg = json!( { "op": Ops::Subscribe.to_string(), @@ -126,7 +126,7 @@ impl RosBridgeComm for Writer { Ok(()) } - async fn unsubscribe(&mut self, topic: &str) -> RosLibRustResult<()> { + async fn unsubscribe(&mut self, topic: &str) -> Result<()> { let msg = json!( { "op": Ops::Unsubscribe.to_string(), @@ -139,7 +139,7 @@ impl RosBridgeComm for Writer { Ok(()) } - async fn publish(&mut self, topic: &str, msg: &T) -> RosLibRustResult<()> { + async fn publish(&mut self, topic: &str, msg: &T) -> Result<()> { let msg = json!( { "op": Ops::Publish.to_string(), @@ -154,14 +154,14 @@ impl RosBridgeComm for Writer { Ok(()) } - async fn advertise(&mut self, topic: &str) -> RosLibRustResult<()> { + async fn advertise(&mut self, topic: &str) -> Result<()> { self.advertise_str(topic, T::ROS_TYPE_NAME).await } // Identical to advertise, but allows providing a string argument for the topic type // This is important as the type is erased in our list of publishers, and not available // when we try to reconnect - async fn advertise_str(&mut self, topic: &str, topic_type: &str) -> RosLibRustResult<()> { + async fn advertise_str(&mut self, topic: &str, topic_type: &str) -> Result<()> { let msg = json!( { "op": Ops::Advertise.to_string(), @@ -180,7 +180,7 @@ impl RosBridgeComm for Writer { service: &str, id: &str, req: Req, - ) -> RosLibRustResult<()> { + ) -> Result<()> { let msg = json!( { "op": Ops::CallService.to_string(), @@ -195,7 +195,7 @@ impl RosBridgeComm for Writer { Ok(()) } - async fn unadvertise(&mut self, topic: &str) -> RosLibRustResult<()> { + async fn unadvertise(&mut self, topic: &str) -> Result<()> { debug!("Sending unadvertise on {}", topic); let msg = json! { { @@ -209,7 +209,7 @@ impl RosBridgeComm for Writer { Ok(()) } - async fn advertise_service(&mut self, srv_name: &str, srv_type: &str) -> RosLibRustResult<()> { + async fn advertise_service(&mut self, srv_name: &str, srv_type: &str) -> Result<()> { debug!("Sending advertise service on {} w/ {}", srv_name, srv_type); let msg = json! { { @@ -223,7 +223,7 @@ impl RosBridgeComm for Writer { Ok(()) } - async fn unadvertise_service(&mut self, topic: &str) -> RosLibRustResult<()> { + async fn unadvertise_service(&mut self, topic: &str) -> Result<()> { debug!("Sending unadvertise service on {topic}"); let msg = json! { { @@ -242,7 +242,7 @@ impl RosBridgeComm for Writer { id: Option, is_success: bool, response: serde_json::Value, - ) -> RosLibRustResult<()> { + ) -> Result<()> { debug!( "Sending service response on {:?} with {:?}, {:?}, {:?}", topic, id, is_success, response diff --git a/roslibrust_rosbridge/src/integration_tests.rs b/roslibrust_rosbridge/src/integration_tests.rs index 80857911..761cc594 100644 --- a/roslibrust_rosbridge/src/integration_tests.rs +++ b/roslibrust_rosbridge/src/integration_tests.rs @@ -11,7 +11,7 @@ mod integration_tests { use std::sync::Arc; - use crate::{ClientHandle, ClientHandleOptions, RosLibRustError, Subscriber, TestResult}; + use crate::{ClientHandle, ClientHandleOptions, Error, Subscriber, TestResult}; use log::debug; use tokio::time::{timeout, Duration}; // On my laptop test was ~90% reliable at 10ms @@ -309,7 +309,7 @@ mod integration_tests { .store(true, std::sync::atomic::Ordering::Relaxed); let res = client.advertise::