AP_DDS: Bump to using latest MicroXRCEDDSGen

* Adds -cs argument to fix case sensitive issue with PoseStamped
* Adds support for uint8_t type alias
* Updated the copies of IDL to remove these mods, matching upstream
* Solves #23302

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
Ryan Friedman 2023-03-22 22:22:03 -06:00 committed by Andrew Tridgell
parent c729a77e45
commit 80a0373717
4 changed files with 15 additions and 20 deletions

View File

@ -1,4 +1,4 @@
// generated from rosidl_adapter/resource/msg.idl.em
/// generated from rosidl_adapter/resource/msg.idl.em
// with input from sensor_msgs/msg/NavSatFix.msg
// generated code does not contain a copyright notice
@ -11,10 +11,10 @@ module sensor_msgs {
module NavSatFix_Constants {
@verbatim (language="comment", text=
"If the covariance of the fix is known, fill it in completely. If the" "\n" "GPS receiver provides the variance of each measurement, put them" "\n" "along the diagonal. If only Dilution of Precision is available," "\n" "estimate an approximate covariance from that.")
const octet COVARIANCE_TYPE_UNKNOWN = 0;
const octet COVARIANCE_TYPE_APPROXIMATED = 1;
const octet COVARIANCE_TYPE_DIAGONAL_KNOWN = 2;
const octet COVARIANCE_TYPE_KNOWN = 3;
const uint8 COVARIANCE_TYPE_UNKNOWN = 0;
const uint8 COVARIANCE_TYPE_APPROXIMATED = 1;
const uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2;
const uint8 COVARIANCE_TYPE_KNOWN = 3;
};
@verbatim (language="comment", text=
"Navigation Satellite fix for any Global Navigation Satellite System" "\n"
@ -59,9 +59,9 @@ module sensor_msgs {
"" "\n"
"Beware: this coordinate system exhibits singularities at the poles.")
@unit (value="m^2")
double position_covariance[9];
double__9 position_covariance;
octet position_covariance_type;
uint8 position_covariance_type;
};
};
};

View File

@ -8,16 +8,16 @@ module sensor_msgs {
module NavSatStatus_Constants {
@verbatim (language="comment", text=
"unable to fix position")
const char STATUS_NO_FIX = -1;
const int8 STATUS_NO_FIX = -1;
@verbatim (language="comment", text=
"unaugmented fix")
const char STATUS_FIX = 0;
const int8 STATUS_FIX = 0;
@verbatim (language="comment", text=
"with satellite-based augmentation")
const char STATUS_SBAS_FIX = 1;
const int8 STATUS_SBAS_FIX = 1;
@verbatim (language="comment", text=
"with ground-based augmentation")
const char STATUS_GBAS_FIX = 2;
const int8 STATUS_GBAS_FIX = 2;
@verbatim (language="comment", text=
"Bits defining which Global Navigation Satellite System signals were" "\n" "used by the receiver.")
const uint16 SERVICE_GPS = 1;
@ -34,7 +34,7 @@ module sensor_msgs {
"type and the last time differential corrections were received. A" "\n"
"fix is valid when status >= STATUS_FIX.")
struct NavSatStatus {
char status;
int8 status;
uint16 service;
};

View File

@ -2,14 +2,9 @@
// with input from geometry_msgs/msg/PoseStamped.msg
// generated code does not contain a copyright notice
#include "Point.idl"
#include "Quaternion.idl"
#include "Pose.idl"
#include "Header.idl"
struct Pose {
geometry_msgs::msg::Point position;
geometry_msgs::msg::Quaternion orientation;
};
module geometry_msgs {
module msg {
@verbatim (language="comment", text=
@ -17,7 +12,7 @@ module geometry_msgs {
struct PoseStamped {
std_msgs::msg::Header header;
Pose pose;
geometry_msgs::msg::Pose pose;
};
};
};

View File

@ -103,7 +103,7 @@ def build(bld):
# build IDL file
source=idl,
target=gen,
rule=f"{bld.env.MICROXRCEDDSGEN[0]} -replace -d {os.path.join(gen_path, 'generated')} {idl}",
rule=f"{bld.env.MICROXRCEDDSGEN[0]} -cs -replace -d {os.path.join(gen_path, 'generated')} {idl}",
group='dynamic_sources',
)
bld.env.AP_LIB_EXTRA_SOURCES['AP_DDS'] += [os.path.join('generated', gen_c)]