mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-02-05 18:51:00 +08:00
[build] batch of fixes from CI errors and warnings (#2672)
This commit is contained in:
committed by
GitHub
parent
e4d9e10492
commit
7afb1b7fea
@@ -10,6 +10,10 @@
|
||||
|
||||
<target name="ap" board="crazyflie_2.1">
|
||||
<!--module name="gps" type="datalink"/-->
|
||||
<module name="cf_deck" type="multi_ranger"/>
|
||||
<module name="range_forcefield">
|
||||
<define name="RANGE_FORCEFIELD_MAX_VEL" value="0.1"/>
|
||||
</module>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
@@ -44,10 +48,6 @@
|
||||
<define name="BMP3_SLAVE_ADDR" value="BMP3_I2C_ADDR_ALT"/>
|
||||
</module>
|
||||
|
||||
<module name="cf_deck" type="multi_ranger"/>
|
||||
<module name="range_forcefield">
|
||||
<define name="RANGE_FORCEFIELD_MAX_VEL" value="0.1"/>
|
||||
</module>
|
||||
<module name="sonar" type="vl53l1x">
|
||||
<define name="SENSOR_SYNC_SEND_SONAR"/>
|
||||
</module>
|
||||
|
||||
@@ -17,7 +17,7 @@
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_guido_optitrack.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_indi.xml settings/control/rotorcraft_speed.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/optical_flow_landing.xml modules/video_capture.xml modules/cv_opticflow.xml modules/air_data.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
@@ -28,7 +28,7 @@
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_guido_optitrack.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_indi.xml settings/control/rotorcraft_speed.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/video_rtp_stream.xml modules/cv_undistort_image.xml modules/video_capture.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
@@ -39,7 +39,7 @@
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_indi.xml settings/control/rotorcraft_speed.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/video_capture.xml modules/cv_opticflow.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
|
||||
@@ -12,5 +12,5 @@
|
||||
<dep>
|
||||
<depends>stabilization_attitude_fw,guidance_basic_fw</depends>
|
||||
</dep>
|
||||
<makefile target="ap|sim|nps" firmware="fixedwing"/>
|
||||
<makefile target="ap|sim|nps|hitl" firmware="fixedwing"/>
|
||||
</module>
|
||||
|
||||
@@ -35,7 +35,7 @@
|
||||
<settings>
|
||||
<dl_settings>
|
||||
<dl_settings NAME="NavSkidLanding">
|
||||
<dl_setting var="v_ctl_landing_throttle_pgain" min="0" step="1" max="1000" shortname="throttle_pgain"/>
|
||||
<dl_setting var="v_ctl_landing_throttle_pgain" min="0" step="1" max="1000" shortname="throttle_pgain" module="guidance/guidance_v"/>
|
||||
<dl_setting var="v_ctl_landing_throttle_igain" min="0" step="0.1" max="100" shortname="throttle_igain"/>
|
||||
<dl_setting var="v_ctl_landing_throttle_max" min="0" step="0.01" max="1" shortname="throttle_max"/>
|
||||
<dl_setting var="v_ctl_landing_desired_speed" min="1" step="1" max="50" shortname="landing_speed"/>
|
||||
|
||||
@@ -35,7 +35,7 @@
|
||||
<init fun="opticflow_pmw3901_init()"/>
|
||||
<periodic fun="opticflow_pmw3901_periodic()" freq="100"/>
|
||||
<event fun="opticflow_pmw3901_event()"/>
|
||||
<makefile>
|
||||
<makefile target="ap">
|
||||
<configure name="OPTICFLOW_PMW3901_SPI_DEV" default="SPI2" case="upper|lower"/>
|
||||
<configure name="OPTICFLOW_PMW3901_SPI_SLAVE_IDX" default="1"/>
|
||||
<define name="USE_$(OPTICFLOW_PMW3901_SPI_DEV_UPPER)"/>
|
||||
|
||||
@@ -52,7 +52,7 @@
|
||||
</dl_settings>
|
||||
</settings>
|
||||
<dep>
|
||||
<depends>stabilization_rotorcraft"</depends>
|
||||
<depends>stabilization_rotorcraft</depends>
|
||||
</dep>
|
||||
<header>
|
||||
<file name="stabilization_indi.h"/>
|
||||
|
||||
@@ -7,10 +7,7 @@
|
||||
</description>
|
||||
</doc>
|
||||
<dep>
|
||||
<depends>stabilization_indi|stabilization_indi_simple</depends>
|
||||
</dep>
|
||||
<dep>
|
||||
<depends>stabilization_rotorcraft</depends>
|
||||
<depends>stabilization_indi|stabilization_indi_simple,stabilization_rotorcraft</depends>
|
||||
</dep>
|
||||
<header>
|
||||
<file name="stabilization_rate_indi.h"/>
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_optitrack.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_indi.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/optical_flow_hover.xml [modules/cv_opticflow.xml] modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="red"
|
||||
release="ac5eaa8da36b999a135f979e598930a9d40f6401"
|
||||
@@ -350,7 +350,7 @@
|
||||
radio="radios/T14SG_SBUS.xml"
|
||||
telemetry="telemetry/default_rotorcraft_slow.xml"
|
||||
flight_plan="flight_plans/tudelft/delft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml ../conf/modules/px4_flash.xml ../conf/modules/glide_wing_lock.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="[modules/air_data.xml] modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps_ubx_ucenter.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="#ffffcccaccca"
|
||||
release="677c4c77398cfbabffae3efdcafdacfd04a0b9ab"
|
||||
@@ -541,7 +541,7 @@
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/tudelft/fan_demo.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/air_data.xml [modules/geo_mag.xml] modules/guidance_indi.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="#ffffcccaccca"
|
||||
release="f580c07814aa1068bf3f6960318b2417fc069cbe"
|
||||
@@ -553,7 +553,7 @@
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/tudelft/rotorcraft_survey_imav2015_competition.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/digital_cam_video.xml modules/video_capture.xml modules/nav_survey_poly_rotorcraft.xml [modules/nav_survey_rectangle_rotorcraft.xml] modules/video_rtp_stream.xml modules/cv_blob_locator.xml modules/air_data.xml [modules/geo_mag.xml] modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/ahrs_float_mlkf.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="#68f5eb116e0c"
|
||||
/>
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
radio="radios/delfly_Rx31_DEVO10.xml"
|
||||
telemetry="telemetry/rotorcraft_with_logger.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml ../conf/modules/logger_sd_spi_direct.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/logger_sd_spi_direct.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_euler.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
@@ -17,7 +17,7 @@
|
||||
radio="radios/delfly_nimble_Rx31_Devo10.xml"
|
||||
telemetry="telemetry/rotorcraft_with_logger.xml"
|
||||
flight_plan="flight_plans/tudelft/delfly_nimble_cyberzoo.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/logger_sd_spi_direct.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_euler.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="blue"
|
||||
release="bd49f8763f106f69dc87ad735c8bd6ff277a3f62"
|
||||
|
||||
@@ -56,7 +56,7 @@ volatile int color_count = 0;
|
||||
#include "subsystems/abi.h"
|
||||
|
||||
// Function
|
||||
static struct image_t *colorfilter_func(struct image_t *img, uint8_t camera_id)
|
||||
static struct image_t *colorfilter_func(struct image_t *img, uint8_t camera_id __attribute__((unused)))
|
||||
{
|
||||
// Filter
|
||||
color_count = image_yuv422_colorfilt(img, img,
|
||||
|
||||
@@ -131,7 +131,7 @@ struct vision_relative_position_struct {
|
||||
|
||||
|
||||
// Function
|
||||
static struct image_t *detect_gate_func(struct image_t *img, uint8_t camera_id)
|
||||
static struct image_t *detect_gate_func(struct image_t *img, uint8_t camera_id __attribute__((unused)))
|
||||
{
|
||||
// detect the gate and draw it in the image:
|
||||
if (just_filtering) {
|
||||
|
||||
@@ -84,7 +84,7 @@ void video_capture_init(void)
|
||||
}
|
||||
|
||||
|
||||
struct image_t *video_capture_func(struct image_t *img, uint8_t camera_id)
|
||||
struct image_t *video_capture_func(struct image_t *img, uint8_t camera_id __attribute__((unused)))
|
||||
{
|
||||
// If take_shot bool is set, save the image
|
||||
if (video_capture_take_shot || video_capture_record_video) {
|
||||
|
||||
@@ -191,7 +191,7 @@ static struct image_t *viewvideo_function(struct UdpSocket *viewvideo_socket, st
|
||||
}
|
||||
|
||||
#ifdef VIEWVIDEO_CAMERA
|
||||
static struct image_t *viewvideo_function1(struct image_t *img, uint8_t camera_id)
|
||||
static struct image_t *viewvideo_function1(struct image_t *img, uint8_t camera_id __attribute__((unused)))
|
||||
{
|
||||
static uint16_t rtp_packet_nr = 0;
|
||||
static uint32_t rtp_frame_time = 0;
|
||||
@@ -202,7 +202,7 @@ static struct image_t *viewvideo_function1(struct image_t *img, uint8_t camera_i
|
||||
#endif
|
||||
|
||||
#ifdef VIEWVIDEO_CAMERA2
|
||||
static struct image_t *viewvideo_function2(struct image_t *img, uint8_t camera_id)
|
||||
static struct image_t *viewvideo_function2(struct image_t *img, uint8_t camera_id __attribute__((unused)))
|
||||
{
|
||||
static uint16_t rtp_packet_nr = 0;
|
||||
static uint32_t rtp_frame_time = 0;
|
||||
|
||||
@@ -168,8 +168,8 @@ static void send_divergence(struct transport_tx *trans, struct link_device *dev)
|
||||
/// Callback function of the ground altitude
|
||||
void vertical_ctrl_agl_cb(uint8_t sender_id, uint32_t stamp, float distance);
|
||||
// Callback function of the optical flow estimate:
|
||||
void vertical_ctrl_optical_flow_cb(uint8_t sender_id, uint32_t stamp, int16_t flow_x,
|
||||
int16_t flow_y, int16_t flow_der_x, int16_t flow_der_y, float quality, float size_divergence);
|
||||
void vertical_ctrl_optical_flow_cb(uint8_t sender_id, uint32_t stamp, int32_t flow_x,
|
||||
int32_t flow_y, int32_t flow_der_x, int32_t flow_der_y, float quality, float size_divergence);
|
||||
|
||||
// common functions for different landing strategies:
|
||||
static void set_cov_div(int32_t thrust);
|
||||
@@ -597,9 +597,9 @@ void vertical_ctrl_agl_cb(uint8_t sender_id UNUSED, __attribute__((unused)) uint
|
||||
of_landing_ctrl.agl = distance;
|
||||
}
|
||||
|
||||
void vertical_ctrl_optical_flow_cb(uint8_t sender_id UNUSED, uint32_t stamp, int16_t flow_x UNUSED,
|
||||
int16_t flow_y UNUSED,
|
||||
int16_t flow_der_x UNUSED, int16_t flow_der_y UNUSED, float quality UNUSED, float size_divergence)
|
||||
void vertical_ctrl_optical_flow_cb(uint8_t sender_id UNUSED, uint32_t stamp,
|
||||
int32_t flow_x UNUSED, int32_t flow_y UNUSED,
|
||||
int32_t flow_der_x UNUSED, int32_t flow_der_y UNUSED, float quality UNUSED, float size_divergence)
|
||||
{
|
||||
divergence_vision = size_divergence;
|
||||
vision_time = ((float)stamp) / 1e6;
|
||||
|
||||
@@ -49,10 +49,11 @@ static void tfmini_parse(uint8_t byte);
|
||||
*/
|
||||
static void tfmini_send_lidar(struct transport_tx *trans, struct link_device *dev)
|
||||
{
|
||||
uint8_t status = (uint8_t) tfmini.parse_status;
|
||||
pprz_msg_send_LIDAR(trans, dev, AC_ID,
|
||||
&tfmini.distance,
|
||||
&tfmini.mode,
|
||||
&tfmini.parse_status);
|
||||
&status);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@@ -162,7 +162,7 @@ void px4flow_init(void)
|
||||
void px4flow_downlink(void)
|
||||
{
|
||||
static float timestamp = 0;
|
||||
static float distance_quality = 0;
|
||||
static uint8_t distance_quality = 0;
|
||||
timestamp = ((float)optical_flow.time_usec) * 0.000001;
|
||||
DOWNLINK_SEND_OPTICAL_FLOW(DefaultChannel, DefaultDevice,
|
||||
×tamp,
|
||||
|
||||
@@ -267,7 +267,7 @@ void px4flow_i2c_downlink(void)
|
||||
uint8_t id = PX4FLOW_I2C_ID;
|
||||
|
||||
float timestamp = get_sys_time_float();
|
||||
static float distance_quality = 0;
|
||||
static uint8_t distance_quality = 0;
|
||||
|
||||
#if REQUEST_INT_FRAME
|
||||
int32_t flow_x = px4flow.i2c_int_frame.pixel_flow_x_integral;
|
||||
|
||||
Reference in New Issue
Block a user