2016-05-16 04:22:34 -03:00
|
|
|
############################################################################
|
|
|
|
#
|
|
|
|
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
|
|
|
#
|
|
|
|
# Redistribution and use in source and binary forms, with or without
|
|
|
|
# modification, are permitted provided that the following conditions
|
|
|
|
# are met:
|
|
|
|
#
|
|
|
|
# 1. Redistributions of source code must retain the above copyright
|
|
|
|
# notice, this list of conditions and the following disclaimer.
|
|
|
|
# 2. Redistributions in binary form must reproduce the above copyright
|
|
|
|
# notice, this list of conditions and the following disclaimer in
|
|
|
|
# the documentation and/or other materials provided with the
|
|
|
|
# distribution.
|
|
|
|
# 3. Neither the name PX4 nor the names of its contributors may be
|
|
|
|
# used to endorse or promote products derived from this software
|
|
|
|
# without specific prior written permission.
|
|
|
|
#
|
|
|
|
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
|
|
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
|
|
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
|
|
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
|
|
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
|
|
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
|
|
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
|
|
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
|
|
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
|
|
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
|
|
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
|
|
# POSSIBILITY OF SUCH DAMAGE.
|
|
|
|
#
|
|
|
|
############################################################################
|
|
|
|
|
2019-11-22 08:48:09 -04:00
|
|
|
# Support IN_LIST if() operator
|
|
|
|
cmake_policy(SET CMP0057 NEW)
|
|
|
|
|
2021-05-05 06:09:28 -03:00
|
|
|
include(px4_list_make_absolute)
|
|
|
|
|
2017-09-25 19:00:59 -03:00
|
|
|
set(msg_files
|
2021-10-19 10:54:49 -03:00
|
|
|
action_request.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
actuator_armed.msg
|
|
|
|
actuator_controls.msg
|
2021-09-29 06:12:38 -03:00
|
|
|
actuator_controls_status.msg
|
2021-09-11 12:29:53 -03:00
|
|
|
actuator_motors.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
actuator_outputs.msg
|
2021-09-11 12:29:53 -03:00
|
|
|
actuator_servos.msg
|
2021-12-03 06:52:01 -04:00
|
|
|
actuator_servos_trim.msg
|
2021-11-05 07:44:12 -03:00
|
|
|
actuator_test.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
adc_report.msg
|
|
|
|
airspeed.msg
|
2019-08-07 08:06:00 -03:00
|
|
|
airspeed_validated.msg
|
2021-02-20 14:15:01 -04:00
|
|
|
airspeed_wind.msg
|
2021-09-29 06:01:06 -03:00
|
|
|
autotune_attitude_control_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
battery_status.msg
|
2022-04-04 05:50:09 -03:00
|
|
|
button_event.msg
|
2017-05-01 08:18:28 -03:00
|
|
|
camera_capture.msg
|
2021-07-31 13:41:49 -03:00
|
|
|
camera_status.msg
|
2017-09-21 17:24:53 -03:00
|
|
|
camera_trigger.msg
|
2019-11-13 10:19:02 -04:00
|
|
|
cellular_status.msg
|
2018-10-30 12:16:56 -03:00
|
|
|
collision_constraints.msg
|
2019-10-14 21:09:39 -03:00
|
|
|
collision_report.msg
|
2017-04-09 14:17:20 -03:00
|
|
|
commander_state.msg
|
2021-01-10 12:30:23 -04:00
|
|
|
control_allocator_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
cpuload.msg
|
|
|
|
differential_pressure.msg
|
|
|
|
distance_sensor.msg
|
2017-03-03 03:25:02 -04:00
|
|
|
ekf2_timestamps.msg
|
2022-02-18 12:56:43 -04:00
|
|
|
estimator_gps_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
esc_report.msg
|
|
|
|
esc_status.msg
|
2021-07-30 12:26:13 -03:00
|
|
|
estimator_baro_bias.msg
|
2021-03-07 17:16:48 -04:00
|
|
|
estimator_event_flags.msg
|
2019-11-11 05:27:57 -04:00
|
|
|
estimator_innovations.msg
|
2020-10-22 06:41:35 -03:00
|
|
|
estimator_optical_flow_vel.msg
|
2020-10-27 11:56:11 -03:00
|
|
|
estimator_selector_status.msg
|
2020-01-26 18:19:47 -04:00
|
|
|
estimator_sensor_bias.msg
|
2020-09-01 15:25:58 -03:00
|
|
|
estimator_states.msg
|
2020-01-18 02:15:00 -04:00
|
|
|
estimator_status.msg
|
msg: new estimator_status_flags message for more accessible ekf2 status logging
- log all estimator (ekf2) flags as separate booleans in a new dedicated low rate message (only publishes at 1 Hz or immediately on any change)
- this is a bit verbose, but it avoids the duplicate bit definitions we currently have across PX4 msgs, ecl analysis script, flight review, and many other custom tools and it's much easier for casual log review in FlightPlot, PlotJuggler, csv, etc
- for compatibility I've left estimator_status filter_fault_flags, innovation_check_flags, and solution_status_flags in place, but they can gradually be removed as tooling is updated
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
2020-12-29 12:27:21 -04:00
|
|
|
estimator_status_flags.msg
|
2022-03-15 11:27:46 -03:00
|
|
|
estimator_aid_source_1d.msg
|
|
|
|
estimator_aid_source_2d.msg
|
|
|
|
estimator_aid_source_3d.msg
|
2021-07-30 12:26:13 -03:00
|
|
|
event.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
follow_target.msg
|
2021-04-23 06:52:28 -03:00
|
|
|
failure_detector_status.msg
|
2020-09-25 12:36:58 -03:00
|
|
|
generator_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
geofence_result.msg
|
2020-05-12 05:32:16 -03:00
|
|
|
gimbal_device_attitude_status.msg
|
|
|
|
gimbal_device_information.msg
|
2021-02-20 14:15:01 -04:00
|
|
|
gimbal_device_set_attitude.msg
|
2020-05-12 05:32:16 -03:00
|
|
|
gimbal_manager_information.msg
|
2021-02-20 14:15:01 -04:00
|
|
|
gimbal_manager_set_attitude.msg
|
|
|
|
gimbal_manager_set_manual_control.msg
|
2020-05-12 05:32:16 -03:00
|
|
|
gimbal_manager_status.msg
|
2016-07-06 04:32:37 -03:00
|
|
|
gps_dump.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
gps_inject_data.msg
|
2021-02-16 11:04:53 -04:00
|
|
|
heater_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
home_position.msg
|
2020-01-19 08:56:05 -04:00
|
|
|
hover_thrust_estimate.msg
|
2021-07-30 23:31:43 -03:00
|
|
|
internal_combustion_engine_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
input_rc.msg
|
2018-04-18 09:06:12 -03:00
|
|
|
iridiumsbd_status.msg
|
2018-01-14 13:52:00 -04:00
|
|
|
irlock_report.msg
|
2018-10-30 14:23:56 -03:00
|
|
|
landing_gear.msg
|
2018-01-14 13:52:00 -04:00
|
|
|
landing_target_innovations.msg
|
|
|
|
landing_target_pose.msg
|
2017-02-24 05:04:08 -04:00
|
|
|
led_control.msg
|
2016-08-12 06:11:11 -03:00
|
|
|
log_message.msg
|
2020-01-29 18:29:30 -04:00
|
|
|
logger_status.msg
|
2021-01-20 10:44:45 -04:00
|
|
|
mag_worker_data.msg
|
2021-10-01 09:17:40 -03:00
|
|
|
magnetometer_bias_estimate.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
manual_control_setpoint.msg
|
2020-12-11 13:11:35 -04:00
|
|
|
manual_control_switches.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
mavlink_log.msg
|
2022-01-26 12:10:43 -04:00
|
|
|
mavlink_tunnel.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
mission.msg
|
|
|
|
mission_result.msg
|
2017-02-03 13:22:24 -04:00
|
|
|
mount_orientation.msg
|
2020-10-13 13:12:03 -03:00
|
|
|
navigator_mission_item.msg
|
2022-01-14 14:14:29 -04:00
|
|
|
npfg_status.msg
|
2018-02-16 09:05:08 -04:00
|
|
|
obstacle_distance.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
offboard_control_mode.msg
|
2019-10-12 01:55:12 -03:00
|
|
|
onboard_computer_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
optical_flow.msg
|
2018-12-04 09:53:53 -04:00
|
|
|
orbit_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
parameter_update.msg
|
2018-04-07 14:37:47 -03:00
|
|
|
ping.msg
|
2021-11-18 07:53:47 -04:00
|
|
|
pps_capture.msg
|
2018-07-25 11:31:17 -03:00
|
|
|
position_controller_landing_status.msg
|
|
|
|
position_controller_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
position_setpoint.msg
|
|
|
|
position_setpoint_triplet.msg
|
2017-07-24 08:05:52 -03:00
|
|
|
power_button_state.msg
|
2019-05-17 14:33:48 -03:00
|
|
|
power_monitor.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
pwm_input.msg
|
2020-07-16 15:39:13 -03:00
|
|
|
px4io_status.msg
|
2018-08-06 12:25:05 -03:00
|
|
|
radio_status.msg
|
2017-11-26 10:24:00 -04:00
|
|
|
rate_ctrl_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
rc_channels.msg
|
|
|
|
rc_parameter_map.msg
|
2020-03-11 10:06:33 -03:00
|
|
|
rpm.msg
|
2021-11-11 15:05:00 -04:00
|
|
|
rtl_time_estimate.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
satellite_info.msg
|
|
|
|
sensor_accel.msg
|
2019-10-14 21:09:39 -03:00
|
|
|
sensor_accel_fifo.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
sensor_baro.msg
|
|
|
|
sensor_combined.msg
|
2016-12-26 00:05:06 -04:00
|
|
|
sensor_correction.msg
|
2020-09-26 00:28:31 -03:00
|
|
|
sensor_gps.msg
|
2022-03-22 17:35:09 -03:00
|
|
|
sensor_gnss_relative.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
sensor_gyro.msg
|
2020-10-02 12:47:27 -03:00
|
|
|
sensor_gyro_fft.msg
|
2019-10-14 21:09:39 -03:00
|
|
|
sensor_gyro_fifo.msg
|
2021-10-20 06:49:13 -03:00
|
|
|
sensor_hygrometer.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
sensor_mag.msg
|
2020-08-16 22:56:15 -03:00
|
|
|
sensor_preflight_mag.msg
|
2017-09-21 17:24:53 -03:00
|
|
|
sensor_selection.msg
|
2020-09-06 23:06:13 -03:00
|
|
|
sensors_status_imu.msg
|
2022-03-04 10:51:02 -04:00
|
|
|
sensors_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
system_power.msg
|
2021-02-16 11:04:53 -04:00
|
|
|
takeoff_status.msg
|
2017-02-03 13:22:24 -04:00
|
|
|
task_stack_info.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
tecs_status.msg
|
|
|
|
telemetry_status.msg
|
|
|
|
test_motor.msg
|
2020-03-04 13:43:39 -04:00
|
|
|
timesync.msg
|
2018-03-12 02:52:03 -03:00
|
|
|
timesync_status.msg
|
2020-02-18 13:39:49 -04:00
|
|
|
trajectory_bezier.msg
|
2022-05-09 12:59:00 -03:00
|
|
|
trajectory_setpoint.msg
|
2018-03-31 08:43:24 -03:00
|
|
|
trajectory_waypoint.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
transponder_report.msg
|
2017-02-10 10:19:03 -04:00
|
|
|
tune_control.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
uavcan_parameter_request.msg
|
|
|
|
uavcan_parameter_value.msg
|
2016-10-12 11:36:42 -03:00
|
|
|
ulog_stream.msg
|
|
|
|
ulog_stream_ack.msg
|
2022-04-04 09:03:44 -03:00
|
|
|
uwb_grid.msg
|
|
|
|
uwb_distance.msg
|
2019-08-07 06:05:48 -03:00
|
|
|
vehicle_acceleration.msg
|
2018-02-18 12:44:21 -04:00
|
|
|
vehicle_air_data.msg
|
2020-01-27 17:44:01 -04:00
|
|
|
vehicle_angular_acceleration.msg
|
2021-01-10 12:30:23 -04:00
|
|
|
vehicle_angular_acceleration_setpoint.msg
|
2019-08-06 13:55:25 -03:00
|
|
|
vehicle_angular_velocity.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
vehicle_attitude.msg
|
|
|
|
vehicle_attitude_setpoint.msg
|
|
|
|
vehicle_command.msg
|
2017-04-09 14:17:20 -03:00
|
|
|
vehicle_command_ack.msg
|
2018-08-06 12:25:05 -03:00
|
|
|
vehicle_constraints.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
vehicle_control_mode.msg
|
|
|
|
vehicle_global_position.msg
|
|
|
|
vehicle_gps_position.msg
|
2020-01-21 17:47:38 -04:00
|
|
|
vehicle_imu.msg
|
2020-05-30 12:07:54 -03:00
|
|
|
vehicle_imu_status.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
vehicle_land_detected.msg
|
|
|
|
vehicle_local_position.msg
|
|
|
|
vehicle_local_position_setpoint.msg
|
2018-02-18 12:44:21 -04:00
|
|
|
vehicle_magnetometer.msg
|
2018-07-11 09:44:43 -03:00
|
|
|
vehicle_odometry.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
vehicle_rates_setpoint.msg
|
2017-02-03 13:22:24 -04:00
|
|
|
vehicle_roi.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
vehicle_status.msg
|
2017-01-27 14:00:39 -04:00
|
|
|
vehicle_status_flags.msg
|
2021-01-10 12:30:23 -04:00
|
|
|
vehicle_thrust_setpoint.msg
|
|
|
|
vehicle_torque_setpoint.msg
|
2020-02-18 13:39:49 -04:00
|
|
|
vehicle_trajectory_bezier.msg
|
2018-07-22 13:18:30 -03:00
|
|
|
vehicle_trajectory_waypoint.msg
|
2016-05-16 04:22:34 -03:00
|
|
|
vtol_vehicle_status.msg
|
2019-06-25 11:07:17 -03:00
|
|
|
wheel_encoders.msg
|
2021-02-20 14:15:01 -04:00
|
|
|
wind.msg
|
2020-03-15 13:57:25 -03:00
|
|
|
yaw_estimator_status.msg
|
2020-01-18 02:15:00 -04:00
|
|
|
)
|
2016-05-16 04:22:34 -03:00
|
|
|
|
2020-10-19 13:35:48 -03:00
|
|
|
if(NOT px4_constrained_flash_build)
|
|
|
|
list(APPEND msg_files
|
|
|
|
debug_array.msg
|
|
|
|
debug_key_value.msg
|
|
|
|
debug_value.msg
|
|
|
|
debug_vect.msg
|
|
|
|
)
|
|
|
|
endif()
|
|
|
|
|
2020-10-19 13:42:22 -03:00
|
|
|
if(PX4_TESTING)
|
|
|
|
list(APPEND msg_files
|
|
|
|
orb_test.msg
|
|
|
|
orb_test_large.msg
|
|
|
|
orb_test_medium.msg
|
|
|
|
)
|
|
|
|
endif()
|
|
|
|
|
2020-10-19 13:35:48 -03:00
|
|
|
list(SORT msg_files)
|
|
|
|
|
2019-11-22 08:48:09 -04:00
|
|
|
set(deprecated_msgs
|
2019-11-11 05:27:57 -04:00
|
|
|
ekf2_innovations.msg # 2019-11-22, Updated estimator interface and logging; replaced by 'estimator_innovations'.
|
2019-11-22 08:48:09 -04:00
|
|
|
)
|
|
|
|
|
|
|
|
foreach(msg IN LISTS deprecated_msgs)
|
|
|
|
if(msg IN_LIST msg_files)
|
|
|
|
get_filename_component(msg_we ${msg} NAME_WE)
|
|
|
|
list(APPEND invalid_msgs ${msg_we})
|
|
|
|
endif()
|
|
|
|
endforeach()
|
|
|
|
if(invalid_msgs)
|
|
|
|
list(LENGTH invalid_msgs invalid_msgs_size)
|
|
|
|
if(${invalid_msgs_size} GREATER 1)
|
|
|
|
foreach(msg IN LISTS invalid_msgs)
|
|
|
|
string(CONCAT invalid_msgs_cs ${invalid_msgs_cs} "'${msg}', ")
|
|
|
|
endforeach()
|
|
|
|
STRING(REGEX REPLACE ", +$" "" invalid_msgs_cs ${invalid_msgs_cs})
|
|
|
|
message(FATAL_ERROR "${invalid_msgs_cs} are listed as deprecated. Please use different names for the messages.")
|
|
|
|
else()
|
|
|
|
message(FATAL_ERROR "'${invalid_msgs}' is listed as deprecated. Please use a different name for the message.")
|
|
|
|
endif()
|
|
|
|
endif()
|
|
|
|
|
2021-05-05 06:09:28 -03:00
|
|
|
px4_list_make_absolute(msg_files ${CMAKE_CURRENT_SOURCE_DIR} ${msg_files})
|
|
|
|
|
2018-03-13 19:40:38 -03:00
|
|
|
if(NOT EXTERNAL_MODULES_LOCATION STREQUAL "")
|
|
|
|
# Check that the msg directory and the CMakeLists.txt file exists
|
|
|
|
if(EXISTS ${EXTERNAL_MODULES_LOCATION}/msg/CMakeLists.txt)
|
|
|
|
add_subdirectory(${EXTERNAL_MODULES_LOCATION}/msg external_msg)
|
|
|
|
|
|
|
|
# Add each of the external message files to the global msg_files list
|
|
|
|
foreach(external_msg_file ${config_msg_list_external})
|
|
|
|
list(APPEND msg_files ${EXTERNAL_MODULES_LOCATION}/msg/${external_msg_file})
|
|
|
|
endforeach()
|
|
|
|
endif()
|
|
|
|
endif()
|
|
|
|
|
2017-09-25 19:00:59 -03:00
|
|
|
# headers
|
|
|
|
set(msg_out_path ${PX4_BINARY_DIR}/uORB/topics)
|
2022-02-11 12:11:34 -04:00
|
|
|
set(ucdr_out_path ${PX4_BINARY_DIR}/uORB/ucdr)
|
2017-09-25 19:00:59 -03:00
|
|
|
set(msg_source_out_path ${CMAKE_CURRENT_BINARY_DIR}/topics_sources)
|
|
|
|
|
2020-03-11 10:06:33 -03:00
|
|
|
set(uorb_headers ${msg_out_path}/uORBTopics.hpp)
|
2017-09-25 19:00:59 -03:00
|
|
|
set(uorb_sources ${msg_source_out_path}/uORBTopics.cpp)
|
2022-02-11 12:11:34 -04:00
|
|
|
set(uorb_ucdr_headers)
|
2017-09-25 19:00:59 -03:00
|
|
|
foreach(msg_file ${msg_files})
|
|
|
|
get_filename_component(msg ${msg_file} NAME_WE)
|
|
|
|
list(APPEND uorb_headers ${msg_out_path}/${msg}.h)
|
|
|
|
list(APPEND uorb_sources ${msg_source_out_path}/${msg}.cpp)
|
2022-02-11 12:11:34 -04:00
|
|
|
list(APPEND uorb_ucdr_headers ${ucdr_out_path}/${msg}.h)
|
2016-05-16 04:22:34 -03:00
|
|
|
endforeach()
|
|
|
|
|
2019-10-18 06:23:32 -03:00
|
|
|
if (px4_constrained_flash_build)
|
|
|
|
set(added_arguments --constrained-flash)
|
|
|
|
endif()
|
|
|
|
|
2020-10-19 14:08:34 -03:00
|
|
|
# set parent scope msg_files for other modules to consume (eg topic_listener)
|
|
|
|
set(msg_files ${msg_files} PARENT_SCOPE)
|
|
|
|
|
2017-09-25 19:00:59 -03:00
|
|
|
# Generate uORB headers
|
|
|
|
add_custom_command(OUTPUT ${uorb_headers}
|
|
|
|
COMMAND ${PYTHON_EXECUTABLE} tools/px_generate_uorb_topic_files.py
|
|
|
|
--headers
|
|
|
|
-f ${msg_files}
|
|
|
|
-i ${CMAKE_CURRENT_SOURCE_DIR}
|
|
|
|
-o ${msg_out_path}
|
|
|
|
-e templates/uorb
|
|
|
|
-t ${CMAKE_CURRENT_BINARY_DIR}/tmp/headers
|
|
|
|
-q
|
2019-10-18 06:23:32 -03:00
|
|
|
${added_arguments}
|
2018-03-27 13:19:04 -03:00
|
|
|
DEPENDS
|
|
|
|
${msg_files}
|
2019-06-10 13:36:16 -03:00
|
|
|
templates/uorb/msg.h.em
|
2020-03-11 10:06:33 -03:00
|
|
|
templates/uorb/uORBTopics.hpp.em
|
2018-03-27 13:19:04 -03:00
|
|
|
tools/px_generate_uorb_topic_files.py
|
2020-07-16 18:31:07 -03:00
|
|
|
tools/px_generate_uorb_topic_helper.py
|
2017-09-25 19:00:59 -03:00
|
|
|
COMMENT "Generating uORB topic headers"
|
|
|
|
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
|
|
|
|
VERBATIM
|
|
|
|
)
|
|
|
|
add_custom_target(uorb_headers DEPENDS ${uorb_headers})
|
2017-01-13 11:43:48 -04:00
|
|
|
|
2022-02-11 12:11:34 -04:00
|
|
|
add_custom_command(OUTPUT ${uorb_ucdr_headers}
|
|
|
|
COMMAND ${PYTHON_EXECUTABLE} tools/px_generate_uorb_topic_files.py
|
|
|
|
--headers
|
|
|
|
-f ${msg_files}
|
|
|
|
-i ${CMAKE_CURRENT_SOURCE_DIR}
|
|
|
|
-o ${ucdr_out_path}
|
|
|
|
-e templates/ucdr
|
|
|
|
-t ${CMAKE_CURRENT_BINARY_DIR}/tmp/ucdr_headers
|
|
|
|
-q
|
|
|
|
${added_arguments}
|
|
|
|
DEPENDS
|
|
|
|
${msg_files}
|
|
|
|
templates/ucdr/msg.h.em
|
|
|
|
tools/px_generate_uorb_topic_files.py
|
|
|
|
tools/px_generate_uorb_topic_helper.py
|
|
|
|
COMMENT "Generating uORB topic ucdr headers"
|
|
|
|
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
|
|
|
|
VERBATIM
|
|
|
|
)
|
|
|
|
add_custom_target(uorb_ucdr_headers DEPENDS ${uorb_ucdr_headers})
|
|
|
|
|
2017-09-25 19:00:59 -03:00
|
|
|
# Generate uORB sources
|
|
|
|
add_custom_command(OUTPUT ${uorb_sources}
|
|
|
|
COMMAND ${PYTHON_EXECUTABLE} tools/px_generate_uorb_topic_files.py
|
|
|
|
--sources
|
|
|
|
-f ${msg_files}
|
|
|
|
-i ${CMAKE_CURRENT_SOURCE_DIR}
|
|
|
|
-o ${msg_source_out_path}
|
|
|
|
-e templates/uorb
|
|
|
|
-t ${CMAKE_CURRENT_BINARY_DIR}/tmp/sources
|
|
|
|
-q
|
2019-10-18 06:23:32 -03:00
|
|
|
${added_arguments}
|
2018-03-27 13:19:04 -03:00
|
|
|
DEPENDS
|
|
|
|
${msg_files}
|
2019-06-10 13:36:16 -03:00
|
|
|
templates/uorb/msg.cpp.em
|
2020-03-11 10:06:33 -03:00
|
|
|
templates/uorb/uORBTopics.cpp.em
|
2018-03-27 13:19:04 -03:00
|
|
|
tools/px_generate_uorb_topic_files.py
|
2020-07-16 18:31:07 -03:00
|
|
|
tools/px_generate_uorb_topic_helper.py
|
2017-09-25 19:00:59 -03:00
|
|
|
COMMENT "Generating uORB topic sources"
|
|
|
|
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
|
|
|
|
VERBATIM
|
|
|
|
)
|
2016-05-16 04:22:34 -03:00
|
|
|
|
2018-04-11 16:10:51 -03:00
|
|
|
add_library(uorb_msgs ${uorb_sources})
|
|
|
|
add_dependencies(uorb_msgs prebuild_targets uorb_headers)
|