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

Tools: remove redundant DroneCAN packet buffer initialization #27743

Merged
merged 2 commits into from
Aug 3, 2024
Merged
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
4 changes: 2 additions & 2 deletions Tools/AP_Bootloader/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ static uint32_t get_random_range(uint16_t range)
static void handle_get_node_info(CanardInstance* ins,
CanardRxTransfer* transfer)
{
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
uavcan_protocol_GetNodeInfoResponse pkt {};

node_status.uptime_sec = AP_HAL::millis() / 1000U;
Expand Down Expand Up @@ -868,7 +868,7 @@ void can_printf(const char *fmt, ...)
// only on H7 for now, where we have plenty of flash
#if defined(STM32H7)
uavcan_protocol_debug_LogMessage pkt {};
uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];
va_list ap;
va_start(ap, fmt);
uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap);
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/adsb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ void AP_Periph_FW::can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg)
pkt.vertical_velocity_valid = (msg.flags & 0x0080) != 0;
pkt.baro_valid = (msg.flags & 0x0100) != 0;

uint8_t buffer[ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_MAX_SIZE] {};
uint8_t buffer[ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_MAX_SIZE];
uint16_t total_size = ardupilot_equipment_trafficmonitor_TrafficReport_encode(&pkt, buffer, !periph.canfdout());

canard_broadcast(ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SIGNATURE,
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ void AP_Periph_FW::can_airspeed_update(void)
}
#endif

uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_MAX_SIZE];
uint16_t total_size = uavcan_equipment_air_data_RawAirData_encode(&pkt, buffer, !periph.canfdout());

canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_SIGNATURE,
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/baro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ void AP_Periph_FW::can_baro_update(void)
pkt.static_pressure = press;
pkt.static_pressure_variance = 0; // should we make this a parameter?

uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_MAX_SIZE];
uint16_t total_size = uavcan_equipment_air_data_StaticPressure_encode(&pkt, buffer, !periph.canfdout());

canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_SIGNATURE,
Expand All @@ -49,7 +49,7 @@ void AP_Periph_FW::can_baro_update(void)
pkt.static_temperature = C_TO_KELVIN(temp);
pkt.static_temperature_variance = 0; // should we make this a parameter?

uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_MAX_SIZE];
uint16_t total_size = uavcan_equipment_air_data_StaticTemperature_encode(&pkt, buffer, !periph.canfdout());

canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_SIGNATURE,
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/battery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ void AP_Periph_FW::can_battery_update(void)
pkt.model_name.len = strnlen((char*)pkt.model_name.data, sizeof(pkt.model_name.data));
#endif //defined(HAL_PERIPH_BATTERY_SKIP_NAME)

uint8_t buffer[UAVCAN_EQUIPMENT_POWER_BATTERYINFO_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_POWER_BATTERYINFO_MAX_SIZE];
const uint16_t total_size = uavcan_equipment_power_BatteryInfo_encode(&pkt, buffer, !periph.canfdout());

canard_broadcast(UAVCAN_EQUIPMENT_POWER_BATTERYINFO_SIGNATURE,
Expand Down
18 changes: 9 additions & 9 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ static void readUniqueID(uint8_t* out_uid)
void AP_Periph_FW::handle_get_node_info(CanardInstance* canard_instance,
CanardRxTransfer* transfer)
{
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
uavcan_protocol_GetNodeInfoResponse pkt {};

node_status.uptime_sec = AP_HAL::millis() / 1000U;
Expand Down Expand Up @@ -324,7 +324,7 @@ void AP_Periph_FW::handle_param_getset(CanardInstance* canard_instance, CanardRx
pkt.name.len = strnlen((char *)pkt.name.data, sizeof(pkt.name.data));
}

uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE];
uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer, !canfdout());

canard_respond(canard_instance,
Expand Down Expand Up @@ -373,7 +373,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C

pkt.ok = true;

uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE];
uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer, !canfdout());

canard_respond(canard_instance,
Expand Down Expand Up @@ -406,7 +406,7 @@ void AP_Periph_FW::handle_begin_firmware_update(CanardInstance* canard_instance,
memcpy(comms->path, req.image_file_remote_path.path.data, req.image_file_remote_path.path.len);
comms->my_node_id = canardGetLocalNodeID(canard_instance);

uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE];
uavcan_protocol_file_BeginFirmwareUpdateResponse reply {};
reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK;

Expand Down Expand Up @@ -753,7 +753,7 @@ void AP_Periph_FW::can_safety_button_update(void)
pkt.button = ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY;
pkt.press_time = counter;

uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE] {};
uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE];
uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer, !canfdout());

canard_broadcast(ARDUPILOT_INDICATION_BUTTON_SIGNATURE,
Expand Down Expand Up @@ -1711,7 +1711,7 @@ void AP_Periph_FW::esc_telem_update()
pkt.power_rating_pct = 0;
pkt.error_count = 0;

uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE];
uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout());
canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE,
UAVCAN_EQUIPMENT_ESC_STATUS_ID,
Expand Down Expand Up @@ -1744,7 +1744,7 @@ void AP_Periph_FW::apd_esc_telem_update()
pkt.power_rating_pct = t.power_rating_pct;
pkt.error_count = t.error_count;

uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE];
uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout());
canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE,
UAVCAN_EQUIPMENT_ESC_STATUS_ID,
Expand Down Expand Up @@ -1913,7 +1913,7 @@ void can_vprintf(uint8_t severity, const char *fmt, va_list ap)
memcpy(pkt.text.data, &buffer_data[buffer_offset], pkt.text.len);
buffer_offset += pkt.text.len;

uint8_t buffer_packet[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE] {};
uint8_t buffer_packet[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];
const uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer_packet, !periph.canfdout());

periph.canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE,
Expand All @@ -1925,7 +1925,7 @@ void can_vprintf(uint8_t severity, const char *fmt, va_list ap)

#else
uavcan_protocol_debug_LogMessage pkt {};
uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];
uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap);
pkt.level.value = level;
pkt.text.len = MIN(n, sizeof(pkt.text.data));
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/compass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ void AP_Periph_FW::can_mag_update(void)
pkt.magnetic_field_ga[i] = field_Ga[i];
}

uint8_t buffer[UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_MAX_SIZE];
uint16_t total_size = uavcan_equipment_ahrs_MagneticFieldStrength_encode(&pkt, buffer, !periph.canfdout());

canard_broadcast(UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_SIGNATURE,
Expand All @@ -86,7 +86,7 @@ void AP_Periph_FW::can_mag_update(void)
pkt.magnetic_field_ga[i] = field_Ga[i];
}

uint8_t buffer[DRONECAN_SENSORS_MAGNETOMETER_MAGNETICFIELDSTRENGTHHIRES_MAX_SIZE] {};
uint8_t buffer[DRONECAN_SENSORS_MAGNETOMETER_MAGNETICFIELDSTRENGTHHIRES_MAX_SIZE];
uint16_t total_size = dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes_encode(&pkt, buffer, !periph.canfdout());

