Skip to content

Commit

Permalink
Commander: avoid automatic type deduction where neither the type is o…
Browse files Browse the repository at this point in the history
…bvious nor it helps with readability
  • Loading branch information
MaEtUgR committed Nov 12, 2024
1 parent 96f1f8c commit ff10f9c
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 10 deletions.
9 changes: 5 additions & 4 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1970,7 +1970,7 @@ void Commander::checkForMissionUpdate()
if (_mission_result_sub.updated()) {
const mission_result_s &mission_result = _mission_result_sub.get();

const auto prev_mission_mission_id = mission_result.mission_id;
const uint32_t prev_mission_mission_id = mission_result.mission_id;
_mission_result_sub.update();

// if mission_result is valid for the current mission
Expand Down Expand Up @@ -2155,9 +2155,10 @@ void Commander::vtolStatusUpdate()
if (_vtol_vehicle_status_sub.update(&_vtol_vehicle_status) && is_vtol(_vehicle_status)) {

// Check if there has been any change while updating the flags (transition = rotary wing status)
const auto new_vehicle_type = _vtol_vehicle_status.vehicle_vtol_state == vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW ?
vehicle_status_s::VEHICLE_TYPE_FIXED_WING :
vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;
const uint8_t new_vehicle_type =
_vtol_vehicle_status.vehicle_vtol_state == vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW ?
vehicle_status_s::VEHICLE_TYPE_FIXED_WING :
vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;

if (new_vehicle_type != _vehicle_status.vehicle_type) {
_vehicle_status.vehicle_type = new_vehicle_type;
Expand Down
8 changes: 4 additions & 4 deletions src/modules/commander/HomePosition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ void HomePosition::fillGlobalHomePos(home_position_s &home, double lat, double l

void HomePosition::setInAirHomePosition()
{
auto &home = _home_position_pub.get();
home_position_s &home = _home_position_pub.get();

if (home.manual_home || (home.valid_lpos && home.valid_hpos && home.valid_alt)) {
return;
Expand Down Expand Up @@ -251,13 +251,13 @@ void HomePosition::setInAirHomePosition()

bool HomePosition::setManually(double lat, double lon, float alt, float yaw)
{
const auto &vehicle_local_position = _local_position_sub.get();
const vehicle_local_position_s &vehicle_local_position = _local_position_sub.get();

if (!vehicle_local_position.xy_global || !vehicle_local_position.z_global) {
return false;
}

auto &home = _home_position_pub.get();
home_position_s &home = _home_position_pub.get();
home.manual_home = true;

home.lat = lat;
Expand Down Expand Up @@ -328,7 +328,7 @@ void HomePosition::update(bool set_automatically, bool check_if_changed)
}

const vehicle_local_position_s &lpos = _local_position_sub.get();
const auto &home = _home_position_pub.get();
const home_position_s &home = _home_position_pub.get();

if (lpos.heading_reset_counter != _heading_reset_counter) {
if (_valid && set_automatically) {
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/gyro_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,7 +253,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)

for (unsigned uorb_index = 0; uorb_index < MAX_GYROS; uorb_index++) {

auto &calibration = worker_data.calibrations[uorb_index];
calibration::Gyroscope &calibration = worker_data.calibrations[uorb_index];

if (calibration.device_id() != 0) {
calibration.set_offset(worker_data.offset[uorb_index]);
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/mag_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -905,7 +905,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma

for (unsigned cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) {

auto &current_cal = worker_data.calibration[cur_mag];
calibration::Magnetometer &current_cal = worker_data.calibration[cur_mag];

if (current_cal.device_id() != 0) {
if (worker_data.append_to_existing_calibration) {
Expand Down

0 comments on commit ff10f9c

Please sign in to comment.