AP_DDS: Preserve folder structure and includes for IDL files

* Remove ALL local changes in IDL (it mirrors upstream)
* Convert to pathlib for more robust manipulation
* Added EOF newlines for all the other missing IDL files

Co-authored-by: Arsh Pratap <arshpratapofficial@gmail.com>
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
arshPratap 2023-04-05 18:53:19 +05:30 committed by Andrew Tridgell
parent f604eedf65
commit 63ed2c646e
21 changed files with 90 additions and 109 deletions

View File

@ -9,7 +9,6 @@
#include <GCS_MAVLink/GCS.h>
#include "AP_DDS_Client.h"
#include "generated/Time.h"
static constexpr uint16_t DELAY_TIME_TOPIC_MS = 10;
@ -124,8 +123,6 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i
msg.position_covariance[8] = vdopSq;
}
#include "generated/TransformStamped.h"
void AP_DDS_Client::populate_static_transforms(tf2_msgs_msg_TFMessage& msg)
{
msg.transforms_size = 0;

View File

@ -4,11 +4,11 @@
#include "uxr/client/client.h"
#include "ucdr/microcdr.h"
#include "generated/Time.h"
#include "builtin_interfaces/msg/Time.h"
#include "AP_DDS_Generic_Fn_T.h"
#include "generated/NavSatFix.h"
#include "generated/TFMessage.h"
#include "sensor_msgs/msg/NavSatFix.h"
#include "tf2_msgs/msg/TFMessage.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Scheduler.h>

View File

@ -1,6 +1,6 @@
#include "generated/Time.h"
#include "generated/NavSatFix.h"
#include "generated/TransformStamped.h"
#include "builtin_interfaces/msg/Time.h"
#include "sensor_msgs/msg/NavSatFix.h"
#include "tf2_msgs/msg/TFMessage.h"
#include "AP_DDS_Generic_Fn_T.h"

View File

@ -20,3 +20,4 @@ module builtin_interfaces {
};
};
};

View File

@ -19,3 +19,4 @@ module builtin_interfaces {
};
};
};

View File

@ -16,3 +16,4 @@ module geometry_msgs {
};
};
};

View File

@ -2,8 +2,8 @@
// with input from geometry_msgs/msg/Pose.msg
// generated code does not contain a copyright notice
#include "Point.idl"
#include "Quaternion.idl"
#include "geometry_msgs/msg/Point.idl"
#include "geometry_msgs/msg/Quaternion.idl"
module geometry_msgs {
module msg {
@ -16,3 +16,4 @@ module geometry_msgs {
};
};
};

View File

@ -2,8 +2,8 @@
// with input from geometry_msgs/msg/PoseStamped.msg
// generated code does not contain a copyright notice
#include "Pose.idl"
#include "Header.idl"
#include "geometry_msgs/msg/Pose.idl"
#include "std_msgs/msg/Header.idl"
module geometry_msgs {
module msg {
@ -16,3 +16,4 @@ module geometry_msgs {
};
};
};

View File

@ -22,3 +22,4 @@ module geometry_msgs {
};
};
};

View File