canard_broadcast(DRONECAN_SENSORS_MAGNETOMETER_MAGNETICFIELDSTRENGTHHIRES_SIGNATURE,
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/efi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ void AP_Periph_FW::can_efi_update(void)
c.exhaust_gas_temperature = state_c.exhaust_gas_temperature;
c.lambda_coefficient = state_c.lambda_coefficient;

uint8_t buffer[UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_MAX_SIZE];
const uint16_t total_size = uavcan_equipment_ice_reciprocating_Status_encode(&pkt, buffer, !canfdout());

canard_broadcast(UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_SIGNATURE,
Expand Down
12 changes: 6 additions & 6 deletions Tools/AP_Periph/gps.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ void AP_Periph_FW::can_gps_update(void)

check_float16_range(pkt.covariance.data, pkt.covariance.len);

uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_FIX2_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_FIX2_MAX_SIZE];
uint16_t total_size = uavcan_equipment_gnss_Fix2_encode(&pkt, buffer, !canfdout());

canard_broadcast(UAVCAN_EQUIPMENT_GNSS_FIX2_SIGNATURE,
Expand All @@ -177,7 +177,7 @@ void AP_Periph_FW::can_gps_update(void)
aux.hdop = gps.get_hdop() * 0.01;
aux.vdop = gps.get_vdop() * 0.01;

uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_AUXILIARY_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_AUXILIARY_MAX_SIZE];
uint16_t total_size = uavcan_equipment_gnss_Auxiliary_encode(&aux, buffer, !canfdout());
canard_broadcast(UAVCAN_EQUIPMENT_GNSS_AUXILIARY_SIGNATURE,
UAVCAN_EQUIPMENT_GNSS_AUXILIARY_ID,
Expand All @@ -204,7 +204,7 @@ void AP_Periph_FW::can_gps_update(void)
status.error_codes = error_codes;
}

uint8_t buffer[ARDUPILOT_GNSS_STATUS_MAX_SIZE] {};
uint8_t buffer[ARDUPILOT_GNSS_STATUS_MAX_SIZE];
const uint16_t total_size = ardupilot_gnss_Status_encode(&status, buffer, !canfdout());
canard_broadcast(ARDUPILOT_GNSS_STATUS_SIGNATURE,
ARDUPILOT_GNSS_STATUS_ID,
Expand All @@ -226,7 +226,7 @@ void AP_Periph_FW::can_gps_update(void)
heading.heading_accuracy_valid = is_positive(yaw_acc_deg);
heading.heading_rad = radians(yaw_deg);
heading.heading_accuracy_rad = radians(yaw_acc_deg);
uint8_t buffer[ARDUPILOT_GNSS_HEADING_MAX_SIZE] {};
uint8_t buffer[ARDUPILOT_GNSS_HEADING_MAX_SIZE];
const uint16_t total_size = ardupilot_gnss_Heading_encode(&heading, buffer, !canfdout());
canard_broadcast(ARDUPILOT_GNSS_HEADING_SIGNATURE,
ARDUPILOT_GNSS_HEADING_ID,
Expand Down Expand Up @@ -271,7 +271,7 @@ void AP_Periph_FW::send_moving_baseline_msg()
mbldata.data.len = n;
memcpy(mbldata.data.data, data, n);

uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE] {};
uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE];
const uint16_t total_size = ardupilot_gnss_MovingBaselineData_encode(&mbldata, buffer, !canfdout());

canard_broadcast(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE,
Expand Down Expand Up @@ -307,7 +307,7 @@ void AP_Periph_FW::send_relposheading_msg() {
relpos.relative_down_pos_m = relative_down_pos;
relpos.reported_heading_acc_deg = reported_heading_acc;
relpos.reported_heading_acc_available = !is_zero(relpos.reported_heading_acc_deg);
uint8_t buffer[ARDUPILOT_GNSS_RELPOSHEADING_MAX_SIZE] {};
uint8_t buffer[ARDUPILOT_GNSS_RELPOSHEADING_MAX_SIZE];
const uint16_t total_size = ardupilot_gnss_RelPosHeading_encode(&relpos, buffer, !canfdout());
canard_broadcast(ARDUPILOT_GNSS_RELPOSHEADING_SIGNATURE,
ARDUPILOT_GNSS_RELPOSHEADING_ID,
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/hardpoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ void AP_Periph_FW::pwm_hardpoint_update()
cmd.hardpoint_id = g.hardpoint_id;
cmd.command = value;

uint8_t buffer[UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_MAX_SIZE];
uint16_t total_size = uavcan_equipment_hardpoint_Command_encode(&cmd, buffer, !canfdout());
canard_broadcast(UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE,
UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID,
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/hwing_esc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ void AP_Periph_FW::hwesc_telem_update()
pkt.power_rating_pct = t.phase_current;
pkt.error_count = t.error_count;

uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE];
uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout());
canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE,
UAVCAN_EQUIPMENT_ESC_STATUS_ID,
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/proximity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ void AP_Periph_FW::can_proximity_update()
break;
}

uint8_t buffer[ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY_MAX_SIZE] {};
uint8_t buffer[ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY_MAX_SIZE];
uint16_t total_size = ardupilot_equipment_proximity_sensor_Proximity_encode(&pkt, buffer, !periph.canfdout());

canard_broadcast(ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY_SIGNATURE,
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/rangefinder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ void AP_Periph_FW::can_rangefinder_update(void)
float dist_m = backend->distance();
pkt.range = dist_m;

uint8_t buffer[UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_MAX_SIZE];
uint16_t total_size = uavcan_equipment_range_sensor_Measurement_encode(&pkt, buffer, !periph.canfdout());

canard_broadcast(UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SIGNATURE,
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/rc_in.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ void AP_Periph_FW::can_send_RCInput(uint8_t quality, uint16_t *values, uint8_t n
}

// encode and send message:
uint8_t buffer[DRONECAN_SENSORS_RC_RCINPUT_MAX_SIZE] {};
uint8_t buffer[DRONECAN_SENSORS_RC_RCINPUT_MAX_SIZE];

uint16_t total_size = dronecan_sensors_rc_RCInput_encode(&pkt, buffer, !periph.canfdout());

Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/rpm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ void AP_Periph_FW::rpm_sensor_send(void)
pkt.flags |= DRONECAN_SENSORS_RPM_RPM_FLAGS_UNHEALTHY;
}

uint8_t buffer[DRONECAN_SENSORS_RPM_RPM_MAX_SIZE] {};
uint8_t buffer[DRONECAN_SENSORS_RPM_RPM_MAX_SIZE];
const uint16_t total_size = dronecan_sensors_rpm_RPM_encode(&pkt, buffer, !canfdout());

canard_broadcast(DRONECAN_SENSORS_RPM_RPM_SIGNATURE,
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/serial_tunnel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@ void AP_Periph_FW::send_serial_monitor_data()
pkt.serial_id = uart_monitor.uart_num;
memcpy(pkt.buffer.data, buf, n);

uint8_t buffer[UAVCAN_TUNNEL_TARGETTED_MAX_SIZE] {};
uint8_t buffer[UAVCAN_TUNNEL_TARGETTED_MAX_SIZE];
const uint16_t total_size = uavcan_tunnel_Targetted_encode(&pkt, buffer, !canfdout());

debug("read %u", unsigned(n));
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/temperature.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ void AP_Periph_FW::temperature_sensor_update(void)
// Use source ID from temperature lib
pkt.device_id = temperature_sensor.get_source_id(index);

uint8_t buffer[UAVCAN_EQUIPMENT_DEVICE_TEMPERATURE_MAX_SIZE] {};
uint8_t buffer[UAVCAN_EQUIPMENT_DEVICE_TEMPERATURE_MAX_SIZE];
const uint16_t total_size = uavcan_equipment_device_Temperature_encode(&pkt, buffer, !canfdout());

canard_broadcast(UAVCAN_EQUIPMENT_DEVICE_TEMPERATURE_SIGNATURE,
Expand Down
Loading