mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
AP_Logger: Correct for loop condition
This commit is contained in:
parent
75dec6fcc7
commit
1bfd9f3763
@ -289,7 +289,7 @@ static uint8_t count_commas(const char *string)
|
|||||||
/// return a unit name given its ID
|
/// return a unit name given its ID
|
||||||
const char* AP_Logger::unit_name(const uint8_t unit_id)
|
const char* AP_Logger::unit_name(const uint8_t unit_id)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<unit_id; i++) {
|
for (uint8_t i=0; i<_num_units; i++) {
|
||||||
if (_units[i].ID == unit_id) {
|
if (_units[i].ID == unit_id) {
|
||||||
return _units[i].unit;
|
return _units[i].unit;
|
||||||
}
|
}
|
||||||
@ -300,7 +300,7 @@ const char* AP_Logger::unit_name(const uint8_t unit_id)
|
|||||||
/// return a multiplier value given its ID
|
/// return a multiplier value given its ID
|
||||||
double AP_Logger::multiplier_name(const uint8_t multiplier_id)
|
double AP_Logger::multiplier_name(const uint8_t multiplier_id)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<multiplier_id; i++) {
|
for (uint8_t i=0; i<_num_multipliers; i++) {
|
||||||
if (_multipliers[i].ID == multiplier_id) {
|
if (_multipliers[i].ID == multiplier_id) {
|
||||||
return _multipliers[i].multiplier;
|
return _multipliers[i].multiplier;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user