px4-firmware/msg/CMakeLists.txt

327 lines
9.0 KiB
CMake
Raw Normal View History

############################################################################
#
# 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.
#
############################################################################
# Support IN_LIST if() operator
cmake_policy(SET CMP0057 NEW)
include(px4_list_make_absolute)
2017-09-25 19:00:59 -03:00
set(msg_files
action_request.msg
actuator_armed.msg
actuator_controls.msg
actuator_controls_status.msg
actuator_motors.msg
actuator_outputs.msg
actuator_servos.msg
actuator_servos_trim.msg
actuator_test.msg
adc_report.msg
airspeed.msg
airspeed_validated.msg
airspeed_wind.msg
autotune_attitude_control_status.msg
battery_status.msg
2017-05-01 08:18:28 -03:00
camera_capture.msg
camera_status.msg
camera_trigger.msg
cellular_status.msg
collision_constraints.msg
2019-10-14 21:09:39 -03:00
collision_report.msg
commander_state.msg
control_allocator_status.msg
cpuload.msg
differential_pressure.msg
distance_sensor.msg
ekf2_timestamps.msg
estimator_gps_status.msg
esc_report.msg
esc_status.msg
estimator_baro_bias.msg
estimator_event_flags.msg
estimator_innovations.msg
estimator_optical_flow_vel.msg
estimator_selector_status.msg
estimator_sensor_bias.msg
estimator_states.msg
estimator_status.msg
estimator_status_flags.msg
event.msg
follow_target.msg
failure_detector_status.msg
generator_status.msg
geofence_result.msg
Support for gimbal v2 protocol - add command to request a message - add gimbal attitude message mavlink_receiver handle GIMBAL_MANAGER_SET_ATTITUDE first implementation of new vmount input MavlinkGimbalV2 - setup class - decode gimbal_manager_set_attitude in ControlData add gimbal information message add gimbal manager information and vehicle command ack mavlink messages: add stream for GIMBAL_MANAGER_INFORMATION mavlink_receiver: handle GIMBAL_DEVICE_INFORMATION remove mavlink cmd handling from vmount input MavlinkGimbalV2 complete gimbal manager: - send out fake gimbal_device_information for dummy gimbals - complete ROI handling with nudging small fixes fix typos cleanup - gimbal device information - flags lock - check sanity of string add support for CMD_DO_GIMBAL_MANAGER_ATTITUDE stream GimbalDeviceAttitudeStatus for dummy gimbals - add uROB gimbal_attitude_status - fill status in vmount output_rc for dummy gimbals not able to send the status themselves - stream mavlink GimbalDeviceAttitudeStatus better handle the request for gimbal infomation request clean up bring gimbal information back on vmount init add new gimbal message to mavlink normal stream fix publication of gimbal device information rename gimbal_attitude_status to gimbal_device_attitude_status stream gimbal_manager_status at 5Hz mavlink: send information only on request Sending the information message once on request should now work and we don't need to keep publishing it. mavlink: debug output for now make sure to copy over control data mavlink: add missing copyright header, pragma once mavlink: address review comments mavlink: handle stream not updated Our answer does not just depend on whether the stream was found but whether we actually were able to send out an update. mavlink: remove outdated comment vmount: add option for yaw stabilization only The stabilize flag is used for gimbals which do not have an internal IMU and need the autopilot's attitude in order to do stabilization. These gimbals are probably quite rare by now but it makes sense to keep the functionality given it can e.g. be used by simple servo gimbals for sensors other than highres cameras. The stabilize flag can also be re-used for gimbals which are capable of stabilizing pitch and roll but not absolute yaw (e.g. locked to North). For such gimbals we can now set the param MNT_DO_STAB to 2. We still support configuring which axes are stabilized by the MAVLink command DO_MOUNT_CONFIGURE, however, this is generally not recommended anymore. vmount: fix incorrect check for bit flag mavlink_messages: remove debug message Signed-off-by: Claudio Micheli <claudio@auterion.com> use device id remove debug print gimbal attitude fix mistake clang tidy fix split: - gimbal_attitude -> gimbal_device_set_attitude, gimbal_manager_set_attitude - gimbal_information -> gimbal_device_informatio, gimbal_manager_information add gimbal protocol messages to rtps msg ids support set attitude for gimbal directly speaking mavlink clean up gimbal urob messages vmount: address a few small review comments vmount: split output into v1 and v2 protocol This way we can continue to support the MAVLink v1 protocol. Also, we don't send the old vehicle commands when actually using the new v2 protocol. vmount: config via ctor instead of duplicate param vmount: use loop to poll all topics Otherwise we might give up too soon and miss some data, or run too fast based on commands that have nothing to do with the gimbal. typhoon_h480: use gimbal v2 protocol, use yaw stab Let's by default use the v2 protocol with typhoon_h480 and enable yaw lock mode by stabilizing yaw.
2020-05-12 05:32:16 -03:00
gimbal_device_attitude_status.msg
gimbal_device_information.msg
gimbal_device_set_attitude.msg
Support for gimbal v2 protocol - add command to request a message - add gimbal attitude message mavlink_receiver handle GIMBAL_MANAGER_SET_ATTITUDE first implementation of new vmount input MavlinkGimbalV2 - setup class - decode gimbal_manager_set_attitude in ControlData add gimbal information message add gimbal manager information and vehicle command ack mavlink messages: add stream for GIMBAL_MANAGER_INFORMATION mavlink_receiver: handle GIMBAL_DEVICE_INFORMATION remove mavlink cmd handling from vmount input MavlinkGimbalV2 complete gimbal manager: - send out fake gimbal_device_information for dummy gimbals - complete ROI handling with nudging small fixes fix typos cleanup - gimbal device information - flags lock - check sanity of string add support for CMD_DO_GIMBAL_MANAGER_ATTITUDE stream GimbalDeviceAttitudeStatus for dummy gimbals - add uROB gimbal_attitude_status - fill status in vmount output_rc for dummy gimbals not able to send the status themselves - stream mavlink GimbalDeviceAttitudeStatus better handle the request for gimbal infomation request clean up bring gimbal information back on vmount init add new gimbal message to mavlink normal stream fix publication of gimbal device information rename gimbal_attitude_status to gimbal_device_attitude_status stream gimbal_manager_status at 5Hz mavlink: send information only on request Sending the information message once on request should now work and we don't need to keep publishing it. mavlink: debug output for now make sure to copy over control data mavlink: add missing copyright header, pragma once mavlink: address review comments mavlink: handle stream not updated Our answer does not just depend on whether the stream was found but whether we actually were able to send out an update. mavlink: remove outdated comment vmount: add option for yaw stabilization only The stabilize flag is used for gimbals which do not have an internal IMU and need the autopilot's attitude in order to do stabilization. These gimbals are probably quite rare by now but it makes sense to keep the functionality given it can e.g. be used by simple servo gimbals for sensors other than highres cameras. The stabilize flag can also be re-used for gimbals which are capable of stabilizing pitch and roll but not absolute yaw (e.g. locked to North). For such gimbals we can now set the param MNT_DO_STAB to 2. We still support configuring which axes are stabilized by the MAVLink command DO_MOUNT_CONFIGURE, however, this is generally not recommended anymore. vmount: fix incorrect check for bit flag mavlink_messages: remove debug message Signed-off-by: Claudio Micheli <claudio@auterion.com> use device id remove debug print gimbal attitude fix mistake clang tidy fix split: - gimbal_attitude -> gimbal_device_set_attitude, gimbal_manager_set_attitude - gimbal_information -> gimbal_device_informatio, gimbal_manager_information add gimbal protocol messages to rtps msg ids support set attitude for gimbal directly speaking mavlink clean up gimbal urob messages vmount: address a few small review comments vmount: split output into v1 and v2 protocol This way we can continue to support the MAVLink v1 protocol. Also, we don't send the old vehicle commands when actually using the new v2 protocol. vmount: config via ctor instead of duplicate param vmount: use loop to poll all topics Otherwise we might give up too soon and miss some data, or run too fast based on commands that have nothing to do with the gimbal. typhoon_h480: use gimbal v2 protocol, use yaw stab Let's by default use the v2 protocol with typhoon_h480 and enable yaw lock mode by stabilizing yaw.
2020-05-12 05:32:16 -03:00
gimbal_manager_information.msg
gimbal_manager_set_attitude.msg
gimbal_manager_set_manual_control.msg
Support for gimbal v2 protocol - add command to request a message - add gimbal attitude message mavlink_receiver handle GIMBAL_MANAGER_SET_ATTITUDE first implementation of new vmount input MavlinkGimbalV2 - setup class - decode gimbal_manager_set_attitude in ControlData add gimbal information message add gimbal manager information and vehicle command ack mavlink messages: add stream for GIMBAL_MANAGER_INFORMATION mavlink_receiver: handle GIMBAL_DEVICE_INFORMATION remove mavlink cmd handling from vmount input MavlinkGimbalV2 complete gimbal manager: - send out fake gimbal_device_information for dummy gimbals - complete ROI handling with nudging small fixes fix typos cleanup - gimbal device information - flags lock - check sanity of string add support for CMD_DO_GIMBAL_MANAGER_ATTITUDE stream GimbalDeviceAttitudeStatus for dummy gimbals - add uROB gimbal_attitude_status - fill status in vmount output_rc for dummy gimbals not able to send the status themselves - stream mavlink GimbalDeviceAttitudeStatus better handle the request for gimbal infomation request clean up bring gimbal information back on vmount init add new gimbal message to mavlink normal stream fix publication of gimbal device information rename gimbal_attitude_status to gimbal_device_attitude_status stream gimbal_manager_status at 5Hz mavlink: send information only on request Sending the information message once on request should now work and we don't need to keep publishing it. mavlink: debug output for now make sure to copy over control data mavlink: add missing copyright header, pragma once mavlink: address review comments mavlink: handle stream not updated Our answer does not just depend on whether the stream was found but whether we actually were able to send out an update. mavlink: remove outdated comment vmount: add option for yaw stabilization only The stabilize flag is used for gimbals which do not have an internal IMU and need the autopilot's attitude in order to do stabilization. These gimbals are probably quite rare by now but it makes sense to keep the functionality given it can e.g. be used by simple servo gimbals for sensors other than highres cameras. The stabilize flag can also be re-used for gimbals which are capable of stabilizing pitch and roll but not absolute yaw (e.g. locked to North). For such gimbals we can now set the param MNT_DO_STAB to 2. We still support configuring which axes are stabilized by the MAVLink command DO_MOUNT_CONFIGURE, however, this is generally not recommended anymore. vmount: fix incorrect check for bit flag mavlink_messages: remove debug message Signed-off-by: Claudio Micheli <claudio@auterion.com> use device id remove debug print gimbal attitude fix mistake clang tidy fix split: - gimbal_attitude -> gimbal_device_set_attitude, gimbal_manager_set_attitude - gimbal_information -> gimbal_device_informatio, gimbal_manager_information add gimbal protocol messages to rtps msg ids support set attitude for gimbal directly speaking mavlink clean up gimbal urob messages vmount: address a few small review comments vmount: split output into v1 and v2 protocol This way we can continue to support the MAVLink v1 protocol. Also, we don't send the old vehicle commands when actually using the new v2 protocol. vmount: config via ctor instead of duplicate param vmount: use loop to poll all topics Otherwise we might give up too soon and miss some data, or run too fast based on commands that have nothing to do with the gimbal. typhoon_h480: use gimbal v2 protocol, use yaw stab Let's by default use the v2 protocol with typhoon_h480 and enable yaw lock mode by stabilizing yaw.
2020-05-12 05:32:16 -03:00
gimbal_manager_status.msg
gps_dump.msg
gps_inject_data.msg
heater_status.msg
home_position.msg
hover_thrust_estimate.msg
internal_combustion_engine_status.msg
input_rc.msg
iridiumsbd_status.msg
irlock_report.msg
landing_gear.msg
landing_target_innovations.msg
landing_target_pose.msg
led_control.msg
log_message.msg
logger_status.msg
mag_worker_data.msg
magnetometer_bias_estimate.msg
manual_control_setpoint.msg
manual_control_switches.msg
mavlink_log.msg
mavlink_tunnel.msg
mission.msg
mission_result.msg
mount_orientation.msg
navigator_mission_item.msg
2022-01-14 14:14:29 -04:00
npfg_status.msg
obstacle_distance.msg
offboard_control_mode.msg
2019-10-12 01:55:12 -03:00
onboard_computer_status.msg
optical_flow.msg
2018-12-04 09:53:53 -04:00
orbit_status.msg
parameter_update.msg
2018-04-07 14:37:47 -03:00
ping.msg
pps_capture.msg
position_controller_landing_status.msg
position_controller_status.msg
position_setpoint.msg
position_setpoint_triplet.msg
power_button_state.msg
power_monitor.msg
pwm_input.msg
px4io_status.msg
radio_status.msg
rate_ctrl_status.msg
rc_channels.msg
rc_parameter_map.msg
rpm.msg
rtl_time_estimate.msg
safety.msg
satellite_info.msg
sensor_accel.msg
2019-10-14 21:09:39 -03:00
sensor_accel_fifo.msg
sensor_baro.msg
sensor_combined.msg
sensor_correction.msg
sensor_gps.msg
sensor_gyro.msg
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
sensor_mag.msg
sensor_preflight_mag.msg
sensor_selection.msg
sensors_status_imu.msg
system_power.msg
takeoff_status.msg
task_stack_info.msg
tecs_status.msg
telemetry_status.msg
test_motor.msg
timesync.msg
timesync_status.msg
trajectory_bezier.msg
trajectory_waypoint.msg
transponder_report.msg
2017-02-10 10:19:03 -04:00
tune_control.msg
uavcan_parameter_request.msg
uavcan_parameter_value.msg
ulog_stream.msg
ulog_stream_ack.msg
vehicle_acceleration.msg
vehicle_air_data.msg
vehicle_angular_acceleration.msg
vehicle_angular_acceleration_setpoint.msg
vehicle_angular_velocity.msg
vehicle_attitude.msg
vehicle_attitude_setpoint.msg
vehicle_command.msg
vehicle_command_ack.msg
vehicle_constraints.msg
vehicle_control_mode.msg
vehicle_global_position.msg
vehicle_gps_position.msg
vehicle_imu.msg
vehicle_imu_status.msg
vehicle_land_detected.msg
vehicle_local_position.msg
vehicle_local_position_setpoint.msg
vehicle_magnetometer.msg
2018-07-11 09:44:43 -03:00
vehicle_odometry.msg
vehicle_rates_setpoint.msg
vehicle_roi.msg
vehicle_status.msg
vehicle_status_flags.msg
vehicle_thrust_setpoint.msg
vehicle_torque_setpoint.msg
vehicle_trajectory_bezier.msg
vehicle_trajectory_waypoint.msg
vtol_vehicle_status.msg
wheel_encoders.msg
wind.msg
yaw_estimator_status.msg
)
if(NOT px4_constrained_flash_build)
list(APPEND msg_files
debug_array.msg
debug_key_value.msg
debug_value.msg
debug_vect.msg
)
endif()
if(PX4_TESTING)
list(APPEND msg_files
orb_test.msg
orb_test_large.msg
orb_test_medium.msg
)
endif()
list(SORT msg_files)
set(deprecated_msgs
ekf2_innovations.msg # 2019-11-22, Updated estimator interface and logging; replaced by 'estimator_innovations'.
)
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()
px4_list_make_absolute(msg_files ${CMAKE_CURRENT_SOURCE_DIR} ${msg_files})
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)
set(msg_source_out_path ${CMAKE_CURRENT_BINARY_DIR}/topics_sources)
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)
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)
endforeach()
if (px4_constrained_flash_build)
set(added_arguments --constrained-flash)
endif()
# 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
${added_arguments}
DEPENDS
${msg_files}
templates/uorb/msg.h.em
templates/uorb/uORBTopics.hpp.em
tools/px_generate_uorb_topic_files.py
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-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
${added_arguments}
DEPENDS
${msg_files}
templates/uorb/msg.cpp.em
templates/uorb/uORBTopics.cpp.em
tools/px_generate_uorb_topic_files.py
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
)
add_library(uorb_msgs ${uorb_sources})
add_dependencies(uorb_msgs prebuild_targets uorb_headers)