diff --git a/src/drivers/distance_sensor/leddar_one/CMakeLists.txt b/src/drivers/distance_sensor/leddar_one/CMakeLists.txt index 1b02c17763..c49e01005e 100644 --- a/src/drivers/distance_sensor/leddar_one/CMakeLists.txt +++ b/src/drivers/distance_sensor/leddar_one/CMakeLists.txt @@ -36,5 +36,7 @@ px4_add_module( STACK_MAIN 1200 SRCS leddar_one.cpp + MODULE_CONFIG + module.yaml DEPENDS ) diff --git a/src/drivers/distance_sensor/leddar_one/module.yaml b/src/drivers/distance_sensor/leddar_one/module.yaml new file mode 100644 index 0000000000..cb16327fdf --- /dev/null +++ b/src/drivers/distance_sensor/leddar_one/module.yaml @@ -0,0 +1,7 @@ +module_name: LeddarOne Rangefinder +serial_config: + - command: leddar_one start -d ${SERIAL_DEV} + port_config_param: + name: SENS_LEDDAR1_CFG + group: Sensors + diff --git a/src/drivers/distance_sensor/sf0x/CMakeLists.txt b/src/drivers/distance_sensor/sf0x/CMakeLists.txt index 165788448c..f26411f4b2 100644 --- a/src/drivers/distance_sensor/sf0x/CMakeLists.txt +++ b/src/drivers/distance_sensor/sf0x/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( SRCS sf0x.cpp sf0x_parser.cpp + MODULE_CONFIG + module.yaml DEPENDS ) diff --git a/src/drivers/distance_sensor/sf0x/module.yaml b/src/drivers/distance_sensor/sf0x/module.yaml new file mode 100644 index 0000000000..b42a2ebc16 --- /dev/null +++ b/src/drivers/distance_sensor/sf0x/module.yaml @@ -0,0 +1,7 @@ +module_name: Lightware Laser Rangefinder +serial_config: + - command: sf0x start -d ${SERIAL_DEV} + port_config_param: + name: SENS_SF0X_CFG + group: Sensors + diff --git a/src/drivers/distance_sensor/tfmini/CMakeLists.txt b/src/drivers/distance_sensor/tfmini/CMakeLists.txt index 583012a3d7..e0cd265ad8 100644 --- a/src/drivers/distance_sensor/tfmini/CMakeLists.txt +++ b/src/drivers/distance_sensor/tfmini/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( SRCS tfmini.cpp tfmini_parser.cpp + MODULE_CONFIG + module.yaml DEPENDS ) diff --git a/src/drivers/distance_sensor/tfmini/module.yaml b/src/drivers/distance_sensor/tfmini/module.yaml new file mode 100644 index 0000000000..770cbe979c --- /dev/null +++ b/src/drivers/distance_sensor/tfmini/module.yaml @@ -0,0 +1,7 @@ +module_name: Benewake TFmini Rangefinder +serial_config: + - command: tfmini start -d ${SERIAL_DEV} + port_config_param: + name: SENS_TFMINI_CFG + group: Sensors + diff --git a/src/drivers/gps/CMakeLists.txt b/src/drivers/gps/CMakeLists.txt index deb5ce24d9..55f1ac7e97 100644 --- a/src/drivers/gps/CMakeLists.txt +++ b/src/drivers/gps/CMakeLists.txt @@ -44,6 +44,8 @@ px4_add_module( devices/src/ashtech.cpp devices/src/ubx.cpp devices/src/rtcm.cpp + MODULE_CONFIG + module.yaml DEPENDS git_gps_devices ) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 1cccc0768a..379aa91178 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -62,6 +62,7 @@ #include #include #include +#include #include #include #include @@ -111,7 +112,7 @@ public: }; GPS(const char *path, gps_driver_mode_t mode, GPSHelper::Interface interface, bool fake_gps, bool enable_sat_info, - Instance instance); + Instance instance, unsigned configured_baudrate); virtual ~GPS(); /** @see ModuleBase */ @@ -148,6 +149,7 @@ private: int _serial_fd{-1}; ///< serial interface to GPS unsigned _baudrate{0}; ///< current baudrate + const unsigned _configured_baudrate{0}; ///< configured baudrate (0=auto-detect) char _port[20] {}; ///< device / serial port path bool _healthy{false}; ///< flag to signal if the GPS is ok @@ -254,7 +256,8 @@ extern "C" __EXPORT int gps_main(int argc, char *argv[]); GPS::GPS(const char *path, gps_driver_mode_t mode, GPSHelper::Interface interface, bool fake_gps, - bool enable_sat_info, Instance instance) : + bool enable_sat_info, Instance instance, unsigned configured_baudrate) : + _configured_baudrate(configured_baudrate), _mode(mode), _interface(interface), _fake_gps(fake_gps), @@ -618,14 +621,6 @@ GPS::run() param_get(handle, &gps_ubx_dynmodel); } - int32_t configured_baudrate = 0; // auto-detect - handle = param_find("SER_GPS1_BAUD"); - - if (handle != PARAM_INVALID) { - param_get(handle, &configured_baudrate); - } - - _orb_inject_data_fd = orb_subscribe(ORB_ID(gps_inject_data)); initializeCommunicationDump(); @@ -694,7 +689,7 @@ GPS::run() break; } - _baudrate = configured_baudrate; + _baudrate = _configured_baudrate; if (_helper && _helper->configure(_baudrate, GPSHelper::OutputMode::GPS) == 0) { @@ -930,12 +925,16 @@ so that they can be used in other projects as well (eg. QGroundControl uses them For testing it can be useful to fake a GPS signal (it will signal the system that it has a valid position): $ gps stop $ gps start -f +Starting 2 GPS devices (the main GPS on /dev/ttyS3 and the secondary on /dev/ttyS4): +gps start -d /dev/ttyS3 -e /dev/ttyS4 )DESCR_STR"); PRINT_MODULE_USAGE_NAME("gps", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "", "GPS device", true); + PRINT_MODULE_USAGE_PARAM_INT('b', 0, 0, 3000000, "Baudrate (can also be p:)", true); PRINT_MODULE_USAGE_PARAM_STRING('e', nullptr, "", "Optional secondary GPS device", true); + PRINT_MODULE_USAGE_PARAM_INT('g', 0, 0, 3000000, "Baudrate (secondary GPS, can also be p:)", true); PRINT_MODULE_USAGE_PARAM_FLAG('f', "Fake a GPS signal (useful for testing)", true); PRINT_MODULE_USAGE_PARAM_FLAG('s', "Enable publication of satellite info", true); @@ -1006,6 +1005,8 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) { const char *device_name = "/dev/ttyS3"; const char *device_name_secondary = nullptr; + int baudrate_main = 0; + int baudrate_secondary = 0; bool fake_gps = false; bool enable_sat_info = false; GPSHelper::Interface interface = GPSHelper::Interface::UART; @@ -1016,8 +1017,21 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) int ch; const char *myoptarg = nullptr; - while ((ch = px4_getopt(argc, argv, "d:e:fsi:p:", &myoptind, &myoptarg)) != EOF) { + while ((ch = px4_getopt(argc, argv, "b:d:e:fg:si:p:", &myoptind, &myoptarg)) != EOF) { switch (ch) { + case 'b': + if (px4_get_parameter_value(myoptarg, baudrate_main) != 0) { + PX4_ERR("baudrate parsing failed"); + error_flag = true; + } + break; + case 'g': + if (px4_get_parameter_value(myoptarg, baudrate_secondary) != 0) { + PX4_ERR("baudrate parsing failed"); + error_flag = true; + } + break; + case 'd': device_name = myoptarg; break; @@ -1080,7 +1094,7 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) GPS *gps; if (instance == Instance::Main) { - gps = new GPS(device_name, mode, interface, fake_gps, enable_sat_info, instance); + gps = new GPS(device_name, mode, interface, fake_gps, enable_sat_info, instance, baudrate_main); if (gps && device_name_secondary) { task_spawn(argc, argv, Instance::Secondary); @@ -1098,7 +1112,7 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) } } } else { // secondary instance - gps = new GPS(device_name_secondary, mode, interface, fake_gps, enable_sat_info, instance); + gps = new GPS(device_name_secondary, mode, interface, fake_gps, enable_sat_info, instance, baudrate_secondary); } return gps; diff --git a/src/drivers/gps/module.yaml b/src/drivers/gps/module.yaml new file mode 100644 index 0000000000..484e434d58 --- /dev/null +++ b/src/drivers/gps/module.yaml @@ -0,0 +1,16 @@ +module_name: GPS +serial_config: + # secondary gps must be first + - command: set DUAL_GPS_ARGS "-e ${SERIAL_DEV} -g p:${BAUD_PARAM}" + port_config_param: + name: GPS_2_CONFIG + group: GPS + label: Secondary GPS + + - command: gps start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} ${DUAL_GPS_ARGS} + port_config_param: + name: GPS_1_CONFIG + group: GPS + default: GPS1 + label: Main GPS + diff --git a/src/drivers/gps/params.c b/src/drivers/gps/params.c index a898e7712d..ee105aff2b 100644 --- a/src/drivers/gps/params.c +++ b/src/drivers/gps/params.c @@ -86,21 +86,3 @@ PARAM_DEFINE_INT32(GPS_UBX_DYNMODEL, 7); */ PARAM_DEFINE_FLOAT(GPS_YAW_OFFSET, 0.f); - -/** - * GPS Baudrate - * - * Configure the Baudrate for the GPS Serial Port. In most cases this can be set to Auto. - * - * The Trimble MB-Two GPS does not support auto-detection and uses a baudrate of 115200. - * - * @value 0 Auto - * @value 9600 9600 8N1 - * @value 19200 19200 8N1 - * @value 38400 38400 8N1 - * @value 57600 57600 8N1 - * @value 115200 115200 8N1 - * @reboot_required true - * @group GPS - */ -PARAM_DEFINE_INT32(SER_GPS1_BAUD, 0); diff --git a/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt b/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt index 851f5cdc43..8f2bed90cf 100644 --- a/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt +++ b/src/drivers/telemetry/frsky_telemetry/CMakeLists.txt @@ -39,5 +39,7 @@ px4_add_module( frsky_data.cpp sPort_data.cpp frsky_telemetry.cpp + MODULE_CONFIG + module.yaml ) diff --git a/src/drivers/telemetry/frsky_telemetry/module.yaml b/src/drivers/telemetry/frsky_telemetry/module.yaml new file mode 100644 index 0000000000..796342de9c --- /dev/null +++ b/src/drivers/telemetry/frsky_telemetry/module.yaml @@ -0,0 +1,7 @@ +module_name: FrSky Telemetry +serial_config: + - command: frsky_telemetry start -d ${SERIAL_DEV} + port_config_param: + name: TEL_FRSKY_CONFIG + group: Telemetry + diff --git a/src/drivers/telemetry/hott/hott_telemetry/CMakeLists.txt b/src/drivers/telemetry/hott/hott_telemetry/CMakeLists.txt index f1abeaf762..81cf72d41c 100644 --- a/src/drivers/telemetry/hott/hott_telemetry/CMakeLists.txt +++ b/src/drivers/telemetry/hott/hott_telemetry/CMakeLists.txt @@ -36,6 +36,8 @@ px4_add_module( COMPILE_FLAGS SRCS hott_telemetry.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers__hott ) diff --git a/src/drivers/telemetry/hott/hott_telemetry/module.yaml b/src/drivers/telemetry/hott/hott_telemetry/module.yaml new file mode 100644 index 0000000000..ff50a8e3d4 --- /dev/null +++ b/src/drivers/telemetry/hott/hott_telemetry/module.yaml @@ -0,0 +1,7 @@ +module_name: HoTT Telemetry +serial_config: + - command: hott_telemetry start -d ${SERIAL_DEV} + port_config_param: + name: TEL_HOTT_CONFIG + group: Telemetry + diff --git a/src/drivers/telemetry/iridiumsbd/CMakeLists.txt b/src/drivers/telemetry/iridiumsbd/CMakeLists.txt index 8a6fc409ee..5c603f91c2 100644 --- a/src/drivers/telemetry/iridiumsbd/CMakeLists.txt +++ b/src/drivers/telemetry/iridiumsbd/CMakeLists.txt @@ -39,5 +39,7 @@ px4_add_module( SRCS IridiumSBD.cpp iridiumsbd_params.c + MODULE_CONFIG + module.yaml DEPENDS ) diff --git a/src/drivers/telemetry/iridiumsbd/module.yaml b/src/drivers/telemetry/iridiumsbd/module.yaml new file mode 100644 index 0000000000..f9b0bdb33d --- /dev/null +++ b/src/drivers/telemetry/iridiumsbd/module.yaml @@ -0,0 +1,15 @@ +module_name: Iridium (with MAVLink) +serial_config: + - command: | + # add a sleep here to make sure that the module is powered + usleep 200000 + if iridiumsbd start -d ${SERIAL_DEV} + then + mavlink start -d /dev/iridium -m iridium -b 115200 + else + tune_control play -t 20 + fi + port_config_param: + name: ISBD_CONFIG + group: Iridium SBD + diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index da98701e6a..1b82aee2fa 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -59,6 +59,8 @@ px4_add_module( mavlink_stream.cpp mavlink_ulog.cpp mavlink_timesync.cpp + MODULE_CONFIG + module.yaml DEPENDS airspeed git_mavlink_v2 diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 8fff96dd8d..c7b4f2b2af 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -682,6 +682,11 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, bool force_flow_ case 1500000: speed = B1500000; break; #endif +#ifdef B2000000 + + case 2000000: speed = B2000000; break; +#endif + #ifdef B3000000 case 3000000: speed = B3000000; break; diff --git a/src/modules/mavlink/module.yaml b/src/modules/mavlink/module.yaml new file mode 100644 index 0000000000..8aefa508a1 --- /dev/null +++ b/src/modules/mavlink/module.yaml @@ -0,0 +1,78 @@ +__max_num_config_instances: &max_num_config_instances 3 + +module_name: MAVLink +serial_config: + - command: | + set MAV_ARGS "-b p:${BAUD_PARAM} -m p:MAV_${i}_MODE -r p:MAV_${i}_RATE" + if param compare MAV_${i}_FORWARD 1 + then + set MAV_ARGS "${MAV_ARGS} -f" + fi + mavlink start -d ${SERIAL_DEV} ${MAV_ARGS} -x + port_config_param: + name: MAV_${i}_CONFIG + group: MAVLink + # MAVLink instances: + # 0: Telem1 Port (Telemetry Link) + # 1: Telem2 Port (Companion Link). Disabled by default to reduce RAM usage + # 2: Board-specific / no fixed function or port + default: [TEL1, "", ""] + num_instances: *max_num_config_instances + +parameters: + - group: MAVLink + definitions: + MAV_${i}_MODE: + description: + short: MAVLink Mode for instance ${i} + long: | + The MAVLink Mode defines the set of streamed messages (for example the + vehicle's attitude) and their sending rates. + + type: enum + values: + 0: Normal + 1: Custom + 2: Onboard + 3: OSD + 4: Magic + 5: Config + 6: Iridium + 7: Minimal + reboot_required: true + num_instances: *max_num_config_instances + default: [0, 2, 0] + + MAV_${i}_RATE: + description: + short: Maximum MAVLink sending rate for instance ${i} + long: | + Configure the maximum sending rate for the MAVLink streams in Bytes/sec. + If the configured streams exceed the maximum rate, the sending rate of + each stream is automatically decreased. + + If this is set to 0, a value of /20 is used, which corresponds to + half of the theoretical maximum bandwidth. + + type: int32 + min: 0 + unit: B/s + reboot_required: true + num_instances: *max_num_config_instances + default: [1200, 0, 0] + + MAV_${i}_FORWARD: + description: + short: Enable MAVLink Message forwarding for instance ${i} + long: | + If enabled, forward incoming MAVLink messages to other MAVLink ports if the + message is either broadcast or the target is not the autopilot. + + This allows for example a GCS to talk to a camera that is connected to the + autopilot via MAVLink (on a different link than the GCS). + + type: boolean + reboot_required: true + num_instances: *max_num_config_instances + default: [true, false, false] + diff --git a/src/modules/micrortps_bridge/micrortps_client/CMakeLists.txt b/src/modules/micrortps_bridge/micrortps_client/CMakeLists.txt index 56c430c8af..db8b6a4a24 100644 --- a/src/modules/micrortps_bridge/micrortps_client/CMakeLists.txt +++ b/src/modules/micrortps_bridge/micrortps_client/CMakeLists.txt @@ -106,6 +106,8 @@ if (NOT "${config_rtps_send_topics}" STREQUAL "" OR NOT "${config_rtps_receive_t microRTPS_client_main.cpp ${msg_out_path}/micrortps_client/microRTPS_client.cpp ${msg_out_path}/micrortps_client/microRTPS_transport.cpp + MODULE_CONFIG + module.yaml DEPENDS topic_bridge_files ) diff --git a/src/modules/micrortps_bridge/micrortps_client/module.yaml b/src/modules/micrortps_bridge/micrortps_client/module.yaml new file mode 100644 index 0000000000..608c0c31e6 --- /dev/null +++ b/src/modules/micrortps_bridge/micrortps_client/module.yaml @@ -0,0 +1,17 @@ +module_name: RTPS +serial_config: + - command: | + protocol_splitter start ${SERIAL_DEV} + mavlink start -d /dev/mavlink -b p:${BAUD_PARAM} -m onboard -r 5000 -x + micrortps_client start -d /dev/rtps -b p:${BAUD_PARAM} -l -1 + port_config_param: + name: RTPS_MAV_CONFIG + group: RTPS + label: MAVLink + FastRTPS + - command: | + micrortps_client start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} -l -1 + port_config_param: + name: RTPS_CONFIG + group: RTPS + label: FastRTPS +