From ce5fbc7751d2fb98fe2b69e517c3d7b2cf1afbc3 Mon Sep 17 00:00:00 2001 From: Daniel Agar <daniel@agar.ca> Date: Sun, 20 Jan 2019 16:16:54 -0500 Subject: [PATCH] mavlink simple analyzer remove <limits> usage - <limits> isn't available in the NuttX c++ standard library --- src/modules/mavlink/mavlink_high_latency2.cpp | 13 +++---- .../mavlink/mavlink_simple_analyzer.cpp | 26 ++++++++++++++ src/modules/mavlink/mavlink_simple_analyzer.h | 34 +++++++++---------- 3 files changed, 46 insertions(+), 27 deletions(-) diff --git a/src/modules/mavlink/mavlink_high_latency2.cpp b/src/modules/mavlink/mavlink_high_latency2.cpp index a60cc9e22f..7b9074f1dc 100644 --- a/src/modules/mavlink/mavlink_high_latency2.cpp +++ b/src/modules/mavlink/mavlink_high_latency2.cpp @@ -138,9 +138,7 @@ bool MavlinkStreamHighLatency2::send(const hrt_abstime t) updated |= write_wind_estimate(&msg); if (updated) { - uint32_t timestamp; - convert_limit_safe(t / 1000, timestamp); - msg.timestamp = timestamp; + msg.timestamp = t / 1000; msg.type = _mavlink->get_system_type(); msg.autopilot = MAV_AUTOPILOT_PX4; @@ -317,13 +315,10 @@ bool MavlinkStreamHighLatency2::write_global_position(mavlink_high_latency2_t *m const bool updated = _global_pos_sub->update(&_global_pos_time, &global_pos); if (_global_pos_time > 0) { - int32_t latitude, longitude; - convert_limit_safe(global_pos.lat * 1e7, latitude); - convert_limit_safe(global_pos.lon * 1e7, longitude); - msg->latitude = latitude; - msg->longitude = longitude; + msg->latitude = global_pos.lat * 1e7; + msg->longitude = global_pos.lon * 1e7; - int16_t altitude; + int16_t altitude = 0; if (global_pos.alt > 0) { convert_limit_safe(global_pos.alt + 0.5f, altitude); diff --git a/src/modules/mavlink/mavlink_simple_analyzer.cpp b/src/modules/mavlink/mavlink_simple_analyzer.cpp index 670af116fe..b49fce369c 100644 --- a/src/modules/mavlink/mavlink_simple_analyzer.cpp +++ b/src/modules/mavlink/mavlink_simple_analyzer.cpp @@ -146,3 +146,29 @@ void SimpleAnalyzer::int_round(float &x) const x += 0.5f; } } + +void convert_limit_safe(float in, uint16_t &out) +{ + if (in > UINT16_MAX) { + out = UINT16_MAX; + + } else if (in < 0) { + out = 0; + + } else { + out = static_cast<uint16_t>(in); + } +} + +void convert_limit_safe(float in, int16_t &out) +{ + if (in > INT16_MAX) { + out = INT16_MAX; + + } else if (in < INT16_MIN) { + out = INT16_MIN; + + } else { + out = static_cast<int16_t>(in); + } +} diff --git a/src/modules/mavlink/mavlink_simple_analyzer.h b/src/modules/mavlink/mavlink_simple_analyzer.h index 57d43436d1..d02423fae0 100644 --- a/src/modules/mavlink/mavlink_simple_analyzer.h +++ b/src/modules/mavlink/mavlink_simple_analyzer.h @@ -39,7 +39,8 @@ #pragma once -#include <limits> +#include <float.h> +#include <stdint.h> /** * SimpleAnalyzer @@ -115,14 +116,22 @@ public: * @param[out] ret: The scaled and rounded value of the current analyzer result. * @parma[in] scalingfactor: The factor which is used to scale the result. */ - template <typename T> - void get_scaled(T &ret, float scalingfactor) const + void get_scaled(uint8_t &ret, float scalingfactor) const { float avg = get_scaled(scalingfactor); int_round(avg); - check_limits(avg, std::numeric_limits<T>::min(), std::numeric_limits<T>::max()); + check_limits(avg, 0, UINT8_MAX); - ret = static_cast<T>(avg); + ret = static_cast<uint8_t>(avg); + } + + void get_scaled(int8_t &ret, float scalingfactor) const + { + float avg = get_scaled(scalingfactor); + int_round(avg); + check_limits(avg, INT8_MIN, INT8_MAX); + + ret = static_cast<int8_t>(avg); } private: @@ -135,16 +144,5 @@ private: void int_round(float &x) const; }; -template<typename Tin, typename Tout> -void convert_limit_safe(Tin in, Tout &out) -{ - if (in > std::numeric_limits<Tout>::max()) { - out = std::numeric_limits<Tout>::max(); - - } else if (in < std::numeric_limits<Tout>::min()) { - out = std::numeric_limits<Tout>::min(); - - } else { - out = static_cast<Tout>(in); - } -} +void convert_limit_safe(float in, uint16_t &out); +void convert_limit_safe(float in, int16_t &out); -- GitLab