diff --git a/conf/airframes/BR/quadshot_asp21_FutabaPPMonUart1.xml b/conf/airframes/BR/quadshot_asp21_FutabaPPMonUart1.xml index abaa7f2bd5..6e230b70e4 100644 --- a/conf/airframes/BR/quadshot_asp21_FutabaPPMonUart1.xml +++ b/conf/airframes/BR/quadshot_asp21_FutabaPPMonUart1.xml @@ -370,7 +370,6 @@ diff --git a/conf/airframes/OPENUAS/openuas_eflite_t28.xml b/conf/airframes/OPENUAS/openuas_eflite_t28.xml index ee62176617..c53cec60bb 100644 --- a/conf/airframes/OPENUAS/openuas_eflite_t28.xml +++ b/conf/airframes/OPENUAS/openuas_eflite_t28.xml @@ -93,7 +93,6 @@ NOTES: - diff --git a/conf/airframes/OPENUAS/openuas_multiplex_minimag.xml b/conf/airframes/OPENUAS/openuas_multiplex_minimag.xml index 4253912f90..f4b943c2dd 100644 --- a/conf/airframes/OPENUAS/openuas_multiplex_minimag.xml +++ b/conf/airframes/OPENUAS/openuas_multiplex_minimag.xml @@ -101,7 +101,6 @@ NOTES: - diff --git a/conf/airframes/OPENUAS/openuas_multiplex_twinstar_nd.xml b/conf/airframes/OPENUAS/openuas_multiplex_twinstar_nd.xml index 8c75f45395..cf4b28eddb 100644 --- a/conf/airframes/OPENUAS/openuas_multiplex_twinstar_nd.xml +++ b/conf/airframes/OPENUAS/openuas_multiplex_twinstar_nd.xml @@ -78,7 +78,6 @@ NOTES: - diff --git a/conf/airframes/OPENUAS/openuas_own_flexo.xml b/conf/airframes/OPENUAS/openuas_own_flexo.xml index a6b20df730..7c703abe19 100644 --- a/conf/airframes/OPENUAS/openuas_own_flexo.xml +++ b/conf/airframes/OPENUAS/openuas_own_flexo.xml @@ -84,7 +84,6 @@ NOTES: - diff --git a/conf/airframes/OPENUAS/openuas_own_sumo_ii.xml b/conf/airframes/OPENUAS/openuas_own_sumo_ii.xml index d8eda59835..e45428562e 100644 --- a/conf/airframes/OPENUAS/openuas_own_sumo_ii.xml +++ b/conf/airframes/OPENUAS/openuas_own_sumo_ii.xml @@ -86,7 +86,6 @@ NOTES: - diff --git a/conf/airframes/OPENUAS/openuas_transitionrobotics_quadshot.xml b/conf/airframes/OPENUAS/openuas_transitionrobotics_quadshot.xml index 8fba227204..50de356204 100644 --- a/conf/airframes/OPENUAS/openuas_transitionrobotics_quadshot.xml +++ b/conf/airframes/OPENUAS/openuas_transitionrobotics_quadshot.xml @@ -83,7 +83,6 @@ diff --git a/conf/airframes/examples/MentorEnergy.xml b/conf/airframes/examples/MentorEnergy.xml index 69f5824f60..d57d827335 100644 --- a/conf/airframes/examples/MentorEnergy.xml +++ b/conf/airframes/examples/MentorEnergy.xml @@ -55,7 +55,6 @@ - diff --git a/conf/airframes/examples/quadshot_asp21_FutabaPPMonUart1.xml b/conf/airframes/examples/quadshot_asp21_FutabaPPMonUart1.xml index 97b8b137ee..7cdb2fb160 100644 --- a/conf/airframes/examples/quadshot_asp21_FutabaPPMonUart1.xml +++ b/conf/airframes/examples/quadshot_asp21_FutabaPPMonUart1.xml @@ -371,7 +371,6 @@ diff --git a/conf/airframes/examples/quadshot_asp21_spektrum.xml b/conf/airframes/examples/quadshot_asp21_spektrum.xml index a6fb51beb1..73ba852151 100644 --- a/conf/airframes/examples/quadshot_asp21_spektrum.xml +++ b/conf/airframes/examples/quadshot_asp21_spektrum.xml @@ -364,7 +364,6 @@ diff --git a/conf/airframes/examples/quadshot_pylons.xml b/conf/airframes/examples/quadshot_pylons.xml index 0011e89802..c534d6f6cd 100644 --- a/conf/airframes/examples/quadshot_pylons.xml +++ b/conf/airframes/examples/quadshot_pylons.xml @@ -250,7 +250,6 @@ - diff --git a/conf/modules/airspeed_ets.xml b/conf/modules/airspeed_ets.xml index 5643754a89..4cadfe3a91 100644 --- a/conf/modules/airspeed_ets.xml +++ b/conf/modules/airspeed_ets.xml @@ -22,7 +22,6 @@ - @@ -47,6 +46,9 @@ + + + diff --git a/conf/telemetry/default_fixedwing.xml b/conf/telemetry/default_fixedwing.xml index f84d338664..dacf1b23e6 100644 --- a/conf/telemetry/default_fixedwing.xml +++ b/conf/telemetry/default_fixedwing.xml @@ -72,6 +72,7 @@ + diff --git a/conf/telemetry/default_rotorcraft.xml b/conf/telemetry/default_rotorcraft.xml index 94e355a184..dad044031e 100644 --- a/conf/telemetry/default_rotorcraft.xml +++ b/conf/telemetry/default_rotorcraft.xml @@ -60,6 +60,7 @@ + diff --git a/conf/telemetry/default_rotorcraft_slow.xml b/conf/telemetry/default_rotorcraft_slow.xml index 609be2fdac..b977f3f399 100644 --- a/conf/telemetry/default_rotorcraft_slow.xml +++ b/conf/telemetry/default_rotorcraft_slow.xml @@ -51,7 +51,8 @@ - + + diff --git a/conf/telemetry/rotorcraft_with_logger.xml b/conf/telemetry/rotorcraft_with_logger.xml index 0ea2c53224..a953ca252d 100644 --- a/conf/telemetry/rotorcraft_with_logger.xml +++ b/conf/telemetry/rotorcraft_with_logger.xml @@ -50,7 +50,8 @@ - + + diff --git a/sw/airborne/arch/sim/led_hw.c b/sw/airborne/arch/sim/led_hw.c index 624c8f1dd1..008ea79d59 100644 --- a/sw/airborne/arch/sim/led_hw.c +++ b/sw/airborne/arch/sim/led_hw.c @@ -10,7 +10,7 @@ bool led_disabled = false; value register_leds_cb(value cb_name) { - leds_closure = caml_named_value(String_val(cb_name)); + leds_closure = (value *)caml_named_value(String_val(cb_name)); return Val_unit; } diff --git a/sw/airborne/arch/sim/sim_ap.c b/sw/airborne/arch/sim/sim_ap.c index fab8228568..12a356dcb7 100644 --- a/sw/airborne/arch/sim/sim_ap.c +++ b/sw/airborne/arch/sim/sim_ap.c @@ -107,7 +107,7 @@ value get_commands(value val_commands) value set_datalink_message(value s) { int n = string_length(s); - char *ss = String_val(s); + char *ss = (char *)String_val(s); assert(n <= MSG_SIZE); int i; diff --git a/sw/airborne/boards/ardrone/actuators.c b/sw/airborne/boards/ardrone/actuators.c index 11318f3e26..9d49cb8e55 100644 --- a/sw/airborne/boards/ardrone/actuators.c +++ b/sw/airborne/boards/ardrone/actuators.c @@ -66,6 +66,7 @@ int actuator_ardrone2_fd; /**< File descriptor for the port */ #define ARDRONE_GPIO_PIN_IRQ_INPUT 176 uint32_t led_hw_values; +uint16_t actuators_pwm_values[ACTUATORS_ARDRONE_NB]; static inline void actuators_ardrone_reset_flipflop(void) { diff --git a/sw/airborne/boards/ardrone/actuators.h b/sw/airborne/boards/ardrone/actuators.h index 69caa44a4c..b044004d0d 100644 --- a/sw/airborne/boards/ardrone/actuators.h +++ b/sw/airborne/boards/ardrone/actuators.h @@ -48,7 +48,7 @@ #define MOT_LEDGREEN 2 #define MOT_LEDORANGE 3 -uint16_t actuators_pwm_values[ACTUATORS_ARDRONE_NB]; +extern uint16_t actuators_pwm_values[ACTUATORS_ARDRONE_NB]; extern void actuators_ardrone_commit(void); extern void actuators_ardrone_init(void); diff --git a/sw/airborne/modules/sensors/airspeed_ets.c b/sw/airborne/modules/sensors/airspeed_ets.c index 003399f2ef..9a823b6720 100644 --- a/sw/airborne/modules/sensors/airspeed_ets.c +++ b/sw/airborne/modules/sensors/airspeed_ets.c @@ -49,6 +49,10 @@ #include "modules/datalink/downlink.h" #include +#if PERIODIC_TELEMETRY +#include "modules/datalink/telemetry.h" +#endif + #ifndef USE_AIRSPEED_ETS #if USE_AIRSPEED #define USE_AIRSPEED_ETS TRUE @@ -56,8 +60,8 @@ PRINT_CONFIG_MSG("USE_AIRSPEED_ETS automatically set to TRUE") #endif #endif -#if !USE_AIRSPEED_ETS && !AIRSPEED_ETS_SYNC_SEND -#warning either set USE_AIRSPEED_ETS or AIRSPEED_ETS_SYNC_SEND to use airspeed_ets +#if !USE_AIRSPEED_ETS +PRINT_CONFIG_MSG("AIRSPEED_ETS not used") #endif #define AIRSPEED_ETS_ADDR 0xEA @@ -93,6 +97,7 @@ bool log_airspeed_ets_started; #endif + // Global variables uint16_t airspeed_ets_raw; uint16_t airspeed_ets_offset; @@ -111,6 +116,21 @@ uint16_t airspeed_ets_cnt; uint32_t airspeed_ets_delay_time; bool airspeed_ets_delay_done; +static void airspeed_ets_downlink(struct transport_tx *trans, struct link_device *dev) +{ + uint8_t dev_id = AIRSPEED_ETS_ID; + float press = 0; + float temp = 0; + float offset = airspeed_ets_offset; + pprz_msg_send_AIRSPEED_RAW(trans,dev,AC_ID, + &dev_id, + &airspeed_ets_raw, + &offset, + &press, + &temp, + &airspeed_ets); +} + void airspeed_ets_init(void) { int n; @@ -133,6 +153,11 @@ void airspeed_ets_init(void) airspeed_ets_delay_done = false; SysTimeTimerStart(airspeed_ets_delay_time); + +#if PERIODIC_TELEMETRY + register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_AIRSPEED_RAW, airspeed_ets_downlink); +#endif + #ifndef SITL #if AIRSPEED_ETS_SDLOG log_airspeed_ets_started = false; @@ -232,9 +257,6 @@ void airspeed_ets_read_event(void) #if USE_AIRSPEED_ETS stateSetAirspeed_f(airspeed_ets); -#endif -#if AIRSPEED_ETS_SYNC_SEND - DOWNLINK_SEND_AIRSPEED_ETS(DefaultChannel, DefaultDevice, &airspeed_ets_raw, &airspeed_ets_offset, &airspeed_ets); #endif } else { airspeed_ets = 0.0; diff --git a/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.c b/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.c index 3ce494870f..00e1c7abfe 100644 --- a/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.c +++ b/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.c @@ -175,9 +175,14 @@ static Butterworth2LowPass ms45xx_filter; static void ms45xx_downlink(struct transport_tx *trans, struct link_device *dev) { - pprz_msg_send_AIRSPEED_MS45XX(trans,dev,AC_ID, + uint8_t dev_id = MS45XX_SENDER_ID; + float temp = ((float)ms45xx.temperature) * 0.1f; + pprz_msg_send_AIRSPEED_RAW(trans,dev,AC_ID, + &dev_id, + &ms45xx.raw_p, + &ms45xx.pressure_offset, &ms45xx.pressure, - &ms45xx.temperature, + &temp, &ms45xx.airspeed); } @@ -186,6 +191,7 @@ void ms45xx_i2c_init(void) ms45xx.pressure = 0.; ms45xx.temperature = 0; ms45xx.airspeed = 0.; + ms45xx.raw_p = 0; ms45xx.pressure_type = MS45XX_PRESSURE_TYPE; ms45xx.pressure_scale = MS45XX_PRESSURE_SCALE; ms45xx.pressure_offset = MS45XX_PRESSURE_OFFSET; @@ -200,7 +206,7 @@ void ms45xx_i2c_init(void) #endif #if PERIODIC_TELEMETRY - register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_AIRSPEED_MS45XX, ms45xx_downlink); + register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_AIRSPEED_RAW, ms45xx_downlink); #endif } @@ -228,6 +234,7 @@ void ms45xx_i2c_event(void) if (status == 0) { /* 14bit raw pressure */ uint16_t p_raw = 0x3FFF & (((uint16_t)(ms45xx_trans.buf[0]) << 8) | (uint16_t)(ms45xx_trans.buf[1])); + ms45xx.raw_p = p_raw; /* 11bit raw temperature, 5 LSB bits not used */ uint16_t temp_raw = 0xFFE0 & (((uint16_t)(ms45xx_trans.buf[2]) << 8) | diff --git a/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.h b/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.h index 78178c315e..847a79e71d 100644 --- a/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.h +++ b/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.h @@ -31,6 +31,7 @@ struct AirspeedMs45xx { float pressure; ///< (differential) pressure in Pascal int16_t temperature; ///< Temperature in 0.1 deg Celcius + uint16_t raw_p; ///< Raw pressure float airspeed; ///< Airspeed in m/s estimated from (differential) pressure. bool pressure_type; ///< Pressure type Differential of Gauge float airspeed_scale; ///< Quadratic scale factor to convert (differential) pressure to airspeed diff --git a/sw/airborne/modules/sensors/airspeed_sdp3x.c b/sw/airborne/modules/sensors/airspeed_sdp3x.c index 8529942c15..7bdcc2ab1a 100644 --- a/sw/airborne/modules/sensors/airspeed_sdp3x.c +++ b/sw/airborne/modules/sensors/airspeed_sdp3x.c @@ -143,10 +143,13 @@ static bool sdp3x_crc(const uint8_t data[], unsigned size, uint8_t checksum) static void sdp3x_downlink(struct transport_tx *trans, struct link_device *dev) { - int16_t temp = (int16_t)(sdp3x.temperature * 10.f); - pprz_msg_send_AIRSPEED_MS45XX(trans,dev,AC_ID, + uint8_t dev_id = SDP3X_SENDER_ID; + pprz_msg_send_AIRSPEED_RAW(trans,dev,AC_ID, + &dev_id, + &sdp3x.raw_p, + &sdp3x.pressure_offset, &sdp3x.pressure, - &temp, + &sdp3x.temperature, &sdp3x.airspeed); } @@ -170,7 +173,7 @@ void sdp3x_init(void) #endif #if PERIODIC_TELEMETRY - register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_AIRSPEED_MS45XX, sdp3x_downlink); // FIXME + register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_AIRSPEED_RAW, sdp3x_downlink); // FIXME #endif } @@ -216,6 +219,7 @@ void sdp3x_event(void) } int16_t p_raw = ((int16_t)(buf[0]) << 8) | (int16_t)(buf[1]); + sdp3x.raw_p = (uint16_t) p_raw; float p_out = ((float)p_raw / sdp3x.pressure_scale) - sdp3x.pressure_offset; diff --git a/sw/airborne/modules/sensors/airspeed_sdp3x.h b/sw/airborne/modules/sensors/airspeed_sdp3x.h index 9b801ad1ef..c7d4a48b44 100644 --- a/sw/airborne/modules/sensors/airspeed_sdp3x.h +++ b/sw/airborne/modules/sensors/airspeed_sdp3x.h @@ -37,6 +37,7 @@ struct AirspeedSdp3x { bool autoset_offset; ///< Set offset value from current filtered value bool sync_send; ///< Flag to enable sending every new measurement via telemetry for debugging purpose bool initialized; ///< init flag + uint16_t raw_p; ///< raw value from chip }; extern struct AirspeedSdp3x sdp3x; diff --git a/sw/airborne/modules/sensors/airspeed_uavcan.c b/sw/airborne/modules/sensors/airspeed_uavcan.c index ae7e480e3d..60dd3e4d44 100644 --- a/sw/airborne/modules/sensors/airspeed_uavcan.c +++ b/sw/airborne/modules/sensors/airspeed_uavcan.c @@ -61,9 +61,17 @@ struct airspeed_uavcan_s airspeed_uavcan; static void airspeed_uavcan_downlink(struct transport_tx *trans, struct link_device *dev) { - pprz_msg_send_AIRSPEED_UAVCAN(trans,dev,AC_ID, + uint8_t dev_id = UAVCAN_SENDER_ID; + uint16_t raw = 0; + float offset = 0; + float airspeed = 0; + pprz_msg_send_AIRSPEED_RAW(trans,dev,AC_ID, + &dev_id, + &raw, + &offset, &airspeed_uavcan.diff_p, - &airspeed_uavcan.temperature); + &airspeed_uavcan.temperature, + &airspeed); } static void airspeed_uavcan_cb(struct uavcan_iface_t *iface __attribute__((unused)), CanardRxTransfer *transfer) { @@ -118,6 +126,6 @@ void airspeed_uavcan_init(void) uavcan_bind(UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_ID, UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_SIGNATURE, &airspeed_uavcan_ev, &airspeed_uavcan_cb); #if PERIODIC_TELEMETRY - register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_AIRSPEED_UAVCAN, airspeed_uavcan_downlink); + register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_AIRSPEED_RAW, airspeed_uavcan_downlink); #endif } diff --git a/sw/ext/pprzlink b/sw/ext/pprzlink index fa4a56b0b4..976ed5280e 160000 --- a/sw/ext/pprzlink +++ b/sw/ext/pprzlink @@ -1 +1 @@ -Subproject commit fa4a56b0b4a49abb046d9413af76d8d4e35f5365 +Subproject commit 976ed5280ec4d55d1b3cde5b5370a45443f66b28