Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Global: Initialize the message variable #23560

Open
wants to merge 14 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/drivers/gpio/mcp23009/mcp23009_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/uavcannode/Subscribers/ESCRawCommand.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class ESCRawCommand :
void callback(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::RawCommand> &msg)
{

actuator_motors_s actuator_motors;
actuator_motors_s actuator_motors{};

actuator_motors.timestamp = hrt_absolute_time();
actuator_motors.timestamp_sample = actuator_motors.timestamp;
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/uavcannode/Subscribers/ServoArrayCommand.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class ServoArrayCommand :
void callback(const uavcan::ReceivedDataStructure<uavcan::equipment::actuator::ArrayCommand> &msg)
{

actuator_servos_s actuator_servos;
actuator_servos_s actuator_servos{};

actuator_servos.timestamp = hrt_absolute_time();
actuator_servos.timestamp_sample = actuator_servos.timestamp;
Expand Down
8 changes: 4 additions & 4 deletions src/lib/dataman_client/DatamanClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions src/lib/drivers/accelerometer/PX4Accelerometer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ void PX4Accelerometer::update(const hrt_abstime &timestamp_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;
Expand Down Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions src/lib/drivers/gyroscope/PX4Gyroscope.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ void PX4Gyroscope::update(const hrt_abstime &timestamp_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;
Expand Down Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion src/lib/drivers/magnetometer/PX4Magnetometer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ void PX4Magnetometer::set_device_type(uint8_t devtype)

void PX4Magnetometer::update(const hrt_abstime &timestamp_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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
4 changes: 2 additions & 2 deletions src/modules/control_allocator/ControlAllocator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
8 changes: 4 additions & 4 deletions src/modules/ekf2/EKF2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1010,7 +1010,7 @@ void EKF2::PublishAttitude(const hrt_abstime &timestamp)
{
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);

Expand Down Expand Up @@ -1654,7 +1654,7 @@ void EKF2::PublishLocalPosition(const hrt_abstime &timestamp)
void EKF2::PublishOdometry(const hrt_abstime &timestamp, const imuSample &imu_sample)
{
// generate vehicle odometry data
vehicle_odometry_s odom;
vehicle_odometry_s odom{};
odom.timestamp_sample = imu_sample.time_us;

// position
Expand Down Expand Up @@ -1765,7 +1765,7 @@ void EKF2::PublishSensorBias(const hrt_abstime &timestamp)
void EKF2::PublishStates(const hrt_abstime &timestamp)
{
// 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);
Expand Down Expand Up @@ -1965,7 +1965,7 @@ void EKF2::PublishYawEstimatorStatus(const hrt_abstime &timestamp)
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,
Expand Down
10 changes: 5 additions & 5 deletions src/modules/ekf2/EKF2Selector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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)) {

Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion src/modules/gimbal/input_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 =
Expand Down
2 changes: 1 addition & 1 deletion src/modules/mavlink/mavlink_ulog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
2 changes: 1 addition & 1 deletion src/modules/mc_rate_control/MulticopterRateControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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++) {
Expand Down
6 changes: 3 additions & 3 deletions src/modules/navigator/geofence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand All @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion src/modules/payload_deliverer/payload_deliverer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Loading