Skip to content

Commit 3229cae

Browse files
committed
Copter: Add a unit to the update time variable
1 parent a730781 commit 3229cae

File tree

1 file changed

+8
-8
lines changed

1 file changed

+8
-8
lines changed

ArduCopter/compassmot.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,8 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
2020
float throttle_pct_max = 0.0f; // maximum throttle reached (as a percentage 0~1.0)
2121
float current_amps_max = 0.0f; // maximum current reached
2222
float interference_pct[COMPASS_MAX_INSTANCES]{}; // interference as a percentage of total mag field (for reporting purposes only)
23-
uint32_t last_run_time;
24-
uint32_t last_send_time;
23+
uint32_t last_run_time_ms;
24+
uint32_t last_send_time_ms;
2525
bool updated = false; // have we updated the compensation vector at least once
2626
uint8_t command_ack_start = command_ack_counter;
2727

@@ -128,19 +128,19 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
128128
hal.util->set_soft_armed(true);
129129

130130
// initialise run time
131-
last_run_time = millis();
132-
last_send_time = millis();
131+
last_run_time_ms = millis();
132+
last_send_time_ms = millis();
133133

134134
// main run while there is no user input and the compass is healthy
135135
while (command_ack_start == command_ack_counter && compass.healthy() && motors->armed()) {
136136
EXPECT_DELAY_MS(5000);
137137

138138
// 50hz loop
139-
if (millis() - last_run_time < 20) {
139+
if (millis() - last_run_time_ms < 20) {
140140
hal.scheduler->delay(5);
141141
continue;
142142
}
143-
last_run_time = millis();
143+
last_run_time_ms = millis();
144144

145145
// read radio input
146146
read_radio();
@@ -217,8 +217,8 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
217217
}
218218
}
219219

220-
if (AP_HAL::millis() - last_send_time > 500) {
221-
last_send_time = AP_HAL::millis();
220+
if (AP_HAL::millis() - last_send_time_ms > 500) {
221+
last_send_time_ms = AP_HAL::millis();
222222
mavlink_msg_compassmot_status_send(gcs_chan.get_chan(),
223223
channel_throttle->get_control_in(),
224224
current,

0 commit comments

Comments
 (0)