diff --git a/rcldotnet/CMakeLists.txt b/rcldotnet/CMakeLists.txt index f80380fc..257b2751 100644 --- a/rcldotnet/CMakeLists.txt +++ b/rcldotnet/CMakeLists.txt @@ -45,6 +45,8 @@ set(CS_SOURCES MessageStaticMemberCache.cs Node.cs Publisher.cs + QosProfile.cs + QoSProfileDelegates.cs RCLdotnet.cs RCLExceptionHelper.cs RCLRet.cs @@ -66,8 +68,6 @@ set(CS_SOURCES ServiceDefinitionStaticMemberCache.cs Subscription.cs Timer.cs - QoS/QosProfile.cs - QoS/QoSProfileDelegates.cs ) find_package(rcldotnet_common REQUIRED) diff --git a/rcldotnet/QoS/QoSProfileDelegates.cs b/rcldotnet/QoSProfileDelegates.cs similarity index 99% rename from rcldotnet/QoS/QoSProfileDelegates.cs rename to rcldotnet/QoSProfileDelegates.cs index 0530677b..c9666def 100644 --- a/rcldotnet/QoS/QoSProfileDelegates.cs +++ b/rcldotnet/QoSProfileDelegates.cs @@ -17,7 +17,7 @@ using System.Runtime.InteropServices; using ROS2.Utils; -namespace ROS2.Qos +namespace ROS2 { internal struct RmwTime { diff --git a/rcldotnet/QoS/QosProfile.cs b/rcldotnet/QosProfile.cs similarity index 99% rename from rcldotnet/QoS/QosProfile.cs rename to rcldotnet/QosProfile.cs index e55862df..37cfa9ae 100644 --- a/rcldotnet/QoS/QosProfile.cs +++ b/rcldotnet/QosProfile.cs @@ -15,7 +15,6 @@ using System; using System.Threading; -using ROS2.Qos; namespace ROS2 { @@ -208,10 +207,10 @@ private QosProfile( /// /// The default QoS profile. - /// + /// /// Unlikely to change but valid as at 2023-10-31. /// https://github.com/ros2/rmw/blob/rolling/rmw/include/rmw/qos_profiles.h - /// + /// /// | --------------- | --------------- | /// | History | KEEP_LAST | /// | Depth | 10 | @@ -228,7 +227,7 @@ private QosProfile( /// /// Profile for clock messages. /// See CreateClockProfile for more details. - /// + /// /// | --------------- | --------------- | /// | History | KEEP_LAST | /// | Depth | 1 | @@ -244,10 +243,10 @@ private QosProfile( /// /// Profile for parameter event messages. - /// + /// /// Unlikely to change but valid as at 2023-10-31. /// https://github.com/ros2/rmw/blob/rolling/rmw/include/rmw/qos_profiles.h - /// + /// /// | --------------- | --------------- | /// | History | KEEP_LAST | /// | Depth | 1000 | @@ -263,10 +262,10 @@ private QosProfile( /// /// Profile for parameter messages. - /// + /// /// Unlikely to change but valid as at 2023-10-31. /// https://github.com/ros2/rmw/blob/rolling/rmw/include/rmw/qos_profiles.h - /// + /// /// | --------------- | --------------- | /// | History | KEEP_LAST | /// | Depth | 1000 | @@ -282,10 +281,10 @@ private QosProfile( /// /// Profile for sensor messages. - /// + /// /// Unlikely to change but valid as at 2023-10-31. /// https://github.com/ros2/rmw/blob/rolling/rmw/include/rmw/qos_profiles.h - /// + /// /// | --------------- | --------------- | /// | History | KEEP_LAST | /// | Depth | 5 | @@ -301,10 +300,10 @@ private QosProfile( /// /// Default profile for services. - /// + /// /// Unlikely to change but valid as at 2023-10-31. /// https://github.com/ros2/rmw/blob/rolling/rmw/include/rmw/qos_profiles.h - /// + /// /// | --------------- | --------------- | /// | History | KEEP_LAST | /// | Depth | 10 | @@ -320,10 +319,10 @@ private QosProfile( /// /// The system default (null) profile. - /// + /// /// Unlikely to change but valid as at 2023-10-31. /// https://github.com/ros2/rmw/blob/rolling/rmw/include/rmw/qos_profiles.h - /// + /// /// | --------------- | --------------- | /// | History | SYSTEM_DEFAULT | /// | Depth | SYSTEM_DEFAULT |