Path: blob/master/libraries/AP_DDS/AP_DDS_Client.cpp
9417 views
#include <AP_HAL/AP_HAL_Boards.h>12#include "AP_DDS_config.h"3#if AP_DDS_ENABLED4#include <uxr/client/util/ping.h>56#if AP_DDS_NEEDS_GPS7#include <AP_GPS/AP_GPS.h>8#endif // AP_DDS_NEEDS_GPS9#include <AP_HAL/AP_HAL.h>10#include <RC_Channel/RC_Channel.h>11#include <AP_RTC/AP_RTC.h>12#include <AP_Math/AP_Math.h>13#include <AP_InertialSensor/AP_InertialSensor.h>14#include <GCS_MAVLink/GCS.h>15#include <AP_BattMonitor/AP_BattMonitor.h>16#include <AP_AHRS/AP_AHRS.h>17#if AP_DDS_ARM_SERVER_ENABLED18#include <AP_Arming/AP_Arming.h>19# endif // AP_DDS_ARM_SERVER_ENABLED20#include <AP_Vehicle/AP_Vehicle.h>21#include <AP_Common/AP_FWVersion.h>22#include <AP_ExternalControl/AP_ExternalControl_config.h>2324#if AP_DDS_ARM_SERVER_ENABLED25#include "ardupilot_msgs/srv/ArmMotors.h"26#endif // AP_DDS_ARM_SERVER_ENABLED27#if AP_DDS_MODE_SWITCH_SERVER_ENABLED28#include "ardupilot_msgs/srv/ModeSwitch.h"29#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED30#if AP_DDS_ARM_CHECK_SERVER_ENABLED31#include "std_srvs/srv/Trigger.h"32#endif // AP_DDS_ARM_CHECK_SERVER_ENABLED33#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED34#include "ardupilot_msgs/srv/Takeoff.h"35#endif // AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED36#if AP_DDS_RC_PUB_ENABLED37#include "AP_RSSI/AP_RSSI.h"38#endif // AP_DDS_RC_PUB_ENABLED3940#if AP_EXTERNAL_CONTROL_ENABLED41#include "AP_DDS_ExternalControl.h"42#endif // AP_EXTERNAL_CONTROL_ENABLED43#include "AP_DDS_Frames.h"4445#include "AP_DDS_Client.h"46#include "AP_DDS_Topic_Table.h"47#include "AP_DDS_Service_Table.h"48#include "AP_DDS_External_Odom.h"4950#define STRCPY(D,S) strncpy(D, S, ARRAY_SIZE(D))5152// Enable DDS at runtime by default53static constexpr uint8_t ENABLED_BY_DEFAULT = 1;54#if AP_DDS_TIME_PUB_ENABLED55static constexpr uint16_t DELAY_TIME_TOPIC_MS = AP_DDS_DELAY_TIME_TOPIC_MS;56#endif // AP_DDS_TIME_PUB_ENABLED57#if AP_DDS_BATTERY_STATE_PUB_ENABLED58static constexpr uint16_t DELAY_BATTERY_STATE_TOPIC_MS = AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS;59#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED60#if AP_DDS_IMU_PUB_ENABLED61static constexpr uint16_t DELAY_IMU_TOPIC_MS = AP_DDS_DELAY_IMU_TOPIC_MS;62#endif // AP_DDS_IMU_PUB_ENABLED63#if AP_DDS_LOCAL_POSE_PUB_ENABLED64static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS;65#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED66#if AP_DDS_LOCAL_VEL_PUB_ENABLED67static constexpr uint16_t DELAY_LOCAL_VELOCITY_TOPIC_MS = AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS;68#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED69#if AP_DDS_AIRSPEED_PUB_ENABLED70static constexpr uint16_t DELAY_AIRSPEED_TOPIC_MS = AP_DDS_DELAY_AIRSPEED_TOPIC_MS;71#endif // AP_DDS_AIRSPEED_PUB_ENABLED72#if AP_DDS_RC_PUB_ENABLED73static constexpr uint16_t DELAY_RC_TOPIC_MS = AP_DDS_DELAY_RC_TOPIC_MS;74#endif // AP_DDS_RC_PUB_ENABLED75#if AP_DDS_GEOPOSE_PUB_ENABLED76static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = AP_DDS_DELAY_GEO_POSE_TOPIC_MS;77#endif // AP_DDS_GEOPOSE_PUB_ENABLED78#if AP_DDS_GOAL_PUB_ENABLED79static constexpr uint16_t DELAY_GOAL_TOPIC_MS = AP_DDS_DELAY_GOAL_TOPIC_MS ;80#endif // AP_DDS_GOAL_PUB_ENABLED81#if AP_DDS_CLOCK_PUB_ENABLED82static constexpr uint16_t DELAY_CLOCK_TOPIC_MS =AP_DDS_DELAY_CLOCK_TOPIC_MS;83#endif // AP_DDS_CLOCK_PUB_ENABLED84#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED85static constexpr uint16_t DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS = AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS;86#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED87static constexpr uint16_t DELAY_PING_MS = 500;88#if AP_DDS_STATUS_PUB_ENABLED89static constexpr uint16_t DELAY_STATUS_TOPIC_MS = AP_DDS_DELAY_STATUS_TOPIC_MS;90#endif // AP_DDS_STATUS_PUB_ENABLED9192// Define the subscriber data members, which are static class scope.93// If these are created on the stack in the subscriber,94// the AP_DDS_Client::on_topic frame size is exceeded.95#if AP_DDS_JOY_SUB_ENABLED96sensor_msgs_msg_Joy AP_DDS_Client::rx_joy_topic {};97#endif // AP_DDS_JOY_SUB_ENABLED98#if AP_DDS_DYNAMIC_TF_SUB_ENABLED99tf2_msgs_msg_TFMessage AP_DDS_Client::rx_dynamic_transforms_topic {};100#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED101#if AP_DDS_VEL_CTRL_ENABLED102geometry_msgs_msg_TwistStamped AP_DDS_Client::rx_velocity_control_topic {};103#endif // AP_DDS_VEL_CTRL_ENABLED104#if AP_DDS_GLOBAL_POS_CTRL_ENABLED105ardupilot_msgs_msg_GlobalPosition AP_DDS_Client::rx_global_position_control_topic {};106#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED107108// Define the parameter server data members, which are static class scope.109// If these are created on the stack, then the AP_DDS_Client::on_request110// frame size is exceeded.111#if AP_DDS_PARAMETER_SERVER_ENABLED112rcl_interfaces_srv_SetParameters_Request AP_DDS_Client::set_parameter_request {};113rcl_interfaces_srv_SetParameters_Response AP_DDS_Client::set_parameter_response {};114rcl_interfaces_srv_GetParameters_Request AP_DDS_Client::get_parameters_request {};115rcl_interfaces_srv_GetParameters_Response AP_DDS_Client::get_parameters_response {};116rcl_interfaces_msg_Parameter AP_DDS_Client::param {};117#endif118119const AP_Param::GroupInfo AP_DDS_Client::var_info[] {120121// @Param: _ENABLE122// @DisplayName: DDS enable123// @Description: Enable DDS subsystem124// @Values: 0:Disabled,1:Enabled125// @RebootRequired: True126// @User: Advanced127AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_DDS_Client, enabled, ENABLED_BY_DEFAULT, AP_PARAM_FLAG_ENABLE),128129#if AP_DDS_UDP_ENABLED130// @Param: _UDP_PORT131// @DisplayName: DDS UDP port132// @Description: UDP port number for DDS133// @Range: 1 65535134// @RebootRequired: True135// @User: Standard136AP_GROUPINFO("_UDP_PORT", 2, AP_DDS_Client, udp.port, 2019),137138// @Group: _IP139// @Path: ../AP_Networking/AP_Networking_address.cpp140AP_SUBGROUPINFO(udp.ip, "_IP", 3, AP_DDS_Client, AP_Networking_IPV4),141142#endif143144// @Param: _DOMAIN_ID145// @DisplayName: DDS DOMAIN ID146// @Description: Set the ROS_DOMAIN_ID147// @Range: 0 232148// @RebootRequired: True149// @User: Standard150AP_GROUPINFO("_DOMAIN_ID", 4, AP_DDS_Client, domain_id, 0),151152// @Param: _TIMEOUT_MS153// @DisplayName: DDS ping timeout154// @Description: The time in milliseconds the DDS client will wait for a response from the XRCE agent before reattempting.155// @Units: ms156// @Range: 1 10000157// @RebootRequired: True158// @Increment: 1159// @User: Standard160AP_GROUPINFO("_TIMEOUT_MS", 5, AP_DDS_Client, ping_timeout_ms, 1000),161162// @Param: _MAX_RETRY163// @DisplayName: DDS ping max attempts164// @Description: The maximum number of times the DDS client will attempt to ping the XRCE agent before exiting. Set to 0 to allow unlimited retries.165// @Range: 0 100166// @RebootRequired: True167// @Increment: 1168// @User: Standard169AP_GROUPINFO("_MAX_RETRY", 6, AP_DDS_Client, ping_max_retry, 10),170171AP_GROUPEND172};173174#if AP_DDS_STATIC_TF_PUB_ENABLED | AP_DDS_LOCAL_POSE_PUB_ENABLED | AP_DDS_GEOPOSE_PUB_ENABLED | AP_DDS_IMU_PUB_ENABLED175static void initialize(geometry_msgs_msg_Quaternion& q)176{177q.x = 0.0;178q.y = 0.0;179q.z = 0.0;180q.w = 1.0;181}182#endif // AP_DDS_STATIC_TF_PUB_ENABLED | AP_DDS_LOCAL_POSE_PUB_ENABLED | AP_DDS_GEOPOSE_PUB_ENABLED | AP_DDS_IMU_PUB_ENABLED183184AP_DDS_Client::~AP_DDS_Client()185{186// close transport187if (is_using_serial) {188uxr_close_custom_transport(&serial.transport);189} else {190#if AP_DDS_UDP_ENABLED191uxr_close_custom_transport(&udp.transport);192#endif193}194}195196#if AP_DDS_TIME_PUB_ENABLED197void AP_DDS_Client::update_topic(builtin_interfaces_msg_Time& msg)198{199uint64_t utc_usec;200if (!AP::rtc().get_utc_usec(utc_usec)) {201utc_usec = AP_HAL::micros64();202}203msg.sec = utc_usec / 1000000ULL;204msg.nanosec = (utc_usec % 1000000ULL) * 1000UL;205206}207#endif // AP_DDS_TIME_PUB_ENABLED208209#if AP_DDS_NAVSATFIX_PUB_ENABLED210bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance)211{212// Add a lambda that takes in navsatfix msg and populates the cov213// Make it constexpr if possible214// https://www.fluentcpp.com/2021/12/13/the-evolutions-of-lambdas-in-c14-c17-and-c20/215// constexpr auto times2 = [] (sensor_msgs_msg_NavSatFix* msg) { return n * 2; };216217auto &gps = AP::gps();218WITH_SEMAPHORE(gps.get_semaphore());219if (!gps.is_healthy(instance)) {220msg.status.status = -1; // STATUS_NO_FIX221msg.status.service = 0; // No services supported222msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN223return false;224}225226// No update is needed227const auto last_fix_time_ms = gps.last_fix_time_ms(instance);228if (last_nav_sat_fix_time_ms[instance] == last_fix_time_ms) {229return false;230} else {231last_nav_sat_fix_time_ms[instance] = last_fix_time_ms;232}233234update_topic(msg.header.stamp);235static_assert(GPS_MAX_RECEIVERS <= 9, "GPS_MAX_RECEIVERS is greater than 9");236hal.util->snprintf(msg.header.frame_id, 2, "%u", instance);237msg.status.service = 0; // SERVICE_GPS238msg.status.status = -1; // STATUS_NO_FIX239240241//! @todo What about glonass, compass, galileo?242//! This will be properly designed and implemented to spec in #23277243msg.status.service = 1; // SERVICE_GPS244245const auto status = gps.status(instance);246switch (status) {247case AP_GPS::NO_GPS:248case AP_GPS::NO_FIX:249msg.status.status = -1; // STATUS_NO_FIX250msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN251return true;252case AP_GPS::GPS_OK_FIX_2D:253case AP_GPS::GPS_OK_FIX_3D:254msg.status.status = 0; // STATUS_FIX255break;256case AP_GPS::GPS_OK_FIX_3D_DGPS:257msg.status.status = 1; // STATUS_SBAS_FIX258break;259case AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT:260case AP_GPS::GPS_OK_FIX_3D_RTK_FIXED:261msg.status.status = 2; // STATUS_SBAS_FIX262break;263default:264//! @todo Can we not just use an enum class and not worry about this condition?265break;266}267const auto loc = gps.location(instance);268msg.latitude = loc.lat * 1E-7;269msg.longitude = loc.lng * 1E-7;270271int32_t alt_cm;272if (!loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_cm)) {273// With absolute frame, this condition is unlikely274msg.status.status = -1; // STATUS_NO_FIX275msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN276return true;277}278msg.altitude = alt_cm * 0.01;279280// ROS allows double precision, ArduPilot exposes float precision today281Matrix3f cov;282msg.position_covariance_type = (uint8_t)gps.position_covariance(instance, cov);283msg.position_covariance[0] = cov[0][0];284msg.position_covariance[1] = cov[0][1];285msg.position_covariance[2] = cov[0][2];286msg.position_covariance[3] = cov[1][0];287msg.position_covariance[4] = cov[1][1];288msg.position_covariance[5] = cov[1][2];289msg.position_covariance[6] = cov[2][0];290msg.position_covariance[7] = cov[2][1];291msg.position_covariance[8] = cov[2][2];292293return true;294}295#endif // AP_DDS_NAVSATFIX_PUB_ENABLED296297#if AP_DDS_STATIC_TF_PUB_ENABLED298void AP_DDS_Client::populate_static_transforms(tf2_msgs_msg_TFMessage& msg)299{300msg.transforms_size = 0;301302auto &gps = AP::gps();303for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {304const auto gps_type = gps.get_type(i);305if (gps_type == AP_GPS::GPS_Type::GPS_TYPE_NONE) {306continue;307}308update_topic(msg.transforms[i].header.stamp);309char gps_frame_id[16];310//! @todo should GPS frame ID's be 0 or 1 indexed in ROS?311hal.util->snprintf(gps_frame_id, sizeof(gps_frame_id), "GPS_%u", i);312STRCPY(msg.transforms[i].header.frame_id, BASE_LINK_FRAME_ID);313STRCPY(msg.transforms[i].child_frame_id, gps_frame_id);314// The body-frame offsets315// X - Forward316// Y - Right317// Z - Down318// https://ardupilot.org/copter/docs/common-sensor-offset-compensation.html#sensor-position-offset-compensation319320const auto offset = gps.get_antenna_offset(i);321322// In ROS REP 103, it follows this convention323// X - Forward324// Y - Left325// Z - Up326// https://www.ros.org/reps/rep-0103.html#axis-orientation327328msg.transforms[i].transform.translation.x = offset[0];329msg.transforms[i].transform.translation.y = -1 * offset[1];330msg.transforms[i].transform.translation.z = -1 * offset[2];331332// Ensure rotation is initialized.333initialize(msg.transforms[i].transform.rotation);334335msg.transforms_size++;336}337338}339#endif // AP_DDS_STATIC_TF_PUB_ENABLED340341#if AP_DDS_BATTERY_STATE_PUB_ENABLED342void AP_DDS_Client::update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_t instance)343{344if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) {345return;346}347static_assert(AP_BATT_MONITOR_MAX_INSTANCES <= 99, "AP_BATT_MONITOR_MAX_INSTANCES is greater than 99");348349update_topic(msg.header.stamp);350hal.util->snprintf(msg.header.frame_id, 2, "%u", instance);351352auto &battery = AP::battery();353354if (!battery.healthy(instance)) {355msg.power_supply_status = 3; //POWER_SUPPLY_HEALTH_DEAD356msg.present = false;357return;358}359msg.present = true;360361msg.voltage = battery.voltage(instance);362363float temperature;364msg.temperature = (battery.get_temperature(temperature, instance)) ? temperature : NAN;365366float current;367msg.current = (battery.current_amps(current, instance)) ? -1 * current : NAN;368369const float design_capacity = (float)battery.pack_capacity_mah(instance) * 0.001;370msg.design_capacity = design_capacity;371372uint8_t percentage;373if (battery.capacity_remaining_pct(percentage, instance)) {374msg.percentage = percentage * 0.01;375msg.charge = (percentage * design_capacity) * 0.01;376} else {377msg.percentage = NAN;378msg.charge = NAN;379}380381msg.capacity = NAN;382383if (battery.current_amps(current, instance)) {384if (percentage == 100) {385msg.power_supply_status = 4; //POWER_SUPPLY_STATUS_FULL386} else if (is_negative(current)) {387msg.power_supply_status = 1; //POWER_SUPPLY_STATUS_CHARGING388} else if (is_positive(current)) {389msg.power_supply_status = 2; //POWER_SUPPLY_STATUS_DISCHARGING390} else {391msg.power_supply_status = 3; //POWER_SUPPLY_STATUS_NOT_CHARGING392}393} else {394msg.power_supply_status = 0; //POWER_SUPPLY_STATUS_UNKNOWN395}396397msg.power_supply_health = (battery.overpower_detected(instance)) ? 4 : 1; //POWER_SUPPLY_HEALTH_OVERVOLTAGE or POWER_SUPPLY_HEALTH_GOOD398399msg.power_supply_technology = 0; //POWER_SUPPLY_TECHNOLOGY_UNKNOWN400401if (battery.has_cell_voltages(instance)) {402const auto &cells = battery.get_cell_voltages(instance);403const uint8_t ncells_max = MIN(ARRAY_SIZE(msg.cell_voltage), ARRAY_SIZE(cells.cells));404for (uint8_t i=0; i< ncells_max; i++) {405msg.cell_voltage[i] = cells.cells[i] * 0.001;406}407}408}409#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED410411#if AP_DDS_LOCAL_POSE_PUB_ENABLED412void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg)413{414update_topic(msg.header.stamp);415STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);416417auto &ahrs = AP::ahrs();418WITH_SEMAPHORE(ahrs.get_semaphore());419420// ROS REP 103 uses the ENU convention:421// X - East422// Y - North423// Z - Up424// https://www.ros.org/reps/rep-0103.html#axis-orientation425// AP_AHRS uses the NED convention426// X - North427// Y - East428// Z - Down429// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,430// as well as invert Z431432Vector3f position;433if (ahrs.get_relative_position_NED_home(position)) {434msg.pose.position.x = position[1];435msg.pose.position.y = position[0];436msg.pose.position.z = -position[2];437}438439// In ROS REP 103, axis orientation uses the following convention:440// X - Forward441// Y - Left442// Z - Up443// https://www.ros.org/reps/rep-0103.html#axis-orientation444// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,445// as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis446// for x to point forward447Quaternion orientation;448if (ahrs.get_quaternion(orientation)) {449Quaternion aux(orientation[0], orientation[2], orientation[1], -orientation[3]); //NED to ENU transformation450Quaternion transformation (sqrtF(2) * 0.5,0,0,sqrtF(2) * 0.5); // Z axis 90 degree rotation451orientation = aux * transformation;452msg.pose.orientation.w = orientation[0];453msg.pose.orientation.x = orientation[1];454msg.pose.orientation.y = orientation[2];455msg.pose.orientation.z = orientation[3];456} else {457initialize(msg.pose.orientation);458}459}460#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED461462#if AP_DDS_LOCAL_VEL_PUB_ENABLED463void AP_DDS_Client::update_topic(geometry_msgs_msg_TwistStamped& msg)464{465update_topic(msg.header.stamp);466STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);467468auto &ahrs = AP::ahrs();469WITH_SEMAPHORE(ahrs.get_semaphore());470471// ROS REP 103 uses the ENU convention:472// X - East473// Y - North474// Z - Up475// https://www.ros.org/reps/rep-0103.html#axis-orientation476// AP_AHRS uses the NED convention477// X - North478// Y - East479// Z - Down480// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,481// as well as invert Z482Vector3f velocity;483if (ahrs.get_velocity_NED(velocity)) {484msg.twist.linear.x = velocity[1];485msg.twist.linear.y = velocity[0];486msg.twist.linear.z = -velocity[2];487}488489// In ROS REP 103, axis orientation uses the following convention:490// X - Forward491// Y - Left492// Z - Up493// https://www.ros.org/reps/rep-0103.html#axis-orientation494// The gyro data is received from AP_AHRS in body-frame495// X - Forward496// Y - Right497// Z - Down498// As a consequence, to follow ROS REP 103, it is necessary to invert Y and Z499Vector3f angular_velocity = ahrs.get_gyro();500msg.twist.angular.x = angular_velocity[0];501msg.twist.angular.y = -angular_velocity[1];502msg.twist.angular.z = -angular_velocity[2];503}504#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED505#if AP_DDS_AIRSPEED_PUB_ENABLED506bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Airspeed& msg)507{508update_topic(msg.header.stamp);509STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);510auto &ahrs = AP::ahrs();511WITH_SEMAPHORE(ahrs.get_semaphore());512// In ROS REP 103, axis orientation uses the following convention:513// X - Forward514// Y - Left515// Z - Up516// https://www.ros.org/reps/rep-0103.html#axis-orientation517// The true airspeed data is received from AP_AHRS in body-frame518// X - Forward519// Y - Right520// Z - Down521// As a consequence, to follow ROS REP 103, it is necessary to invert Y and Z522Vector3f true_airspeed_vec_bf;523bool is_airspeed_available {false};524if (ahrs.airspeed_vector_TAS(true_airspeed_vec_bf)) {525msg.true_airspeed.x = true_airspeed_vec_bf[0];526msg.true_airspeed.y = -true_airspeed_vec_bf[1];527msg.true_airspeed.z = -true_airspeed_vec_bf[2];528msg.eas_2_tas = ahrs.get_EAS2TAS();529is_airspeed_available = true;530}531return is_airspeed_available;532}533#endif // AP_DDS_AIRSPEED_PUB_ENABLED534535#if AP_DDS_RC_PUB_ENABLED536bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Rc& msg)537{538update_topic(msg.header.stamp);539AP_RSSI *ap_rssi = AP_RSSI::get_singleton();540auto rc = RC_Channels::get_singleton();541static int16_t counter = 0;542543// Is connected if not in failsafe.544// This is only valid if the RC has been connected at least once545msg.is_connected = !rc->in_rc_failsafe();546// Receiver RSSI is reported between 0.0 and 1.0.547msg.receiver_rssi = static_cast<uint8_t>(ap_rssi->read_receiver_rssi()*100.f);548549// Limit the max number of available channels to 8550msg.channels_size = MIN(static_cast<uint32_t>(rc->get_valid_channel_count()), 32U);551msg.active_overrides_size = msg.channels_size;552if (msg.channels_size) {553for (uint8_t i = 0; i < static_cast<uint8_t>(msg.channels_size); i++) {554msg.channels[i] = rc->rc_channel(i)->get_radio_in();555msg.active_overrides[i] = rc->rc_channel(i)->has_override();556}557} else {558// If no channels are available, the RC is disconnected.559msg.is_connected = false;560}561562// Return true if Radio is connected, or once every 10 steps to reduce useless traffic.563return msg.is_connected ? true : (counter++ % 10 == 0);564}565#endif // AP_DDS_RC_PUB_ENABLED566567#if AP_DDS_GEOPOSE_PUB_ENABLED568void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg)569{570update_topic(msg.header.stamp);571STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);572573auto &ahrs = AP::ahrs();574WITH_SEMAPHORE(ahrs.get_semaphore());575576Location loc;577if (ahrs.get_location(loc)) {578msg.pose.position.latitude = loc.lat * 1E-7;579msg.pose.position.longitude = loc.lng * 1E-7;580// TODO this is assumed to be absolute frame in WGS-84 as per the GeoPose message definition in ROS.581// Use loc.get_alt_frame() to convert if necessary.582msg.pose.position.altitude = loc.alt * 0.01; // Transform from cm to m583}584585// In ROS REP 103, axis orientation uses the following convention:586// X - Forward587// Y - Left588// Z - Up589// https://www.ros.org/reps/rep-0103.html#axis-orientation590// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,591// as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis592// for x to point forward593Quaternion orientation;594if (ahrs.get_quaternion(orientation)) {595Quaternion aux(orientation[0], orientation[2], orientation[1], -orientation[3]); //NED to ENU transformation596Quaternion transformation(sqrtF(2) * 0.5, 0, 0, sqrtF(2) * 0.5); // Z axis 90 degree rotation597orientation = aux * transformation;598msg.pose.orientation.w = orientation[0];599msg.pose.orientation.x = orientation[1];600msg.pose.orientation.y = orientation[2];601msg.pose.orientation.z = orientation[3];602} else {603initialize(msg.pose.orientation);604}605}606#endif // AP_DDS_GEOPOSE_PUB_ENABLED607608#if AP_DDS_GOAL_PUB_ENABLED609bool AP_DDS_Client::update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg)610{611const auto &vehicle = AP::vehicle();612update_topic(msg.header.stamp);613Location target_loc;614// Exit if no target is available.615if (!vehicle->get_target_location(target_loc)) {616return false;617}618target_loc.change_alt_frame(Location::AltFrame::ABSOLUTE);619msg.position.latitude = target_loc.lat * 1e-7;620msg.position.longitude = target_loc.lng * 1e-7;621msg.position.altitude = target_loc.alt * 1e-2;622623// Check whether the goal has changed or if the topic has never been published.624const double tolerance_lat_lon = 1e-8; // One order of magnitude smaller than the target's resolution.625const double distance_alt = 1e-3;626if (abs(msg.position.latitude - prev_goal_msg.position.latitude) > tolerance_lat_lon ||627abs(msg.position.longitude - prev_goal_msg.position.longitude) > tolerance_lat_lon ||628abs(msg.position.altitude - prev_goal_msg.position.altitude) > distance_alt ||629prev_goal_msg.header.stamp.sec == 0 ) {630update_topic(prev_goal_msg.header.stamp);631prev_goal_msg.position.latitude = msg.position.latitude;632prev_goal_msg.position.longitude = msg.position.longitude;633prev_goal_msg.position.altitude = msg.position.altitude;634return true;635} else {636return false;637}638}639#endif // AP_DDS_GOAL_PUB_ENABLED640641#if AP_DDS_IMU_PUB_ENABLED642void AP_DDS_Client::update_topic(sensor_msgs_msg_Imu& msg)643{644update_topic(msg.header.stamp);645STRCPY(msg.header.frame_id, BASE_LINK_NED_FRAME_ID);646647auto &imu = AP::ins();648auto &ahrs = AP::ahrs();649650WITH_SEMAPHORE(ahrs.get_semaphore());651652Quaternion orientation;653if (ahrs.get_quaternion(orientation)) {654msg.orientation.x = orientation[0];655msg.orientation.y = orientation[1];656msg.orientation.z = orientation[2];657msg.orientation.w = orientation[3];658} else {659initialize(msg.orientation);660}661662uint8_t accel_index = ahrs.get_primary_accel_index();663uint8_t gyro_index = ahrs.get_primary_gyro_index();664const Vector3f accel_data = imu.get_accel(accel_index);665const Vector3f gyro_data = imu.get_gyro(gyro_index);666667// Populate the message fields668msg.linear_acceleration.x = accel_data.x;669msg.linear_acceleration.y = accel_data.y;670msg.linear_acceleration.z = accel_data.z;671672msg.angular_velocity.x = gyro_data.x;673msg.angular_velocity.y = gyro_data.y;674msg.angular_velocity.z = gyro_data.z;675}676#endif // AP_DDS_IMU_PUB_ENABLED677678#if AP_DDS_CLOCK_PUB_ENABLED679void AP_DDS_Client::update_topic(rosgraph_msgs_msg_Clock& msg)680{681update_topic(msg.clock);682}683#endif // AP_DDS_CLOCK_PUB_ENABLED684685#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED686void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPointStamped& msg)687{688update_topic(msg.header.stamp);689STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);690691auto &ahrs = AP::ahrs();692WITH_SEMAPHORE(ahrs.get_semaphore());693694Location ekf_origin;695// LLA is WGS-84 geodetic coordinate.696// Altitude converted from cm to m.697if (ahrs.get_origin(ekf_origin)) {698msg.position.latitude = ekf_origin.lat * 1E-7;699msg.position.longitude = ekf_origin.lng * 1E-7;700msg.position.altitude = ekf_origin.alt * 0.01;701}702}703#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED704705#if AP_DDS_STATUS_PUB_ENABLED706bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Status& msg)707{708// Fill the new message.709const auto &vehicle = AP::vehicle();710const auto &battery = AP::battery();711msg.vehicle_type = static_cast<uint8_t>(AP::fwversion().vehicle_type);712msg.armed = hal.util->get_soft_armed();713msg.mode = vehicle->get_mode();714msg.flying = vehicle->get_likely_flying();715msg.external_control = true; // Always true for now. To be filled after PR#28429.716uint8_t fs_iter = 0;717msg.failsafe_size = 0;718if (rc().in_rc_failsafe()) {719msg.failsafe[fs_iter++] = Status::FS_RADIO;720}721if (battery.has_failsafed()) {722msg.failsafe[fs_iter++] = Status::FS_BATTERY;723}724// TODO: replace flag with function.725if (AP_Notify::flags.failsafe_gcs) {726msg.failsafe[fs_iter++] = Status::FS_GCS;727}728// TODO: replace flag with function.729if (AP_Notify::flags.failsafe_ekf) {730msg.failsafe[fs_iter++] = Status::FS_EKF;731}732msg.failsafe_size = fs_iter;733734// Compare with the previous one.735bool is_message_changed {false};736is_message_changed |= (last_status_msg_.flying != msg.flying);737is_message_changed |= (last_status_msg_.armed != msg.armed);738is_message_changed |= (last_status_msg_.mode != msg.mode);739is_message_changed |= (last_status_msg_.vehicle_type != msg.vehicle_type);740is_message_changed |= (last_status_msg_.failsafe_size != msg.failsafe_size);741is_message_changed |= (last_status_msg_.external_control != msg.external_control);742743const auto timestamp = AP_HAL::millis64();744if ( is_message_changed ) {745last_status_msg_.flying = msg.flying;746last_status_msg_.armed = msg.armed;747last_status_msg_.mode = msg.mode;748last_status_msg_.vehicle_type = msg.vehicle_type;749last_status_msg_.failsafe_size = msg.failsafe_size;750last_status_msg_.external_control = msg.external_control;751last_status_publish_time_ms = timestamp;752update_topic(msg.header.stamp);753return true;754} else if (timestamp - last_status_publish_time_ms > DELAY_STATUS_TOPIC_MS * 5) {755// Publish the status message at 2Hz even if no change is detected.756last_status_publish_time_ms = timestamp;757update_topic(msg.header.stamp);758return true;759} else {760return false;761}762}763#endif // AP_DDS_STATUS_PUB_ENABLED764/*765start the DDS thread766*/767bool AP_DDS_Client::start(void)768{769AP_Param::setup_object_defaults(this, var_info);770AP_Param::load_object_from_eeprom(this, var_info);771772if (enabled == 0) {773return true;774}775776if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_DDS_Client::main_loop, void),777"DDS",7788192, AP_HAL::Scheduler::PRIORITY_IO, 1)) {779GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Thread create failed", msg_prefix);780return false;781}782return true;783}784785// read function triggered at every subscription callback786void AP_DDS_Client::on_topic_trampoline(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length,787void* args)788{789AP_DDS_Client *dds = (AP_DDS_Client *)args;790dds->on_topic(uxr_session, object_id, request_id, stream_id, ub, length);791}792793void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length)794{795/*796TEMPLATE for reading to the subscribed topics7971) Store the read contents into the ucdr buffer7982) Deserialize the said contents into the topic instance799*/800(void) uxr_session;801(void) request_id;802(void) stream_id;803(void) length;804switch (object_id.id) {805#if AP_DDS_JOY_SUB_ENABLED806case topics[to_underlying(TopicIndex::JOY_SUB)].dr_id.id: {807const bool success = sensor_msgs_msg_Joy_deserialize_topic(ub, &rx_joy_topic);808809if (success == false) {810break;811}812813if (rx_joy_topic.axes_size >= 4) {814const uint32_t t_now = AP_HAL::millis();815816for (uint8_t i = 0; i < MIN(8U, rx_joy_topic.axes_size); i++) {817// Ignore channel override if NaN.818if (std::isnan(rx_joy_topic.axes[i])) {819// Setting the RC override to 0U releases the channel back to the RC.820RC_Channels::set_override(i, 0U, t_now);821} else {822const uint16_t mapped_data = static_cast<uint16_t>(823linear_interpolate(rc().channel(i)->get_radio_min(),824rc().channel(i)->get_radio_max(),825rx_joy_topic.axes[i],826-1.0, 1.0));827RC_Channels::set_override(i, mapped_data, t_now);828}829}830831}832break;833}834#endif // AP_DDS_JOY_SUB_ENABLED835#if AP_DDS_DYNAMIC_TF_SUB_ENABLED836case topics[to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB)].dr_id.id: {837const bool success = tf2_msgs_msg_TFMessage_deserialize_topic(ub, &rx_dynamic_transforms_topic);838if (success == false) {839break;840}841842if (rx_dynamic_transforms_topic.transforms_size > 0) {843#if AP_DDS_VISUALODOM_ENABLED844AP_DDS_External_Odom::handle_external_odom(rx_dynamic_transforms_topic);845#endif // AP_DDS_VISUALODOM_ENABLED846847} else {848GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Received tf2_msgs/TFMessage: TF is empty", msg_prefix);849}850break;851}852#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED853#if AP_DDS_VEL_CTRL_ENABLED854case topics[to_underlying(TopicIndex::VELOCITY_CONTROL_SUB)].dr_id.id: {855const bool success = geometry_msgs_msg_TwistStamped_deserialize_topic(ub, &rx_velocity_control_topic);856if (success == false) {857break;858}859#if AP_EXTERNAL_CONTROL_ENABLED860if (!AP_DDS_External_Control::handle_velocity_control(rx_velocity_control_topic)) {861// TODO #23430 handle velocity control failure through rosout, throttled.862}863#endif // AP_EXTERNAL_CONTROL_ENABLED864break;865}866#endif // AP_DDS_VEL_CTRL_ENABLED867#if AP_DDS_GLOBAL_POS_CTRL_ENABLED868case topics[to_underlying(TopicIndex::GLOBAL_POSITION_SUB)].dr_id.id: {869const bool success = ardupilot_msgs_msg_GlobalPosition_deserialize_topic(ub, &rx_global_position_control_topic);870if (success == false) {871break;872}873874#if AP_EXTERNAL_CONTROL_ENABLED875if (!AP_DDS_External_Control::handle_global_position_control(rx_global_position_control_topic)) {876// TODO #23430 handle global position control failure through rosout, throttled.877}878#endif // AP_EXTERNAL_CONTROL_ENABLED879break;880}881#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED882}883884}885886/*887callback on request completion888*/889void AP_DDS_Client::on_request_trampoline(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length, void* args)890{891AP_DDS_Client *dds = (AP_DDS_Client *)args;892dds->on_request(uxr_session, object_id, request_id, sample_id, ub, length);893}894895void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length)896{897(void) request_id;898(void) length;899switch (object_id.id) {900#if AP_DDS_ARM_SERVER_ENABLED901case services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id: {902ardupilot_msgs_srv_ArmMotors_Request arm_motors_request;903ardupilot_msgs_srv_ArmMotors_Response arm_motors_response;904const bool deserialize_success = ardupilot_msgs_srv_ArmMotors_Request_deserialize_topic(ub, &arm_motors_request);905if (deserialize_success == false) {906break;907}908909GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for %sing received", msg_prefix, arm_motors_request.arm ? "arm" : "disarm");910#if AP_EXTERNAL_CONTROL_ENABLED911const bool do_checks = true;912arm_motors_response.result = arm_motors_request.arm ? AP_DDS_External_Control::arm(AP_Arming::Method::DDS, do_checks) : AP_DDS_External_Control::disarm(AP_Arming::Method::DDS, do_checks);913if (!arm_motors_response.result) {914// TODO #23430 handle arm failure through rosout, throttled.915}916#endif // AP_EXTERNAL_CONTROL_ENABLED917918const uxrObjectId replier_id = {919.id = services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id,920.type = UXR_REPLIER_ID921};922923uint8_t reply_buffer[8] {};924ucdrBuffer reply_ub;925926ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));927const bool serialize_success = ardupilot_msgs_srv_ArmMotors_Response_serialize_topic(&reply_ub, &arm_motors_response);928if (serialize_success == false) {929break;930}931932uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));933GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Arming/Disarming : %s", msg_prefix, arm_motors_response.result ? "SUCCESS" : "FAIL");934break;935}936#endif // AP_DDS_ARM_SERVER_ENABLED937#if AP_DDS_MODE_SWITCH_SERVER_ENABLED938case services[to_underlying(ServiceIndex::MODE_SWITCH)].rep_id: {939ardupilot_msgs_srv_ModeSwitch_Request mode_switch_request;940ardupilot_msgs_srv_ModeSwitch_Response mode_switch_response;941const bool deserialize_success = ardupilot_msgs_srv_ModeSwitch_Request_deserialize_topic(ub, &mode_switch_request);942if (deserialize_success == false) {943break;944}945mode_switch_response.status = AP::vehicle()->set_mode(mode_switch_request.mode, ModeReason::DDS_COMMAND);946mode_switch_response.curr_mode = AP::vehicle()->get_mode();947948const uxrObjectId replier_id = {949.id = services[to_underlying(ServiceIndex::MODE_SWITCH)].rep_id,950.type = UXR_REPLIER_ID951};952953uint8_t reply_buffer[8] {};954ucdrBuffer reply_ub;955956ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));957const bool serialize_success = ardupilot_msgs_srv_ModeSwitch_Response_serialize_topic(&reply_ub, &mode_switch_response);958if (serialize_success == false) {959break;960}961962uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));963GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Mode Switch : %s", msg_prefix, mode_switch_response.status ? "SUCCESS" : "FAIL");964break;965}966#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED967#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED968case services[to_underlying(ServiceIndex::TAKEOFF)].rep_id: {969ardupilot_msgs_srv_Takeoff_Request takeoff_request;970ardupilot_msgs_srv_Takeoff_Response takeoff_response;971const bool deserialize_success = ardupilot_msgs_srv_Takeoff_Request_deserialize_topic(ub, &takeoff_request);972if (deserialize_success == false) {973break;974}975takeoff_response.status = AP::vehicle()->start_takeoff(takeoff_request.alt);976977const uxrObjectId replier_id = {978.id = services[to_underlying(ServiceIndex::TAKEOFF)].rep_id,979.type = UXR_REPLIER_ID980};981982uint8_t reply_buffer[8] {};983ucdrBuffer reply_ub;984985ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));986const bool serialize_success = ardupilot_msgs_srv_Takeoff_Response_serialize_topic(&reply_ub, &takeoff_response);987if (serialize_success == false) {988break;989}990991uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));992GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Takeoff : %s", msg_prefix, takeoff_response.status ? "SUCCESS" : "FAIL");993break;994}995#endif // AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED996#if AP_DDS_ARM_CHECK_SERVER_ENABLED997case services[to_underlying(ServiceIndex::PREARM_CHECK)].rep_id: {998std_srvs_srv_Trigger_Request prearm_check_request;999std_srvs_srv_Trigger_Response prearm_check_response;1000const bool deserialize_success = std_srvs_srv_Trigger_Request_deserialize_topic(ub, &prearm_check_request);1001if (deserialize_success == false) {1002break;1003}1004prearm_check_response.success = AP::arming().pre_arm_checks(false);1005STRCPY(prearm_check_response.message, prearm_check_response.success ? "Vehicle is Armable" : "Vehicle is Not Armable");10061007const uxrObjectId replier_id = {1008.id = services[to_underlying(ServiceIndex::PREARM_CHECK)].rep_id,1009.type = UXR_REPLIER_ID1010};10111012uint8_t reply_buffer[sizeof(prearm_check_response.message) + 1] {};1013ucdrBuffer reply_ub;10141015ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));1016const bool serialize_success = std_srvs_srv_Trigger_Response_serialize_topic(&reply_ub, &prearm_check_response);1017if (serialize_success == false) {1018break;1019}10201021uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));1022break;1023}1024#endif //AP_DDS_ARM_CHECK_SERVER_ENABLED1025#if AP_DDS_PARAMETER_SERVER_ENABLED1026case services[to_underlying(ServiceIndex::SET_PARAMETERS)].rep_id: {1027const bool deserialize_success = rcl_interfaces_srv_SetParameters_Request_deserialize_topic(ub, &set_parameter_request);1028if (deserialize_success == false) {1029GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Set Parameters Request : Failed to deserialize request.", msg_prefix);1030break;1031}10321033if (set_parameter_request.parameters_size > 8U) {1034break;1035}10361037// Set parameters and responses for each one requested1038set_parameter_response.results_size = set_parameter_request.parameters_size;1039for (size_t i = 0; i < set_parameter_request.parameters_size; i++) {1040param = set_parameter_request.parameters[i];10411042enum ap_var_type var_type;10431044// set parameter1045AP_Param *vp;1046char param_key[AP_MAX_NAME_SIZE + 1];1047strncpy(param_key, (char *)param.name, AP_MAX_NAME_SIZE);1048param_key[AP_MAX_NAME_SIZE] = 0;10491050// Currently only integer and double value types can be set.1051// The following parameter value types are not handled:1052// bool, string, byte_array, bool_array, integer_array, double_array and string_array1053bool param_isnan = true;1054bool param_isinf = true;1055float param_value = 0.0f;1056switch (param.value.type) {1057case ParameterType::PARAMETER_INTEGER: {1058param_isnan = isnan(param.value.integer_value);1059param_isinf = isinf(param.value.integer_value);1060param_value = float(param.value.integer_value);1061break;1062}1063case ParameterType::PARAMETER_DOUBLE: {1064param_isnan = isnan(param.value.double_value);1065param_isinf = isinf(param.value.double_value);1066param_value = float(param.value.double_value);1067break;1068}1069default: {1070break;1071}1072}10731074// find existing param to get the old value1075uint16_t parameter_flags = 0;1076vp = AP_Param::find(param_key, &var_type, ¶meter_flags);1077if (vp == nullptr || param_isnan || param_isinf) {1078set_parameter_response.results[i].successful = false;1079strncpy(set_parameter_response.results[i].reason, "Parameter not found", sizeof(set_parameter_response.results[i].reason));1080continue;1081}10821083// Add existing parameter checks used in GCS_Param.cpp1084if (parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) {1085// The user can set BRD_OPTIONS to enable set of internal1086// parameters, for developer testing or unusual use cases1087if (AP_BoardConfig::allow_set_internal_parameters()) {1088parameter_flags &= ~AP_PARAM_FLAG_INTERNAL_USE_ONLY;1089}1090}10911092if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) {1093set_parameter_response.results[i].successful = false;1094strncpy(set_parameter_response.results[i].reason, "Parameter is read only",sizeof(set_parameter_response.results[i].reason));1095continue;1096}10971098// Set and save the value if it changed1099bool force_save = vp->set_and_save_by_name_ifchanged(param_key, param_value);11001101if (force_save && (parameter_flags & AP_PARAM_FLAG_ENABLE)) {1102AP_Param::invalidate_count();1103}11041105set_parameter_response.results[i].successful = true;1106strncpy(set_parameter_response.results[i].reason, "Parameter accepted", sizeof(set_parameter_response.results[i].reason));1107}11081109const uxrObjectId replier_id = {1110.id = services[to_underlying(ServiceIndex::SET_PARAMETERS)].rep_id,1111.type = UXR_REPLIER_ID1112};11131114const uint32_t reply_size = rcl_interfaces_srv_SetParameters_Response_size_of_topic(&set_parameter_response, 0U);1115uint8_t reply_buffer[reply_size];1116memset(reply_buffer, 0, reply_size * sizeof(uint8_t));1117ucdrBuffer reply_ub;11181119ucdr_init_buffer(&reply_ub, reply_buffer, reply_size);1120const bool serialize_success = rcl_interfaces_srv_SetParameters_Response_serialize_topic(&reply_ub, &set_parameter_response);1121if (serialize_success == false) {1122break;1123}11241125uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));1126bool successful_params = true;1127for (size_t i = 0; i < set_parameter_response.results_size; i++) {1128// Check that all the parameters were set successfully1129successful_params &= set_parameter_response.results[i].successful;1130}1131GCS_SEND_TEXT(successful_params ? MAV_SEVERITY_INFO : MAV_SEVERITY_WARNING, "%s Set Parameters Request : %s", msg_prefix, successful_params ? "SUCCESSFUL" : "ONE OR MORE PARAMS FAILED" );1132break;1133}1134case services[to_underlying(ServiceIndex::GET_PARAMETERS)].rep_id: {1135const bool deserialize_success = rcl_interfaces_srv_GetParameters_Request_deserialize_topic(ub, &get_parameters_request);1136if (deserialize_success == false) {1137GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Get Parameters Request : Failed to deserialize request.", msg_prefix);1138break;1139}11401141if (get_parameters_request.names_size > 8U) {1142break;1143}11441145bool successful_read = true;1146get_parameters_response.values_size = get_parameters_request.names_size;1147for (size_t i = 0; i < get_parameters_request.names_size; i++) {1148enum ap_var_type var_type;11491150AP_Param *vp;1151char param_key[AP_MAX_NAME_SIZE + 1];1152strncpy(param_key, (char *)get_parameters_request.names[i], AP_MAX_NAME_SIZE);1153param_key[AP_MAX_NAME_SIZE] = 0;11541155vp = AP_Param::find(param_key, &var_type);1156if (vp == nullptr) {1157get_parameters_response.values[i].type = ParameterType::PARAMETER_NOT_SET;1158successful_read &= false;1159continue;1160}11611162switch (var_type) {1163case AP_PARAM_INT8: {1164get_parameters_response.values[i].type = ParameterType::PARAMETER_INTEGER;1165get_parameters_response.values[i].integer_value = ((AP_Int8 *)vp)->get();1166successful_read &= true;1167break;1168}1169case AP_PARAM_INT16: {1170get_parameters_response.values[i].type = ParameterType::PARAMETER_INTEGER;1171get_parameters_response.values[i].integer_value = ((AP_Int16 *)vp)->get();1172successful_read &= true;1173break;1174}1175case AP_PARAM_INT32: {1176get_parameters_response.values[i].type = ParameterType::PARAMETER_INTEGER;1177get_parameters_response.values[i].integer_value = ((AP_Int32 *)vp)->get();1178successful_read &= true;1179break;1180}1181case AP_PARAM_FLOAT: {1182get_parameters_response.values[i].type = ParameterType::PARAMETER_DOUBLE;1183get_parameters_response.values[i].double_value = vp->cast_to_float(var_type);1184successful_read &= true;1185break;1186}1187default: {1188get_parameters_response.values[i].type = ParameterType::PARAMETER_NOT_SET;1189successful_read &= false;1190break;1191}1192}1193}11941195const uxrObjectId replier_id = {1196.id = services[to_underlying(ServiceIndex::GET_PARAMETERS)].rep_id,1197.type = UXR_REPLIER_ID1198};11991200const uint32_t reply_size = rcl_interfaces_srv_GetParameters_Response_size_of_topic(&get_parameters_response, 0U);1201uint8_t reply_buffer[reply_size];1202memset(reply_buffer, 0, reply_size * sizeof(uint8_t));1203ucdrBuffer reply_ub;12041205ucdr_init_buffer(&reply_ub, reply_buffer, reply_size);1206const bool serialize_success = rcl_interfaces_srv_GetParameters_Response_serialize_topic(&reply_ub, &get_parameters_response);1207if (serialize_success == false) {1208break;1209}12101211uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));12121213GCS_SEND_TEXT(successful_read ? MAV_SEVERITY_INFO : MAV_SEVERITY_WARNING, "%s Get Parameters Request : %s", msg_prefix, successful_read ? "SUCCESSFUL" : "ONE OR MORE PARAM NOT FOUND");1214break;1215}1216#endif // AP_DDS_PARAMETER_SERVER_ENABLED1217}1218}12191220/*1221main loop for DDS thread1222*/1223void AP_DDS_Client::main_loop(void)1224{1225GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s initializing...", msg_prefix);1226if (!init_transport()) {1227return;1228}12291230//! @todo check for request to stop task1231while (true) {1232if (comm == nullptr) {1233GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s transport invalid, exiting", msg_prefix);1234return;1235}1236// If using UDP, check if the network is active before proceeding1237// not applicable for SITL, which doesn't use AP_Networking1238#if AP_DDS_UDP_ENABLED && !AP_NETWORKING_BACKEND_SITL1239if (!is_using_serial) {1240const auto &network = AP::network();1241if (network.get_ip_active() == 0) {1242hal.scheduler->delay(1000);1243continue;1244}12451246}1247#endif12481249// check ping1250if (ping_max_retry == 0) {1251if (!uxr_ping_agent(comm, ping_timeout_ms)) {1252GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s No ping response, retrying", msg_prefix);1253continue;1254}1255} else {1256if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_retry)) {1257GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s No ping response, exiting", msg_prefix);1258continue;1259}1260}12611262// create session1263if (!init_session() || !create()) {1264GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Creation Requests failed", msg_prefix);1265return;1266}1267connected = true;1268GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Initialization passed", msg_prefix);12691270#if AP_DDS_STATIC_TF_PUB_ENABLED1271populate_static_transforms(tx_static_transforms_topic);1272write_static_transforms();1273#endif // AP_DDS_STATIC_TF_PUB_ENABLED12741275uint64_t last_ping_ms{0};1276uint8_t num_pings_missed{0};1277bool had_ping_reply{false};1278while (connected) {1279hal.scheduler->delay(1);12801281// publish topics1282update();12831284// check ping response1285if (session.on_pong_flag == PONG_IN_SESSION_STATUS) {1286had_ping_reply = true;1287}12881289const auto cur_time_ms = AP_HAL::millis64();1290if (cur_time_ms - last_ping_ms > DELAY_PING_MS) {1291last_ping_ms = cur_time_ms;12921293if (had_ping_reply) {1294num_pings_missed = 0;12951296} else {1297++num_pings_missed;1298}12991300const int ping_agent_timeout_ms{0};1301const uint8_t ping_agent_attempts{1};1302uxr_ping_agent_session(&session, ping_agent_timeout_ms, ping_agent_attempts);13031304had_ping_reply = false;1305}13061307if (num_pings_missed > 2) {1308GCS_SEND_TEXT(MAV_SEVERITY_ERROR,1309"%s No ping response, disconnecting", msg_prefix);1310connected = false;1311}1312}13131314// delete session if connected1315if (connected) {1316uxr_delete_session(&session);1317}1318}1319}13201321bool AP_DDS_Client::init_transport()1322{1323// serial init will fail if the SERIALn_PROTOCOL is not setup1324bool initTransportStatus = ddsSerialInit();1325is_using_serial = initTransportStatus;13261327if (is_using_serial) {1328GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Using Serial", msg_prefix);1329}13301331#if AP_DDS_UDP_ENABLED1332// fallback to UDP if available1333if (!initTransportStatus) {1334initTransportStatus = ddsUdpInit();1335GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Using UDP", msg_prefix);1336}1337#endif13381339if (!initTransportStatus) {1340GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Transport initialization failed", msg_prefix);1341return false;1342}13431344return true;1345}13461347bool AP_DDS_Client::init_session()1348{1349// init session1350uxr_init_session(&session, comm, key);13511352// Register topic callbacks1353uxr_set_topic_callback(&session, AP_DDS_Client::on_topic_trampoline, this);13541355// ROS-2 Service : Register service request callbacks1356uxr_set_request_callback(&session, AP_DDS_Client::on_request_trampoline, this);13571358while (!uxr_create_session(&session)) {1359GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Initialization waiting...", msg_prefix);1360hal.scheduler->delay(1000);1361}13621363// setup reliable stream buffers1364input_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE];1365output_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE];1366if (input_reliable_stream == nullptr || output_reliable_stream == nullptr) {1367GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Allocation failed", msg_prefix);1368return false;1369}13701371reliable_in = uxr_create_input_reliable_stream(&session, input_reliable_stream, DDS_BUFFER_SIZE, DDS_STREAM_HISTORY);1372reliable_out = uxr_create_output_reliable_stream(&session, output_reliable_stream, DDS_BUFFER_SIZE, DDS_STREAM_HISTORY);13731374GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Init complete", msg_prefix);13751376return true;1377}13781379bool AP_DDS_Client::create()1380{1381WITH_SEMAPHORE(csem);13821383// Participant1384const uxrObjectId participant_id = {1385.id = 0x01,1386.type = UXR_PARTICIPANT_ID1387};1388const char* participant_name = AP_DDS_PARTICIPANT_NAME;1389const auto participant_req_id = uxr_buffer_create_participant_bin(&session, reliable_out, participant_id,1390static_cast<uint16_t>(domain_id), participant_name, UXR_REPLACE);13911392//Participant requests1393constexpr uint8_t nRequestsParticipant = 1;1394const uint16_t requestsParticipant[nRequestsParticipant] = {participant_req_id};13951396constexpr uint16_t maxTimeMsPerRequestMs = 500;1397constexpr uint16_t requestTimeoutParticipantMs = (uint16_t) nRequestsParticipant * maxTimeMsPerRequestMs;1398uint8_t statusParticipant[nRequestsParticipant];1399if (!uxr_run_session_until_all_status(&session, requestTimeoutParticipantMs, requestsParticipant, statusParticipant, nRequestsParticipant)) {1400GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Participant session request failure", msg_prefix);1401// TODO add a failure log message sharing the status results1402return false;1403}14041405for (uint16_t i = 0 ; i < ARRAY_SIZE(topics); i++) {1406// Topic1407const uxrObjectId topic_id = {1408.id = topics[i].topic_id,1409.type = UXR_TOPIC_ID1410};1411const auto topic_req_id = uxr_buffer_create_topic_bin(&session, reliable_out, topic_id,1412participant_id, topics[i].topic_name, topics[i].type_name, UXR_REPLACE);14131414// Status requests1415constexpr uint8_t nRequests = 3;1416uint16_t requests[nRequests];1417constexpr uint16_t requestTimeoutMs = nRequests * maxTimeMsPerRequestMs;1418uint8_t status[nRequests];14191420if (topics[i].topic_rw == Topic_rw::DataWriter) {1421// Publisher1422const uxrObjectId pub_id = {1423.id = topics[i].pub_id,1424.type = UXR_PUBLISHER_ID1425};1426const auto pub_req_id = uxr_buffer_create_publisher_bin(&session, reliable_out, pub_id,1427participant_id, UXR_REPLACE);14281429// Data Writer1430const auto dwriter_req_id = uxr_buffer_create_datawriter_bin(&session, reliable_out, topics[i].dw_id,1431pub_id, topic_id, topics[i].qos, UXR_REPLACE);14321433// save the request statuses1434requests[0] = topic_req_id;1435requests[1] = pub_req_id;1436requests[2] = dwriter_req_id;14371438bool success = false;1439for (uint8_t retry = 0; retry < 3; retry++) {1440success = uxr_run_session_until_all_status(&session, requestTimeoutMs * (retry + 1), requests, status, nRequests);1441if (success) {1442break;1443}1444GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s Topic/Pub/Writer session request retry for index '%u'", msg_prefix, i);1445}1446if (!success) {1447GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Topic/Pub/Writer session request failure for index '%u'", msg_prefix, i);1448for (uint8_t s = 0 ; s < nRequests; s++) {1449GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Status '%d' result '%u'", msg_prefix, s, status[s]);1450}1451// TODO add a failure log message sharing the status results1452return false;1453} else {1454GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Topic/Pub/Writer session pass for index '%u'", msg_prefix, i);1455}1456} else if (topics[i].topic_rw == Topic_rw::DataReader) {1457// Subscriber1458const uxrObjectId sub_id = {1459.id = topics[i].sub_id,1460.type = UXR_SUBSCRIBER_ID1461};1462const auto sub_req_id = uxr_buffer_create_subscriber_bin(&session, reliable_out, sub_id,1463participant_id, UXR_REPLACE);14641465// Data Reader1466const auto dreader_req_id = uxr_buffer_create_datareader_bin(&session, reliable_out, topics[i].dr_id,1467sub_id, topic_id, topics[i].qos, UXR_REPLACE);14681469// save the request statuses1470requests[0] = topic_req_id;1471requests[1] = sub_req_id;1472requests[2] = dreader_req_id;14731474bool success = false;1475for (uint8_t retry = 0; retry < 3; retry++) {1476success = uxr_run_session_until_all_status(&session, requestTimeoutMs * (retry + 1), requests, status, nRequests);1477if (success) {1478break;1479}1480GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s Topic/Sub/Reader session request retry for index '%u'", msg_prefix, i);1481}1482if (!success) {1483GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Topic/Sub/Reader session request failure for index '%u'", msg_prefix, i);1484for (uint8_t s = 0 ; s < nRequests; s++) {1485GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Status '%d' result '%u'", msg_prefix, s, status[s]);1486}1487// TODO add a failure log message sharing the status results1488return false;1489} else {1490GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Topic/Sub/Reader session pass for index '%u'", msg_prefix, i);1491uxr_buffer_request_data(&session, reliable_out, topics[i].dr_id, reliable_in, &delivery_control);1492}1493}1494}14951496// ROS-2 Service : else case for service requests14971498for (uint16_t i = 0; i < ARRAY_SIZE(services); i++) {14991500constexpr uint16_t requestTimeoutMs = maxTimeMsPerRequestMs;15011502if (services[i].service_rr == Service_rr::Replier) {1503const uxrObjectId rep_id = {1504.id = services[i].rep_id,1505.type = UXR_REPLIER_ID1506};1507const auto replier_req_id = uxr_buffer_create_replier_bin(&session, reliable_out, rep_id,1508participant_id, services[i].service_name, services[i].request_type, services[i].reply_type,1509services[i].request_topic_name, services[i].reply_topic_name, services[i].qos, UXR_REPLACE);15101511uint16_t request = replier_req_id;1512uint8_t status;15131514bool success = false;1515for (uint8_t retry = 0; retry < 3; retry++) {1516success = uxr_run_session_until_all_status(&session, requestTimeoutMs * (retry + 1), &request, &status, 1);1517if (success) {1518break;1519}1520GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s Service/Replier session request retry for index '%u'", msg_prefix, i);1521}1522if (!success) {1523GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Service/Replier session request failure for index '%u'", msg_prefix, i);1524GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Status result '%u'", msg_prefix, status);1525// TODO add a failure log message sharing the status results1526return false;1527} else {1528GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Service/Replier session pass for index '%u'", msg_prefix, i);1529uxr_buffer_request_data(&session, reliable_out, rep_id, reliable_in, &delivery_control);1530}15311532} else if (services[i].service_rr == Service_rr::Requester) {1533// TODO : Add Similar Code for Requester Profile1534}1535}15361537return true;1538}15391540void AP_DDS_Client::write_time_topic()1541{1542WITH_SEMAPHORE(csem);1543if (connected) {1544ucdrBuffer ub {};1545const uint32_t topic_size = builtin_interfaces_msg_Time_size_of_topic(&time_topic, 0);1546uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::TIME_PUB)].dw_id, &ub, topic_size);1547const bool success = builtin_interfaces_msg_Time_serialize_topic(&ub, &time_topic);1548if (!success) {1549// TODO sometimes serialization fails on bootup. Determine why.1550// AP_HAL::panic("FATAL: XRCE_Client failed to serialize");1551}1552}1553}15541555#if AP_DDS_NAVSATFIX_PUB_ENABLED1556void AP_DDS_Client::write_nav_sat_fix_topic()1557{1558WITH_SEMAPHORE(csem);1559if (connected) {1560ucdrBuffer ub {};1561const uint32_t topic_size = sensor_msgs_msg_NavSatFix_size_of_topic(&nav_sat_fix_topic, 0);1562uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::NAV_SAT_FIX_PUB)].dw_id, &ub, topic_size);1563const bool success = sensor_msgs_msg_NavSatFix_serialize_topic(&ub, &nav_sat_fix_topic);1564if (!success) {1565// TODO sometimes serialization fails on bootup. Determine why.1566// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1567}1568}1569}1570#endif // AP_DDS_NAVSATFIX_PUB_ENABLED15711572#if AP_DDS_STATIC_TF_PUB_ENABLED1573void AP_DDS_Client::write_static_transforms()1574{1575WITH_SEMAPHORE(csem);1576if (connected) {1577ucdrBuffer ub {};1578const uint32_t topic_size = tf2_msgs_msg_TFMessage_size_of_topic(&tx_static_transforms_topic, 0);1579uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB)].dw_id, &ub, topic_size);1580const bool success = tf2_msgs_msg_TFMessage_serialize_topic(&ub, &tx_static_transforms_topic);1581if (!success) {1582// TODO sometimes serialization fails on bootup. Determine why.1583// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1584}1585}1586}1587#endif // AP_DDS_STATIC_TF_PUB_ENABLED15881589#if AP_DDS_BATTERY_STATE_PUB_ENABLED1590void AP_DDS_Client::write_battery_state_topic()1591{1592WITH_SEMAPHORE(csem);1593if (connected) {1594ucdrBuffer ub {};1595const uint32_t topic_size = sensor_msgs_msg_BatteryState_size_of_topic(&battery_state_topic, 0);1596uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::BATTERY_STATE_PUB)].dw_id, &ub, topic_size);1597const bool success = sensor_msgs_msg_BatteryState_serialize_topic(&ub, &battery_state_topic);1598if (!success) {1599// TODO sometimes serialization fails on bootup. Determine why.1600// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1601}1602}1603}1604#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED16051606#if AP_DDS_LOCAL_POSE_PUB_ENABLED1607void AP_DDS_Client::write_local_pose_topic()1608{1609WITH_SEMAPHORE(csem);1610if (connected) {1611ucdrBuffer ub {};1612const uint32_t topic_size = geometry_msgs_msg_PoseStamped_size_of_topic(&local_pose_topic, 0);1613uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::LOCAL_POSE_PUB)].dw_id, &ub, topic_size);1614const bool success = geometry_msgs_msg_PoseStamped_serialize_topic(&ub, &local_pose_topic);1615if (!success) {1616// TODO sometimes serialization fails on bootup. Determine why.1617// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1618}1619}1620}1621#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED16221623#if AP_DDS_LOCAL_VEL_PUB_ENABLED1624void AP_DDS_Client::write_tx_local_velocity_topic()1625{1626WITH_SEMAPHORE(csem);1627if (connected) {1628ucdrBuffer ub {};1629const uint32_t topic_size = geometry_msgs_msg_TwistStamped_size_of_topic(&tx_local_velocity_topic, 0);1630uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::LOCAL_VELOCITY_PUB)].dw_id, &ub, topic_size);1631const bool success = geometry_msgs_msg_TwistStamped_serialize_topic(&ub, &tx_local_velocity_topic);1632if (!success) {1633// TODO sometimes serialization fails on bootup. Determine why.1634// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1635}1636}1637}1638#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED1639#if AP_DDS_AIRSPEED_PUB_ENABLED1640void AP_DDS_Client::write_tx_local_airspeed_topic()1641{1642WITH_SEMAPHORE(csem);1643if (connected) {1644ucdrBuffer ub {};1645const uint32_t topic_size = ardupilot_msgs_msg_Airspeed_size_of_topic(&tx_local_airspeed_topic, 0);1646uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB)].dw_id, &ub, topic_size);1647const bool success = ardupilot_msgs_msg_Airspeed_serialize_topic(&ub, &tx_local_airspeed_topic);1648if (!success) {1649// TODO sometimes serialization fails on bootup. Determine why.1650// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1651}1652}1653}1654#endif // AP_DDS_AIRSPEED_PUB_ENABLED1655#if AP_DDS_RC_PUB_ENABLED1656void AP_DDS_Client::write_tx_local_rc_topic()1657{1658WITH_SEMAPHORE(csem);1659if (connected) {1660ucdrBuffer ub {};1661const uint32_t topic_size = ardupilot_msgs_msg_Rc_size_of_topic(&tx_local_rc_topic, 0);1662uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::LOCAL_RC_PUB)].dw_id, &ub, topic_size);1663const bool success = ardupilot_msgs_msg_Rc_serialize_topic(&ub, &tx_local_rc_topic);1664if (!success) {1665// TODO sometimes serialization fails on bootup. Determine why.1666// AP_HAL::panic("FATAL: DDS_Client failed to serialize\n");1667}1668}1669}1670#endif // AP_DDS_RC_PUB_ENABLED1671#if AP_DDS_IMU_PUB_ENABLED1672void AP_DDS_Client::write_imu_topic()1673{1674WITH_SEMAPHORE(csem);1675if (connected) {1676ucdrBuffer ub {};1677const uint32_t topic_size = sensor_msgs_msg_Imu_size_of_topic(&imu_topic, 0);1678uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::IMU_PUB)].dw_id, &ub, topic_size);1679const bool success = sensor_msgs_msg_Imu_serialize_topic(&ub, &imu_topic);1680if (!success) {1681// TODO sometimes serialization fails on bootup. Determine why.1682// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1683}1684}1685}1686#endif // AP_DDS_IMU_PUB_ENABLED16871688#if AP_DDS_GEOPOSE_PUB_ENABLED1689void AP_DDS_Client::write_geo_pose_topic()1690{1691WITH_SEMAPHORE(csem);1692if (connected) {1693ucdrBuffer ub {};1694const uint32_t topic_size = geographic_msgs_msg_GeoPoseStamped_size_of_topic(&geo_pose_topic, 0);1695uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::GEOPOSE_PUB)].dw_id, &ub, topic_size);1696const bool success = geographic_msgs_msg_GeoPoseStamped_serialize_topic(&ub, &geo_pose_topic);1697if (!success) {1698// TODO sometimes serialization fails on bootup. Determine why.1699// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1700}1701}1702}1703#endif // AP_DDS_GEOPOSE_PUB_ENABLED17041705#if AP_DDS_CLOCK_PUB_ENABLED1706void AP_DDS_Client::write_clock_topic()1707{1708WITH_SEMAPHORE(csem);1709if (connected) {1710ucdrBuffer ub {};1711const uint32_t topic_size = rosgraph_msgs_msg_Clock_size_of_topic(&clock_topic, 0);1712uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::CLOCK_PUB)].dw_id, &ub, topic_size);1713const bool success = rosgraph_msgs_msg_Clock_serialize_topic(&ub, &clock_topic);1714if (!success) {1715// TODO sometimes serialization fails on bootup. Determine why.1716// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1717}1718}1719}1720#endif // AP_DDS_CLOCK_PUB_ENABLED17211722#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED1723void AP_DDS_Client::write_gps_global_origin_topic()1724{1725WITH_SEMAPHORE(csem);1726if (connected) {1727ucdrBuffer ub {};1728const uint32_t topic_size = geographic_msgs_msg_GeoPointStamped_size_of_topic(&gps_global_origin_topic, 0);1729uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB)].dw_id, &ub, topic_size);1730const bool success = geographic_msgs_msg_GeoPointStamped_serialize_topic(&ub, &gps_global_origin_topic);1731if (!success) {1732// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1733}1734}1735}1736#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED17371738#if AP_DDS_GOAL_PUB_ENABLED1739void AP_DDS_Client::write_goal_topic()1740{1741WITH_SEMAPHORE(csem);1742if (connected) {1743ucdrBuffer ub {};1744const uint32_t topic_size = geographic_msgs_msg_GeoPointStamped_size_of_topic(&goal_topic, 0);1745uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::GOAL_PUB)].dw_id, &ub, topic_size);1746const bool success = geographic_msgs_msg_GeoPointStamped_serialize_topic(&ub, &goal_topic);1747if (!success) {1748// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1749}1750}1751}1752#endif // AP_DDS_GOAL_PUB_ENABLED17531754#if AP_DDS_STATUS_PUB_ENABLED1755void AP_DDS_Client::write_status_topic()1756{1757WITH_SEMAPHORE(csem);1758if (connected) {1759ucdrBuffer ub {};1760const uint32_t topic_size = ardupilot_msgs_msg_Status_size_of_topic(&status_topic, 0);1761uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::STATUS_PUB)].dw_id, &ub, topic_size);1762const bool success = ardupilot_msgs_msg_Status_serialize_topic(&ub, &status_topic);1763if (!success) {1764// TODO sometimes serialization fails on bootup. Determine why.1765// AP_HAL::panic("FATAL: DDS_Client failed to serialize");1766}1767}1768}1769#endif // AP_DDS_STATUS_PUB_ENABLED17701771void AP_DDS_Client::update()1772{1773WITH_SEMAPHORE(csem);1774const auto cur_time_ms = AP_HAL::millis64();17751776#if AP_DDS_TIME_PUB_ENABLED1777if (cur_time_ms - last_time_time_ms > DELAY_TIME_TOPIC_MS) {1778update_topic(time_topic);1779last_time_time_ms = cur_time_ms;1780write_time_topic();1781}1782#endif // AP_DDS_TIME_PUB_ENABLED1783#if AP_DDS_NAVSATFIX_PUB_ENABLED1784for (uint8_t gps_instance = 0; gps_instance < GPS_MAX_INSTANCES; gps_instance++) {1785if (update_topic(nav_sat_fix_topic, gps_instance)) {1786write_nav_sat_fix_topic();1787}1788}1789#endif // AP_DDS_NAVSATFIX_PUB_ENABLED1790#if AP_DDS_BATTERY_STATE_PUB_ENABLED1791if (cur_time_ms - last_battery_state_time_ms > DELAY_BATTERY_STATE_TOPIC_MS) {1792for (uint8_t battery_instance = 0; battery_instance < AP_BATT_MONITOR_MAX_INSTANCES; battery_instance++) {1793update_topic(battery_state_topic, battery_instance);1794if (battery_state_topic.present) {1795write_battery_state_topic();1796}1797}1798last_battery_state_time_ms = cur_time_ms;1799}1800#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED1801#if AP_DDS_LOCAL_POSE_PUB_ENABLED1802if (cur_time_ms - last_local_pose_time_ms > DELAY_LOCAL_POSE_TOPIC_MS) {1803update_topic(local_pose_topic);1804last_local_pose_time_ms = cur_time_ms;1805write_local_pose_topic();1806}1807#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED1808#if AP_DDS_LOCAL_VEL_PUB_ENABLED1809if (cur_time_ms - last_local_velocity_time_ms > DELAY_LOCAL_VELOCITY_TOPIC_MS) {1810update_topic(tx_local_velocity_topic);1811last_local_velocity_time_ms = cur_time_ms;1812write_tx_local_velocity_topic();1813}1814#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED1815#if AP_DDS_AIRSPEED_PUB_ENABLED1816if (cur_time_ms - last_airspeed_time_ms > DELAY_AIRSPEED_TOPIC_MS) {1817last_airspeed_time_ms = cur_time_ms;1818if (update_topic(tx_local_airspeed_topic)) {1819write_tx_local_airspeed_topic();1820}1821}1822#endif // AP_DDS_AIRSPEED_PUB_ENABLED1823#if AP_DDS_RC_PUB_ENABLED1824if (cur_time_ms - last_rc_time_ms > DELAY_RC_TOPIC_MS) {1825last_rc_time_ms = cur_time_ms;1826if (update_topic(tx_local_rc_topic)) {1827write_tx_local_rc_topic();1828}1829}1830#endif // AP_DDS_RC_PUB_ENABLED1831#if AP_DDS_IMU_PUB_ENABLED1832if (cur_time_ms - last_imu_time_ms > DELAY_IMU_TOPIC_MS) {1833update_topic(imu_topic);1834last_imu_time_ms = cur_time_ms;1835write_imu_topic();1836}1837#endif // AP_DDS_IMU_PUB_ENABLED1838#if AP_DDS_GEOPOSE_PUB_ENABLED1839if (cur_time_ms - last_geo_pose_time_ms > DELAY_GEO_POSE_TOPIC_MS) {1840update_topic(geo_pose_topic);1841last_geo_pose_time_ms = cur_time_ms;1842write_geo_pose_topic();1843}1844#endif // AP_DDS_GEOPOSE_PUB_ENABLED1845#if AP_DDS_CLOCK_PUB_ENABLED1846if (cur_time_ms - last_clock_time_ms > DELAY_CLOCK_TOPIC_MS) {1847update_topic(clock_topic);1848last_clock_time_ms = cur_time_ms;1849write_clock_topic();1850}1851#endif // AP_DDS_CLOCK_PUB_ENABLED1852#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED1853if (cur_time_ms - last_gps_global_origin_time_ms > DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS) {1854update_topic(gps_global_origin_topic);1855last_gps_global_origin_time_ms = cur_time_ms;1856write_gps_global_origin_topic();1857}1858#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED1859#if AP_DDS_GOAL_PUB_ENABLED1860if (cur_time_ms - last_goal_time_ms > DELAY_GOAL_TOPIC_MS) {1861if (update_topic_goal(goal_topic)) {1862write_goal_topic();1863}1864last_goal_time_ms = cur_time_ms;1865}1866#endif // AP_DDS_GOAL_PUB_ENABLED1867#if AP_DDS_STATUS_PUB_ENABLED1868if (cur_time_ms - last_status_check_time_ms > DELAY_STATUS_TOPIC_MS) {1869if (update_topic(status_topic)) {1870write_status_topic();1871}1872last_status_check_time_ms = cur_time_ms;1873}1874#endif // AP_DDS_STATUS_PUB_ENABLED18751876status_ok = uxr_run_session_time(&session, 1);1877}18781879#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS1880extern "C" {1881int clock_gettime(clockid_t clockid, struct timespec *ts);1882}18831884int clock_gettime(clockid_t clockid, struct timespec *ts)1885{1886//! @todo the value of clockid is ignored here.1887//! A fallback mechanism is employed against the caller's choice of clock.1888uint64_t utc_usec;1889if (!AP::rtc().get_utc_usec(utc_usec)) {1890utc_usec = AP_HAL::micros64();1891}1892ts->tv_sec = utc_usec / 1000000ULL;1893ts->tv_nsec = (utc_usec % 1000000ULL) * 1000UL;1894return 0;1895}1896#endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS18971898#endif // AP_DDS_ENABLED189919001901