diff --git a/src/drivers/gpio/mcp23009/mcp23009_main.cpp b/src/drivers/gpio/mcp23009/mcp23009_main.cpp index f5f9a2cfc416..02061a1ccf76 100644 --- a/src/drivers/gpio/mcp23009/mcp23009_main.cpp +++ b/src/drivers/gpio/mcp23009/mcp23009_main.cpp @@ -97,7 +97,7 @@ void MCP23009::RunImpl() // read every time we run, either when requested or when scheduled on interval { - gpio_in_s _gpio_in; + gpio_in_s _gpio_in{}; _gpio_in.timestamp = hrt_absolute_time(); _gpio_in.device_id = get_device_id(); uint8_t input; diff --git a/src/drivers/uavcannode/Subscribers/ESCRawCommand.hpp b/src/drivers/uavcannode/Subscribers/ESCRawCommand.hpp index 83604fd161e2..38f439e862d1 100644 --- a/src/drivers/uavcannode/Subscribers/ESCRawCommand.hpp +++ b/src/drivers/uavcannode/Subscribers/ESCRawCommand.hpp @@ -81,7 +81,7 @@ class ESCRawCommand : void callback(const uavcan::ReceivedDataStructure &msg) { - actuator_motors_s actuator_motors; + actuator_motors_s actuator_motors{}; actuator_motors.timestamp = hrt_absolute_time(); actuator_motors.timestamp_sample = actuator_motors.timestamp; diff --git a/src/drivers/uavcannode/Subscribers/ServoArrayCommand.hpp b/src/drivers/uavcannode/Subscribers/ServoArrayCommand.hpp index a92693bb40f6..c0783a13ecdc 100644 --- a/src/drivers/uavcannode/Subscribers/ServoArrayCommand.hpp +++ b/src/drivers/uavcannode/Subscribers/ServoArrayCommand.hpp @@ -81,7 +81,7 @@ class ServoArrayCommand : void callback(const uavcan::ReceivedDataStructure &msg) { - actuator_servos_s actuator_servos; + actuator_servos_s actuator_servos{}; actuator_servos.timestamp = hrt_absolute_time(); actuator_servos.timestamp_sample = actuator_servos.timestamp; diff --git a/src/lib/dataman_client/DatamanClient.cpp b/src/lib/dataman_client/DatamanClient.cpp index c2c0ec995fcd..e4c77c07320b 100644 --- a/src/lib/dataman_client/DatamanClient.cpp +++ b/src/lib/dataman_client/DatamanClient.cpp @@ -259,7 +259,7 @@ bool DatamanClient::readAsync(dm_item_t item, uint32_t index, uint8_t *buffer, u hrt_abstime timestamp = hrt_absolute_time(); - dataman_request_s request; + dataman_request_s request{}; request.timestamp = timestamp; request.index = index; request.data_length = length; @@ -297,7 +297,7 @@ bool DatamanClient::writeAsync(dm_item_t item, uint32_t index, uint8_t *buffer, hrt_abstime timestamp = hrt_absolute_time(); - dataman_request_s request; + dataman_request_s request{}; request.timestamp = timestamp; request.index = index; request.data_length = length; @@ -332,7 +332,7 @@ bool DatamanClient::clearAsync(dm_item_t item) hrt_abstime timestamp = hrt_absolute_time(); - dataman_request_s request; + dataman_request_s request{}; request.timestamp = timestamp; request.client_id = _client_id; request.request_type = DM_CLEAR; @@ -397,7 +397,7 @@ void DatamanClient::update() _active_request.timestamp = timestamp; - dataman_request_s request; + dataman_request_s request{}; request.timestamp = timestamp; request.index = _active_request.index; request.data_length = _active_request.length; diff --git a/src/lib/drivers/accelerometer/PX4Accelerometer.cpp b/src/lib/drivers/accelerometer/PX4Accelerometer.cpp index f09120a14578..38909a4b7457 100644 --- a/src/lib/drivers/accelerometer/PX4Accelerometer.cpp +++ b/src/lib/drivers/accelerometer/PX4Accelerometer.cpp @@ -117,7 +117,7 @@ void PX4Accelerometer::update(const hrt_abstime ×tamp_sample, float x, floa rotate_3f(_rotation, x, y, z); // publish - sensor_accel_s report; + sensor_accel_s report{}; report.timestamp_sample = timestamp_sample; report.device_id = _device_id; @@ -151,7 +151,7 @@ void PX4Accelerometer::updateFIFO(sensor_accel_fifo_s &sample) // publish - sensor_accel_s report; + sensor_accel_s report{}; report.timestamp_sample = sample.timestamp_sample; report.device_id = _device_id; report.temperature = _temperature; diff --git a/src/lib/drivers/gyroscope/PX4Gyroscope.cpp b/src/lib/drivers/gyroscope/PX4Gyroscope.cpp index 687747d4aa92..5386659ef518 100644 --- a/src/lib/drivers/gyroscope/PX4Gyroscope.cpp +++ b/src/lib/drivers/gyroscope/PX4Gyroscope.cpp @@ -116,7 +116,7 @@ void PX4Gyroscope::update(const hrt_abstime ×tamp_sample, float x, float y, // Apply rotation (before scaling) rotate_3f(_rotation, x, y, z); - sensor_gyro_s report; + sensor_gyro_s report{}; report.timestamp_sample = timestamp_sample; report.device_id = _device_id; @@ -150,7 +150,7 @@ void PX4Gyroscope::updateFIFO(sensor_gyro_fifo_s &sample) // publish - sensor_gyro_s report; + sensor_gyro_s report{}; report.timestamp_sample = sample.timestamp_sample; report.device_id = _device_id; report.temperature = _temperature; diff --git a/src/lib/drivers/magnetometer/PX4Magnetometer.cpp b/src/lib/drivers/magnetometer/PX4Magnetometer.cpp index 40907d870d6d..bd2304d34140 100644 --- a/src/lib/drivers/magnetometer/PX4Magnetometer.cpp +++ b/src/lib/drivers/magnetometer/PX4Magnetometer.cpp @@ -62,7 +62,7 @@ void PX4Magnetometer::set_device_type(uint8_t devtype) void PX4Magnetometer::update(const hrt_abstime ×tamp_sample, float x, float y, float z) { - sensor_mag_s report; + sensor_mag_s report{}; report.timestamp_sample = timestamp_sample; report.device_id = _device_id; report.temperature = _temperature; diff --git a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.cpp b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.cpp index a6381485139f..85682698a8ae 100644 --- a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.cpp +++ b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.cpp @@ -91,7 +91,7 @@ bool HealthAndArmingChecks::update(bool force_reporting) _reporter._mavlink_log_pub = nullptr; // LEGACY end - health_report_s health_report; + health_report_s health_report{}; _reporter.getHealthReport(health_report); health_report.timestamp = hrt_absolute_time(); _health_report_pub.publish(health_report); diff --git a/src/modules/control_allocator/ControlAllocator.cpp b/src/modules/control_allocator/ControlAllocator.cpp index 48363eeb1e38..4c2713ca3382 100644 --- a/src/modules/control_allocator/ControlAllocator.cpp +++ b/src/modules/control_allocator/ControlAllocator.cpp @@ -657,11 +657,11 @@ ControlAllocator::publish_actuator_controls() return; } - actuator_motors_s actuator_motors; + actuator_motors_s actuator_motors{}; actuator_motors.timestamp = hrt_absolute_time(); actuator_motors.timestamp_sample = _timestamp_sample; - actuator_servos_s actuator_servos; + actuator_servos_s actuator_servos{}; actuator_servos.timestamp = actuator_motors.timestamp; actuator_servos.timestamp_sample = _timestamp_sample; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index af2eb6615f40..72618642de48 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1010,7 +1010,7 @@ void EKF2::PublishAttitude(const hrt_abstime ×tamp) { if (_ekf.attitude_valid()) { // generate vehicle attitude quaternion data - vehicle_attitude_s att; + vehicle_attitude_s att{}; att.timestamp_sample = timestamp; _ekf.getQuaternion().copyTo(att.q); @@ -1654,7 +1654,7 @@ void EKF2::PublishLocalPosition(const hrt_abstime ×tamp) void EKF2::PublishOdometry(const hrt_abstime ×tamp, const imuSample &imu_sample) { // generate vehicle odometry data - vehicle_odometry_s odom; + vehicle_odometry_s odom{}; odom.timestamp_sample = imu_sample.time_us; // position @@ -1765,7 +1765,7 @@ void EKF2::PublishSensorBias(const hrt_abstime ×tamp) void EKF2::PublishStates(const hrt_abstime ×tamp) { // publish estimator states - estimator_states_s states; + estimator_states_s states{}; states.timestamp_sample = _ekf.time_delayed_us(); const auto state_vector = _ekf.state().vector(); state_vector.copyTo(states.states); @@ -1965,7 +1965,7 @@ void EKF2::PublishYawEstimatorStatus(const hrt_abstime ×tamp) static_assert(sizeof(yaw_estimator_status_s::yaw) / sizeof(float) == N_MODELS_EKFGSF, "yaw_estimator_status_s::yaw wrong size"); - yaw_estimator_status_s yaw_est_test_data; + yaw_estimator_status_s yaw_est_test_data{}; if (_ekf.getDataEKFGSF(&yaw_est_test_data.yaw_composite, &yaw_est_test_data.yaw_variance, yaw_est_test_data.yaw, diff --git a/src/modules/ekf2/EKF2Selector.cpp b/src/modules/ekf2/EKF2Selector.cpp index f5f67e2cded9..c8b7e099361a 100644 --- a/src/modules/ekf2/EKF2Selector.cpp +++ b/src/modules/ekf2/EKF2Selector.cpp @@ -364,7 +364,7 @@ bool EKF2Selector::UpdateErrorScores() void EKF2Selector::PublishVehicleAttitude() { // selected estimator_attitude -> vehicle_attitude - vehicle_attitude_s attitude; + vehicle_attitude_s attitude{}; if (_instance[_selected_instance].estimator_attitude_sub.update(&attitude)) { bool instance_change = false; @@ -418,7 +418,7 @@ void EKF2Selector::PublishVehicleAttitude() void EKF2Selector::PublishVehicleLocalPosition() { // selected estimator_local_position -> vehicle_local_position - vehicle_local_position_s local_position; + vehicle_local_position_s local_position{}; if (_instance[_selected_instance].estimator_local_position_sub.update(&local_position)) { bool instance_change = false; @@ -544,7 +544,7 @@ void EKF2Selector::PublishVehicleLocalPosition() void EKF2Selector::PublishVehicleOdometry() { // selected estimator_odometry -> vehicle_odometry - vehicle_odometry_s odometry; + vehicle_odometry_s odometry{}; if (_instance[_selected_instance].estimator_odometry_sub.update(&odometry)) { @@ -591,7 +591,7 @@ void EKF2Selector::PublishVehicleOdometry() void EKF2Selector::PublishVehicleGlobalPosition() { // selected estimator_global_position -> vehicle_global_position - vehicle_global_position_s global_position; + vehicle_global_position_s global_position{}; if (_instance[_selected_instance].estimator_global_position_sub.update(&global_position)) { bool instance_change = false; @@ -672,7 +672,7 @@ void EKF2Selector::PublishVehicleGlobalPosition() void EKF2Selector::PublishWindEstimate() { // selected estimator_wind -> wind - wind_s wind; + wind_s wind{}; if (_instance[_selected_instance].estimator_wind_sub.update(&wind)) { bool publish = true; diff --git a/src/modules/gimbal/input_mavlink.cpp b/src/modules/gimbal/input_mavlink.cpp index ebfde30d2a73..62af8d76880c 100644 --- a/src/modules/gimbal/input_mavlink.cpp +++ b/src/modules/gimbal/input_mavlink.cpp @@ -470,7 +470,7 @@ void InputMavlinkGimbalV2::_stream_gimbal_manager_information(const ControlData { // TODO: Take gimbal_device_information into account. - gimbal_manager_information_s gimbal_manager_info; + gimbal_manager_information_s gimbal_manager_info{}; gimbal_manager_info.timestamp = hrt_absolute_time(); gimbal_manager_info.cap_flags = diff --git a/src/modules/mavlink/mavlink_ulog.cpp b/src/modules/mavlink/mavlink_ulog.cpp index 64b9ec981d20..45c3ba2cac1a 100644 --- a/src/modules/mavlink/mavlink_ulog.cpp +++ b/src/modules/mavlink/mavlink_ulog.cpp @@ -258,7 +258,7 @@ void MavlinkULog::handle_ack(mavlink_logging_ack_t ack) void MavlinkULog::publish_ack(uint16_t sequence) { - ulog_stream_ack_s ack; + ulog_stream_ack_s ack{}; ack.timestamp = hrt_absolute_time(); ack.msg_sequence = sequence; diff --git a/src/modules/mc_rate_control/MulticopterRateControl.cpp b/src/modules/mc_rate_control/MulticopterRateControl.cpp index e8a371d1e278..2c9aef08a95b 100644 --- a/src/modules/mc_rate_control/MulticopterRateControl.cpp +++ b/src/modules/mc_rate_control/MulticopterRateControl.cpp @@ -276,7 +276,7 @@ void MulticopterRateControl::updateActuatorControlsStatus(const vehicle_torque_s if (_energy_integration_time > 500e-3f) { - actuator_controls_status_s status; + actuator_controls_status_s status{}; status.timestamp = vehicle_torque_setpoint.timestamp; for (int i = 0; i < 3; i++) { diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp index ea2c30a18eee..2c317bb79d9b 100644 --- a/src/modules/navigator/geofence.cpp +++ b/src/modules/navigator/geofence.cpp @@ -104,7 +104,7 @@ void Geofence::run() _initiate_fence_updated = false; _dataman_state = DatamanState::Read; - geofence_status_s status; + geofence_status_s status{}; status.timestamp = hrt_absolute_time(); status.geofence_id = _opaque_id; status.status = geofence_status_s::GF_STATUS_LOADING; @@ -159,7 +159,7 @@ void Geofence::run() _dataman_state = DatamanState::UpdateRequestWait; _fence_updated = true; - geofence_status_s status; + geofence_status_s status{}; status.timestamp = hrt_absolute_time(); status.geofence_id = _opaque_id; status.status = geofence_status_s::GF_STATUS_READY; @@ -179,7 +179,7 @@ void Geofence::run() _updateFence(); _fence_updated = true; - geofence_status_s status; + geofence_status_s status{}; status.timestamp = hrt_absolute_time(); status.geofence_id = _opaque_id; status.status = geofence_status_s::GF_STATUS_READY; diff --git a/src/modules/payload_deliverer/payload_deliverer.cpp b/src/modules/payload_deliverer/payload_deliverer.cpp index 0edb3a527051..450ee086b462 100644 --- a/src/modules/payload_deliverer/payload_deliverer.cpp +++ b/src/modules/payload_deliverer/payload_deliverer.cpp @@ -236,7 +236,7 @@ void PayloadDeliverer::handle_vehicle_command(const hrt_abstime &now, const veh bool PayloadDeliverer::send_gripper_vehicle_command(const int32_t gripper_action) { - vehicle_command_s vcmd; + vehicle_command_s vcmd{}; vcmd.timestamp = hrt_absolute_time(); vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_GRIPPER; vcmd.param2 = gripper_action;