Compare commits

..

1 Commits

Author SHA1 Message Date
PX4 BuildBot 60e7be9007 boards: update all NuttX defconfigs 2024-03-25 11:50:39 +00:00
22 changed files with 46 additions and 38 deletions

View File

@ -1,14 +1,6 @@
root = true root = true
[*] [*.{c,cpp,cc,h,hpp}]
insert_final_newline = false
[{*.{c,cpp,cc,h,hpp},CMakeLists.txt,Kconfig}]
indent_style = tab indent_style = tab
tab_width = 8 tab_width = 8
# Not in the official standard, but supported by many editors
max_line_length = 120 max_line_length = 120
[*.yaml]
indent_style = space
indent_size = 2

View File

@ -219,12 +219,12 @@ CONFIG_STM32H7_TIM2=y
CONFIG_STM32H7_TIM3=y CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_TIM8=y CONFIG_STM32H7_TIM8=y
CONFIG_STM32H7_USART1=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_UART4=y CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART1=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART_BREAKS=y CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y CONFIG_STM32H7_USART_SINGLEWIRE=y

View File

@ -364,13 +364,6 @@ PX4IO::~PX4IO()
bool PX4IO::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], bool PX4IO::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) unsigned num_outputs, unsigned num_control_groups_updated)
{ {
for (size_t i = 0; i < num_outputs; i++) {
if (!_mixing_output.isFunctionSet(i)) {
// do not run any signal on disabled channels
outputs[i] = 0;
}
}
if (!_test_fmu_fail) { if (!_test_fmu_fail) {
/* output to the servos */ /* output to the servos */
io_reg_set(PX4IO_PAGE_DIRECT_PWM, 0, outputs, num_outputs); io_reg_set(PX4IO_PAGE_DIRECT_PWM, 0, outputs, num_outputs);

View File

@ -455,8 +455,7 @@ bool MixingOutput::update()
} }
} }
// Send output if any function mapped or one last disabling sample if (!all_disabled) {
if (!all_disabled || !_was_all_disabled) {
if (!_armed.armed && !_armed.manual_lockdown) { if (!_armed.armed && !_armed.manual_lockdown) {
_actuator_test.overrideValues(outputs, _max_num_outputs); _actuator_test.overrideValues(outputs, _max_num_outputs);
} }
@ -464,8 +463,6 @@ bool MixingOutput::update()
limitAndUpdateOutputs(outputs, has_updates); limitAndUpdateOutputs(outputs, has_updates);
} }
_was_all_disabled = all_disabled;
return true; return true;
} }

View File

@ -288,7 +288,6 @@ private:
hrt_abstime _lowrate_schedule_interval{300_ms}; hrt_abstime _lowrate_schedule_interval{300_ms};
ActuatorTest _actuator_test{_function_assignment}; ActuatorTest _actuator_test{_function_assignment};
uint32_t _reversible_mask{0}; ///< per-output bits. If set, the output is configured to be reversible (motors only) uint32_t _reversible_mask{0}; ///< per-output bits. If set, the output is configured to be reversible (motors only)
bool _was_all_disabled{false};
uORB::SubscriptionCallbackWorkItem *_subscription_callback{nullptr}; ///< current scheduling callback uORB::SubscriptionCallbackWorkItem *_subscription_callback{nullptr}; ///< current scheduling callback

View File

@ -191,15 +191,11 @@ TEST_F(MixerModuleTest, basic)
mixing_output.setAllMaxValues(MAX_VALUE); mixing_output.setAllMaxValues(MAX_VALUE);
EXPECT_EQ(test_module.num_updates, 0); EXPECT_EQ(test_module.num_updates, 0);
// all functions disabled: expect to get one single update to process disabling the output signal // all functions disabled: not expected to get an update
mixing_output.update(); mixing_output.update();
mixing_output.updateSubscriptions(false); mixing_output.updateSubscriptions(false);
mixing_output.update(); mixing_output.update();
EXPECT_EQ(test_module.num_updates, 1); EXPECT_EQ(test_module.num_updates, 0);
mixing_output.update();
mixing_output.updateSubscriptions(false);
mixing_output.update();
EXPECT_EQ(test_module.num_updates, 1);
test_module.reset(); test_module.reset();
// configure motor, ensure all still disarmed // configure motor, ensure all still disarmed

View File

@ -180,19 +180,15 @@ mixer_tick()
* Run the mixers. * Run the mixers.
*/ */
if (source == MIX_FAILSAFE) { if (source == MIX_FAILSAFE) {
// Set failsafe value if the PWM output isn't disabled /* copy failsafe values to the servo outputs */
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) { for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
if (r_page_servos[i] != 0) { r_page_servos[i] = r_page_servo_failsafe[i];
r_page_servos[i] = r_page_servo_failsafe[i];
}
} }
} else if (source == MIX_DISARMED) { } else if (source == MIX_DISARMED) {
// Set disarmed value if the PWM output isn't disabled /* copy disarmed values to the servo outputs */
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) { for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
if (r_page_servos[i] != 0) { r_page_servos[i] = r_page_servo_disarmed[i];
r_page_servos[i] = r_page_servo_disarmed[i];
}
} }
} }

View File

