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: Change numeric and hexadecimal number determination to standard methods #25198

Open
wants to merge 6 commits into
base: master
Choose a base branch
from
5 changes: 3 additions & 2 deletions libraries/AP_ADSB/AP_ADSB.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@
#include <GCS_MAVLink/GCS.h>
#include <AP_RTC/AP_RTC.h>

#include <ctype.h>

#define VEHICLE_TIMEOUT_MS 5000 // if no updates in this time, drop it from the list
#define ADSB_SQUAWK_OCTAL_DEFAULT 1200

Expand Down Expand Up @@ -778,8 +780,7 @@ void AP_ADSB::set_callsign(const char* str, const bool append_icao)
break;
}

} else if (('A' <= str[i] && str[i] <= 'Z') ||
('0' <= str[i] && str[i] <= '9')) {
} else if (isupper(str[i]) || isdigit(str[i])) {
// valid as-is
// spaces are also allowed but are handled in the last else
out_state.cfg.callsign[i] = str[i];
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_CANManager/AP_SLCANIface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#if AP_CAN_SLCAN_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>

#include "AP_CANManager.h"

Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_HAL/utility/print_vprintf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include "print_vprintf.h"

#include <cmath>
#include <ctype.h>
#include <stdarg.h>
#include <string.h>

Expand Down Expand Up @@ -126,7 +127,7 @@ void print_vprintf(AP_HAL::BetterStream *s, const char *fmt, va_list ap)
}

if (flags < FL_LONG) {
if (c >= '0' && c <= '9') {
if (isdigit(c)) {
c -= '0';
if (flags & FL_PREC) {
prec = 10*prec + c;
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Math/definitions.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include <cmath>
#include <ctype.h>

#include <AP_HAL/AP_HAL_Boards.h>

Expand Down Expand Up @@ -127,3 +128,5 @@ static const double WGS84_E = (sqrt(2 * WGS84_F - WGS84_F * WGS84_F));

// kg/m^3 to g/cm^3
#define KG_PER_M3_TO_G_PER_CM3(x) (0.001 * x)

#define ishexa(c) (isdigit(c) || ((c) >= 'A' && (c) <= 'F') || ((c) >= 'a' && (c) <= 'f'))
6 changes: 3 additions & 3 deletions libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@

#if AP_RANGEFINDER_LWI2C_ENABLED

#include <ctype.h>

#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/sparse-endian.h>

Expand Down Expand Up @@ -431,9 +433,7 @@ bool AP_RangeFinder_LightWareI2C::sf20_parse_stream(uint8_t *stream_buf,
bool number_found = false;
uint16_t accumulator = 0;
uint16_t digit_u16 = (uint16_t)stream_buf[*p_num_processed_chars];
while ((((digit_u16 <= '9') &&
(digit_u16 >= '0')) ||
(digit_u16 == '.')) &&
while ((isdigit(digit_u16) || (digit_u16 == '.')) &&
(*p_num_processed_chars < lx20_max_reply_len_bytes)) {
(*p_num_processed_chars)++;
if (decrement_multiplier) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Winch/AP_Winch_Daiwa.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ void AP_Winch_Daiwa::read_data_from_winch()
while (nbytes-- > 0) {
int16_t b = uart->read();

if ((b >= '0' && b <= '9') || (b >= 'A' && b <= 'F') || (b >= 'a' && b <= 'f')) {
if (ishexa(b)) {
// add digits to buffer
buff[buff_len] = b;
buff_len++;
Expand Down
Loading