diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_goal_lla_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_goal_lla_msg_received.py new file mode 100644 index 00000000000000..bf7623862f6136 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_goal_lla_msg_received.py @@ -0,0 +1,153 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +""" +Bring up ArduPilot SITL and check the Goal GeoPointStamped message is being published. + +colcon test --packages-select ardupilot_dds_tests \ +--event-handlers=console_cohesion+ --pytest-args -k test_goal_lla_msg_received + +""" + +import launch_pytest +import math +import pytest +import rclpy +import rclpy.node +from scipy.spatial.transform import Rotation as R +import threading + +from launch import LaunchDescription + +from launch_pytest.tools import process as process_tools + +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy +from rclpy.qos import QoSHistoryPolicy + +from geographic_msgs.msg import GeoPointStamped + +TOPIC = "ap/goal_lla" + + +class GeoPointListener(rclpy.node.Node): + """Subscribe to GeoPointStamped messages.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("geopoint_listener") + self.msg_event_object = threading.Event() + + # Declare and acquire `topic` parameter + self.declare_parameter("topic", TOPIC) + self.topic = self.get_parameter("topic").get_parameter_value().string_value + + def start_subscriber(self): + """Start the subscriber.""" + qos_profile = QoSProfile( + reliability=QoSReliabilityPolicy.BEST_EFFORT, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1, + ) + + self.subscription = self.create_subscription(GeoPointStamped, self.topic, self.subscriber_callback, qos_profile) + + # Add a spin thread. + self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,)) + self.ros_spin_thread.start() + + def subscriber_callback(self, msg): + """Process a GeoPointStamped message.""" + self.msg_event_object.set() + + +@launch_pytest.fixture +def launch_sitl_copter_dds_serial(sitl_copter_dds_serial): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_serial + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + + +@launch_pytest.fixture +def launch_sitl_copter_dds_udp(sitl_copter_dds_udp): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_udp + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_serial) +def test_dds_serial_geopose_msg_recv(launch_context, launch_sitl_copter_dds_serial): + """Test position messages are published by AP_DDS.""" + _, actions = launch_sitl_copter_dds_serial + virtual_ports = actions["virtual_ports"].action + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, virtual_ports, timeout=2) + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = GeoPointListener() + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=10.0) + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." + finally: + rclpy.shutdown() + yield + + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_udp) +def test_dds_udp_geopose_msg_recv(launch_context, launch_sitl_copter_dds_udp): + """Test position messages are published by AP_DDS.""" + _, actions = launch_sitl_copter_dds_udp + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = GeoPointListener() + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=10.0) + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." + finally: + rclpy.shutdown() + yield diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 5ef37ca24895b8..db5d6ebdfe8950 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -29,6 +29,9 @@ #include "AP_DDS_Service_Table.h" #include "AP_DDS_External_Odom.h" +static constexpr double lat_lon_scale_factor = 1e-7; +static constexpr double alt_scale_factor = 0.01; + // Enable DDS at runtime by default static constexpr uint8_t ENABLED_BY_DEFAULT = 1; #if AP_DDS_TIME_PUB_ENABLED @@ -52,6 +55,9 @@ static constexpr uint16_t DELAY_AIRSPEED_TOPIC_MS = 33; #if AP_DDS_GEOPOSE_PUB_ENABLED static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = 33; #endif // AP_DDS_GEOPOSE_PUB_ENABLED +#if AP_DDS_GOAL_PUB_ENABLED +static constexpr uint16_t DELAY_GOAL_TOPIC_MS = 200; +#endif // AP_DDS_GOAL_PUB_ENABLED #if AP_DDS_CLOCK_PUB_ENABLED static constexpr uint16_t DELAY_CLOCK_TOPIC_MS = 10; #endif // AP_DDS_CLOCK_PUB_ENABLED @@ -526,6 +532,19 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg) } #endif // AP_DDS_GEOPOSE_PUB_ENABLED +#if AP_DDS_GOAL_PUB_ENABLED +void AP_DDS_Client::update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg) +{ + const auto &vehicle = AP::vehicle(); + update_topic(msg.header.stamp); + Location target_loc; + vehicle->get_target_location(target_loc); + msg.position.latitude = target_loc.lat * lat_lon_scale_factor; + msg.position.longitude = target_loc.lng * lat_lon_scale_factor; + msg.position.altitude = target_loc.alt * alt_scale_factor; +} +#endif // AP_DDS_GOAL_PUB_ENABLED + #if AP_DDS_IMU_PUB_ENABLED void AP_DDS_Client::update_topic(sensor_msgs_msg_Imu& msg) { @@ -1242,6 +1261,22 @@ void AP_DDS_Client::write_gps_global_origin_topic() } #endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +#if AP_DDS_GOAL_PUB_ENABLED +void AP_DDS_Client::write_goal_topic() +{ + WITH_SEMAPHORE(csem); + if (connected) { + ucdrBuffer ub {}; + const uint32_t topic_size = geographic_msgs_msg_GeoPointStamped_size_of_topic(&goal_topic, 0); + uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::GOAL_PUB)].dw_id, &ub, topic_size); + const bool success = geographic_msgs_msg_GeoPointStamped_serialize_topic(&ub, &goal_topic); + if (!success) { + // AP_HAL::panic("FATAL: DDS_Client failed to serialize\n"); + } + } +} +#endif // AP_DDS_GOAL_PUB_ENABLED + void AP_DDS_Client::update() { WITH_SEMAPHORE(csem); @@ -1318,6 +1353,13 @@ void AP_DDS_Client::update() write_gps_global_origin_topic(); } #endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +#if AP_DDS_GOAL_PUB_ENABLED + if (cur_time_ms - last_goal_time_ms > DELAY_GOAL_TOPIC_MS) { + update_topic_goal(goal_topic); + last_goal_time_ms = cur_time_ms; + write_goal_topic(); + } +#endif // AP_DDS_GOAL_PUB_ENABLED status_ok = uxr_run_session_time(&session, 1); } diff --git a/libraries/AP_DDS/AP_DDS_Client.h b/libraries/AP_DDS/AP_DDS_Client.h index 005b87f30aa213..31c45c2faad7be 100644 --- a/libraries/AP_DDS/AP_DDS_Client.h +++ b/libraries/AP_DDS/AP_DDS_Client.h @@ -103,6 +103,15 @@ class AP_DDS_Client static void update_topic(geographic_msgs_msg_GeoPointStamped& msg); # endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +#if AP_DDS_GOAL_PUB_ENABLED + geographic_msgs_msg_GeoPointStamped goal_topic; + // The last ms timestamp AP_DDS wrote a gps global origin message + uint64_t last_goal_time_ms; + //! @brief Serialize the current gps global origin and publish to the IO stream(s) + void write_goal_topic(); + static void update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg); +# endif // AP_DDS_GOAL_PUB_ENABLED + #if AP_DDS_GEOPOSE_PUB_ENABLED geographic_msgs_msg_GeoPoseStamped geo_pose_topic; // The last ms timestamp AP_DDS wrote a GeoPose message diff --git a/libraries/AP_DDS/AP_DDS_Topic_Table.h b/libraries/AP_DDS/AP_DDS_Topic_Table.h index 05d68e0c78e3ff..6b8d059c54c7b9 100644 --- a/libraries/AP_DDS/AP_DDS_Topic_Table.h +++ b/libraries/AP_DDS/AP_DDS_Topic_Table.h @@ -42,6 +42,9 @@ enum class TopicIndex: uint8_t { #if AP_DDS_GEOPOSE_PUB_ENABLED GEOPOSE_PUB, #endif // AP_DDS_GEOPOSE_PUB_ENABLED +#ifdef AP_DDS_GOAL_PUB_ENABLED + GOAL_PUB, +#endif // AP_DDS_GOAL_PUB_ENABLED #if AP_DDS_CLOCK_PUB_ENABLED CLOCK_PUB, #endif // AP_DDS_CLOCK_PUB_ENABLED @@ -232,6 +235,24 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = { }, }, #endif // AP_DDS_GEOPOSE_PUB_ENABLED +#if AP_DDS_GOAL_PUB_ENABLED + { + .topic_id = to_underlying(TopicIndex::GOAL_PUB), + .pub_id = to_underlying(TopicIndex::GOAL_PUB), + .sub_id = to_underlying(TopicIndex::GOAL_PUB), + .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAWRITER_ID}, + .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAREADER_ID}, + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/goal_lla", + .type_name = "geographic_msgs::msg::dds_::GeoPointStamped_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, + }, +#endif // AP_DDS_GOAL_PUB_ENABLED #if AP_DDS_CLOCK_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::CLOCK_PUB), diff --git a/libraries/AP_DDS/AP_DDS_config.h b/libraries/AP_DDS/AP_DDS_config.h index 2e0d3d6264f8c5..0fd40c74218f60 100644 --- a/libraries/AP_DDS/AP_DDS_config.h +++ b/libraries/AP_DDS/AP_DDS_config.h @@ -66,6 +66,10 @@ #define AP_DDS_CLOCK_PUB_ENABLED 1 #endif +#ifndef AP_DDS_GOAL_PUB_ENABLED +#define AP_DDS_GOAL_PUB_ENABLED 1 +#endif + #ifndef AP_DDS_JOY_SUB_ENABLED #define AP_DDS_JOY_SUB_ENABLED 1 #endif