@ -2,8 +2,8 @@
// with input from geometry_msgs/msg/Transform.msg
// generated code does not contain a copyright notice
#include "Quaternion.idl"
#include "Vector3.idl"
#include "geometry_msgs/msg/Quaternion.idl"
#include "geometry_msgs/msg/Vector3.idl"
module geometry_msgs {
module msg {

View File

@ -2,8 +2,8 @@
// with input from geometry_msgs/msg/TransformStamped.msg
// generated code does not contain a copyright notice
#include "Transform.idl"
#include "Header.idl"
#include "geometry_msgs/msg/Transform.idl"
#include "std_msgs/msg/Header.idl"
module geometry_msgs {
module msg {

View File

@ -2,7 +2,7 @@
// with input from geometry_msgs/msg/Twist.msg
// generated code does not contain a copyright notice
#include "Vector3.idl"
#include "geometry_msgs/msg/Vector3.idl"
module geometry_msgs {
module msg {
@ -15,3 +15,4 @@ module geometry_msgs {
};
};
};

View File

@ -2,13 +2,8 @@
// with input from geometry_msgs/msg/TwistStamped.msg
// generated code does not contain a copyright notice
#include "Vector3.idl"
#include "Header.idl"
struct Twist {
geometry_msgs::msg::Vector3 linear;
geometry_msgs::msg::Vector3 angular;
};
#include "geometry_msgs/msg/Twist.idl"
#include "std_msgs/msg/Header.idl"
module geometry_msgs {
module msg {
@ -17,7 +12,8 @@ module geometry_msgs {
struct TwistStamped {
std_msgs::msg::Header header;
Twist twist;
geometry_msgs::msg::Twist twist;
};
};
};

View File

@ -20,3 +20,4 @@ module geometry_msgs {
};
};
};

View File

@ -2,38 +2,38 @@
// with input from sensor_msgs/msg/BatteryState.msg
// generated code does not contain a copyright notice
#include "Header.idl"
#include "std_msgs/msg/Header.idl"
module sensor_msgs {
module msg {
module BatteryState_Constants {
@verbatim (language="comment", text=
"Constants are chosen to match the enums in the linux kernel" "\n" "defined in include/linux/power_supply.h as of version 3.7" "\n" "The one difference is for style reasons the constants are" "\n" "all uppercase not mixed case." "\n" "Power supply status constants")
const octet POWER_SUPPLY_STATUS_UNKNOWN = 0;
const octet POWER_SUPPLY_STATUS_CHARGING = 1;
const octet POWER_SUPPLY_STATUS_DISCHARGING = 2;
const octet POWER_SUPPLY_STATUS_NOT_CHARGING = 3;
const octet POWER_SUPPLY_STATUS_FULL = 4;
const uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0;
const uint8 POWER_SUPPLY_STATUS_CHARGING = 1;
const uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2;
const uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3;
const uint8 POWER_SUPPLY_STATUS_FULL = 4;
@verbatim (language="comment", text=
"Power supply health constants")
const octet POWER_SUPPLY_HEALTH_UNKNOWN = 0;
const octet POWER_SUPPLY_HEALTH_GOOD = 1;
const octet POWER_SUPPLY_HEALTH_OVERHEAT = 2;
const octet POWER_SUPPLY_HEALTH_DEAD = 3;
const octet POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4;
const octet POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5;
const octet POWER_SUPPLY_HEALTH_COLD = 6;
const octet POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7;
const octet POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8;
const uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0;
const uint8 POWER_SUPPLY_HEALTH_GOOD = 1;
const uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2;
const uint8 POWER_SUPPLY_HEALTH_DEAD = 3;
const uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4;
const uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5;
const uint8 POWER_SUPPLY_HEALTH_COLD = 6;
const uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7;
const uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8;
@verbatim (language="comment", text=
"Power supply technology (chemistry) constants")
const octet POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0;
const octet POWER_SUPPLY_TECHNOLOGY_NIMH = 1;
const octet POWER_SUPPLY_TECHNOLOGY_LION = 2;
const octet POWER_SUPPLY_TECHNOLOGY_LIPO = 3;
const octet POWER_SUPPLY_TECHNOLOGY_LIFE = 4;
const octet POWER_SUPPLY_TECHNOLOGY_NICD = 5;
const octet POWER_SUPPLY_TECHNOLOGY_LIMN = 6;
const uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0;
const uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1;
const uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2;
const uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3;
const uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4;
const uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5;
const uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6;
};
struct BatteryState {
std_msgs::msg::Header header;
@ -68,15 +68,15 @@ module sensor_msgs {
@verbatim (language="comment", text=
"The charging status as reported. Values defined above")
octet power_supply_status;
uint8 power_supply_status;
@verbatim (language="comment", text=
"The battery health metric. Values defined above")
octet power_supply_health;
uint8 power_supply_health;
@verbatim (language="comment", text=
"The battery chemistry. Values defined above")
octet power_supply_technology;
uint8 power_supply_technology;
@verbatim (language="comment", text=
"True if the battery is present")
@ -102,3 +102,4 @@ module sensor_msgs {
};
};
};

View File

@ -1,9 +1,9 @@
/// 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
#include "NavSatStatus.idl"
#include "Header.idl"
#include "sensor_msgs/msg/NavSatStatus.idl"
#include "std_msgs/msg/Header.idl"
module sensor_msgs {
module msg {
@ -65,3 +65,4 @@ module sensor_msgs {
};
};
};

View File

@ -2,7 +2,7 @@
// with input from std_msgs/msg/Header.msg
// generated code does not contain a copyright notice
#include "Time.idl"
#include "builtin_interfaces/msg/Time.idl"
module std_msgs {
module msg {
@ -21,3 +21,4 @@ module std_msgs {
};
};
};

View File

@ -2,7 +2,7 @@
// with input from tf2_msgs/msg/TFMessage.msg
// generated code does not contain a copyright notice
#include "TransformStamped.idl"
#include "geometry_msgs/msg/TransformStamped.idl"
module tf2_msgs {
module msg {

View File

@ -38,9 +38,9 @@ While DDS support in Ardupilot is mostly through git submodules, another tool ne
```console
sudo apt install default-jre
````
- Follow instructions [here](https://micro-xrce-dds.docs.eprosima.com/en/latest/installation.html#installing-the-micro-xrce-dds-gen-tool) to install the generator, but use `develop` branch instead of `master` (for now).
- Follow instructions [here](https://micro-xrce-dds.docs.eprosima.com/en/latest/installation.html#installing-the-micro-xrce-dds-gen-tool) to install the latest version of the generator
```console
git clone -b develop --recurse-submodules https://github.com/eProsima/Micro-XRCE-DDS-Gen.git
git clone --recurse-submodules https://github.com/eProsima/Micro-XRCE-DDS-Gen.git
cd Micro-XRCE-DDS-Gen
./gradlew assemble
```
@ -173,11 +173,7 @@ After your setups are complete, do the following:
## Adding DDS messages to Ardupilot
Unlike the use of ROS 2 `.msg` files, since Ardupilot supports native DDS, the message files follow [OMG IDL DDS v4.2](https://www.omg.org/spec/IDL/4.2/PDF).
This package is intended to work with any `.idl` file complying with those extensions, with some limitations.
1. IDL files need to be in the same folder, and modified includes.
1. Topic types can't use alias types.
1. Arrays need manually edited type names.
This package is intended to work with any `.idl` file complying with those extensions.
Over time, these restrictions will ideally go away.
@ -187,14 +183,9 @@ cd ardupilot
source /opt/ros/humble/setup.bash
# Find the IDL file
find /opt/ros/$ROS_DISTRO -type f -wholename \*builtin_interfaces/msg/Time.idl
# Create the directory in the source tree if it doesn't exist
mkdir -p libraries/AP_DDS_Client/Idl/builtin_interfaces/msg/
# Create the directory in the source tree if it doesn't exist similar to the one found in the ros directory
mkdir -p libraries/AP_DDS/Idl/builtin_interfaces/msg/
# Copy the IDL
cp -r /opt/ros/humble/share/builtin_interfaces/msg/Time.idl libraries/AP_DDS_Client/Idl/builtin_interfaces/msg/
# Now, apply the mods manually to be compliant with MicroXRCEDDSGen limitations
# Create an output directory to test it
mkdir -p /tmp/xrce_out
# Run the generator
microxrceddsgen -replace -d /tmp/xrce_out libraries/AP_DDS_Client/Idl/builtin_interfaces/msg/Time.idl
# cat /tmp/xrce_out/
cp /opt/ros/humble/share/builtin_interfaces/msg/Time.idl libraries/AP_DDS/Idl/builtin_interfaces/msg/
# Build the code again with the `--enable-dds` flag as described above
```

View File

@ -1,7 +1,7 @@
#!/usr/bin/env python3
import os
import pathlib
def configure(cfg):
@ -49,13 +49,13 @@ def build(bld):
extra_bld_inc = [
'modules/Micro-CDR/include',
'modules/Micro-XRCE-DDS-Client/include',
gen_path,
str(pathlib.PurePath(gen_path, "generated")),
]
for inc in extra_bld_inc:
bld.env.INCLUDES += [bld.bldnode.find_or_declare(inc).abspath()]
for i in range(len(config_h_nodes)):
print("building %s" % config_h_nodes[i].abspath())
print(f"building {config_h_nodes[i].abspath()}")
bld(
# build config.h file
source=config_h_in_nodes[i],
@ -71,42 +71,27 @@ def build(bld):
group='dynamic_sources',
)
# temporary whitelist while include issue is sorted out
whitelist = [
'BatteryState.idl',
'Duration.idl',
'Header.idl',
'NavSatFix.idl',
'NavSatStatus.idl',
'Point.idl',
'Pose.idl',
'PoseStamped.idl',
'Quaternion.idl',
'Time.idl',
'Transform.idl',
'TransformStamped.idl',
"TFMessage.idl",
'Twist.idl',
'TwistStamped.idl',
'Vector3.idl',
]
# TODO instead of keeping standard IDL files in the source tree, copy them with "ros2 pkg prefix --share " tools
idl_files = bld.srcnode.ant_glob('libraries/AP_DDS/Idl/**/*.idl')
idl_include_path = bld.srcnode.make_node(str(pathlib.PurePath(gen_path, "Idl"))).abspath()
for idl in idl_files:
b = os.path.basename(idl.abspath())
if not b in whitelist:
continue
gen_h = b.replace('.idl', '.h')
gen_c = b.replace('.idl', '.c')
gen = [
bld.bldnode.find_or_declare(os.path.join(gen_path, "generated", gen_h)),
bld.bldnode.find_or_declare(os.path.join(gen_path, "generated", gen_c)),
]
idl_path = pathlib.PurePath(idl.abspath())
b = idl_path.name
gen_h = idl_path.with_suffix('.h').name
gen_c = idl_path.with_suffix('.c').name
idl_folder = idl_path.parts[-3:-1]
dst_dir = pathlib.PurePath(gen_path, "generated", *idl_folder)
gen = [bld.bldnode.find_or_declare(str(dst_dir / name)) for name in [gen_h, gen_c]]
gen_cmd = f"{bld.env.MICROXRCEDDSGEN[0]} -cs -replace -d {dst_dir} -I {idl_include_path} {idl}"
bld(
# build IDL file
source=idl,
target=gen,
rule=f"{bld.env.MICROXRCEDDSGEN[0]} -cs -replace -d {os.path.join(gen_path, 'generated')} {idl}",
rule=gen_cmd,
group='dynamic_sources',
)
bld.env.AP_LIB_EXTRA_SOURCES['AP_DDS'] += [os.path.join('generated', gen_c)]
bld.env.AP_LIB_EXTRA_SOURCES['AP_DDS'] += [str(gen[1])]