@ -85,6 +85,10 @@ menu "Zenoh publishers/subscribers"
bool "camera_trigger" bool "camera_trigger"
default n default n
config ZENOH_PUBSUB_CAN_INTERFACE_STATUS
bool "can_interface_status"
default n
config ZENOH_PUBSUB_CELLULAR_STATUS config ZENOH_PUBSUB_CELLULAR_STATUS
bool "cellular_status" bool "cellular_status"
default n default n
@ -249,6 +253,10 @@ menu "Zenoh publishers/subscribers"
bool "geofence_result" bool "geofence_result"
default n default n
config ZENOH_PUBSUB_GEOFENCE_STATUS
bool "geofence_status"
default n
config ZENOH_PUBSUB_GIMBAL_CONTROLS config ZENOH_PUBSUB_GIMBAL_CONTROLS
bool "gimbal_controls" bool "gimbal_controls"
default n default n
@ -465,6 +473,22 @@ menu "Zenoh publishers/subscribers"
bool "orbit_status" bool "orbit_status"
default n default n
config ZENOH_PUBSUB_PARAMETER_RESET_REQUEST
bool "parameter_reset_request"
default n
config ZENOH_PUBSUB_PARAMETER_SET_USED_REQUEST
bool "parameter_set_used_request"
default n
config ZENOH_PUBSUB_PARAMETER_SET_VALUE_REQUEST
bool "parameter_set_value_request"
default n
config ZENOH_PUBSUB_PARAMETER_SET_VALUE_RESPONSE
bool "parameter_set_value_response"
default n
config ZENOH_PUBSUB_PARAMETER_UPDATE config ZENOH_PUBSUB_PARAMETER_UPDATE
bool "parameter_update" bool "parameter_update"
default n default n
@ -545,6 +569,10 @@ menu "Zenoh publishers/subscribers"
bool "rpm" bool "rpm"
default n default n
config ZENOH_PUBSUB_RTL_STATUS
bool "rtl_status"
default n
config ZENOH_PUBSUB_RTL_TIME_ESTIMATE config ZENOH_PUBSUB_RTL_TIME_ESTIMATE
bool "rtl_time_estimate" bool "rtl_time_estimate"
default n default n
@ -851,6 +879,7 @@ config ZENOH_PUBSUB_ALL_SELECTION
select ZENOH_PUBSUB_CAMERA_CAPTURE select ZENOH_PUBSUB_CAMERA_CAPTURE
select ZENOH_PUBSUB_CAMERA_STATUS select ZENOH_PUBSUB_CAMERA_STATUS
select ZENOH_PUBSUB_CAMERA_TRIGGER select ZENOH_PUBSUB_CAMERA_TRIGGER
select ZENOH_PUBSUB_CAN_INTERFACE_STATUS
select ZENOH_PUBSUB_CELLULAR_STATUS select ZENOH_PUBSUB_CELLULAR_STATUS
select ZENOH_PUBSUB_COLLISION_CONSTRAINTS select ZENOH_PUBSUB_COLLISION_CONSTRAINTS
select ZENOH_PUBSUB_COLLISION_REPORT select ZENOH_PUBSUB_COLLISION_REPORT
@ -892,6 +921,7 @@ config ZENOH_PUBSUB_ALL_SELECTION
select ZENOH_PUBSUB_FOLLOW_TARGET_STATUS select ZENOH_PUBSUB_FOLLOW_TARGET_STATUS
select ZENOH_PUBSUB_GENERATOR_STATUS select ZENOH_PUBSUB_GENERATOR_STATUS
select ZENOH_PUBSUB_GEOFENCE_RESULT select ZENOH_PUBSUB_GEOFENCE_RESULT
select ZENOH_PUBSUB_GEOFENCE_STATUS
select ZENOH_PUBSUB_GIMBAL_CONTROLS select ZENOH_PUBSUB_GIMBAL_CONTROLS
select ZENOH_PUBSUB_GIMBAL_DEVICE_ATTITUDE_STATUS select ZENOH_PUBSUB_GIMBAL_DEVICE_ATTITUDE_STATUS
select ZENOH_PUBSUB_GIMBAL_DEVICE_INFORMATION select ZENOH_PUBSUB_GIMBAL_DEVICE_INFORMATION
@ -946,6 +976,10 @@ config ZENOH_PUBSUB_ALL_SELECTION
select ZENOH_PUBSUB_ORB_TEST_LARGE select ZENOH_PUBSUB_ORB_TEST_LARGE
select ZENOH_PUBSUB_ORB_TEST_MEDIUM select ZENOH_PUBSUB_ORB_TEST_MEDIUM
select ZENOH_PUBSUB_ORBIT_STATUS select ZENOH_PUBSUB_ORBIT_STATUS
select ZENOH_PUBSUB_PARAMETER_RESET_REQUEST
select ZENOH_PUBSUB_PARAMETER_SET_USED_REQUEST
select ZENOH_PUBSUB_PARAMETER_SET_VALUE_REQUEST
select ZENOH_PUBSUB_PARAMETER_SET_VALUE_RESPONSE
select ZENOH_PUBSUB_PARAMETER_UPDATE select ZENOH_PUBSUB_PARAMETER_UPDATE
select ZENOH_PUBSUB_PING select ZENOH_PUBSUB_PING
select ZENOH_PUBSUB_POSITION_CONTROLLER_LANDING_STATUS select ZENOH_PUBSUB_POSITION_CONTROLLER_LANDING_STATUS
@ -966,6 +1000,7 @@ config ZENOH_PUBSUB_ALL_SELECTION
select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REPLY select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REPLY
select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REQUEST select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REQUEST
select ZENOH_PUBSUB_RPM select ZENOH_PUBSUB_RPM
select ZENOH_PUBSUB_RTL_STATUS
select ZENOH_PUBSUB_RTL_TIME_ESTIMATE select ZENOH_PUBSUB_RTL_TIME_ESTIMATE
select ZENOH_PUBSUB_SATELLITE_INFO select ZENOH_PUBSUB_SATELLITE_INFO
select ZENOH_PUBSUB_SENSOR_ACCEL select ZENOH_PUBSUB_SENSOR_ACCEL