123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312 |
- #include <AP_RSSI/AP_RSSI.h>
- #include <GCS_MAVLink/GCS.h>
- #include <RC_Channel/RC_Channel.h>
- #include <utility>
- extern const AP_HAL::HAL& hal;
- #ifndef BOARD_RSSI_DEFAULT
- #define BOARD_RSSI_DEFAULT 0
- #endif
- #ifndef BOARD_RSSI_ANA_PIN
- #define BOARD_RSSI_ANA_PIN 0
- #endif
- #ifndef BOARD_RSSI_ANA_PIN_HIGH
- #define BOARD_RSSI_ANA_PIN_HIGH 5.0f
- #endif
- const AP_Param::GroupInfo AP_RSSI::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO_FLAGS("TYPE", 0, AP_RSSI, rssi_type, BOARD_RSSI_DEFAULT, AP_PARAM_FLAG_ENABLE),
-
-
-
-
-
- AP_GROUPINFO("ANA_PIN", 1, AP_RSSI, rssi_analog_pin, BOARD_RSSI_ANA_PIN),
-
-
-
-
-
-
-
- AP_GROUPINFO("PIN_LOW", 2, AP_RSSI, rssi_analog_pin_range_low, 0.0f),
-
-
-
-
-
-
-
- AP_GROUPINFO("PIN_HIGH", 3, AP_RSSI, rssi_analog_pin_range_high, BOARD_RSSI_ANA_PIN_HIGH),
-
-
-
-
-
- AP_GROUPINFO("CHANNEL", 4, AP_RSSI, rssi_channel, 0),
-
-
-
-
-
-
- AP_GROUPINFO("CHAN_LOW", 5, AP_RSSI, rssi_channel_low_pwm_value, 1000),
-
-
-
-
-
-
- AP_GROUPINFO("CHAN_HIGH", 6, AP_RSSI, rssi_channel_high_pwm_value, 2000),
- AP_GROUPEND
- };
- AP_RSSI::AP_RSSI()
- {
- AP_Param::setup_object_defaults(this, var_info);
- if (_singleton) {
- AP_HAL::panic("Too many RSSI sensors");
- }
- _singleton = this;
- }
- AP_RSSI::~AP_RSSI(void)
- {
- }
- AP_RSSI *AP_RSSI::get_singleton()
- {
- return _singleton;
- }
- void AP_RSSI::init()
- {
-
-
- rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);
- }
- float AP_RSSI::read_receiver_rssi()
- {
- switch (RssiType(rssi_type.get())) {
- case RssiType::TYPE_DISABLED:
- return 0.0f;
- case RssiType::ANALOG_PIN:
- return read_pin_rssi();
- case RssiType::RC_CHANNEL_VALUE:
- return read_channel_rssi();
- case RssiType::RECEIVER: {
- int16_t rssi = RC_Channels::get_receiver_rssi();
- if (rssi != -1) {
- return rssi / 255.0;
- }
- return 0.0f;
- }
- case RssiType::PWM_PIN:
- return read_pwm_pin_rssi();
- }
-
- return 0.0f;
- }
- uint8_t AP_RSSI::read_receiver_rssi_uint8()
- {
- return read_receiver_rssi() * 255;
- }
- float AP_RSSI::read_pin_rssi()
- {
- rssi_analog_source->set_pin(rssi_analog_pin);
- float current_analog_voltage = rssi_analog_source->voltage_average();
- return scale_and_constrain_float_rssi(current_analog_voltage, rssi_analog_pin_range_low, rssi_analog_pin_range_high);
- }
- float AP_RSSI::read_channel_rssi()
- {
- RC_Channel *c = rc().channel(rssi_channel-1);
- if (c == nullptr) {
- return 0.0f;
- }
- uint16_t rssi_channel_value = c->get_radio_in();
- float channel_rssi = scale_and_constrain_float_rssi(rssi_channel_value, rssi_channel_low_pwm_value, rssi_channel_high_pwm_value);
- return channel_rssi;
- }
- void AP_RSSI::check_pwm_pin_rssi()
- {
- if (rssi_analog_pin == pwm_state.last_rssi_analog_pin) {
- return;
- }
-
- if (pwm_state.last_rssi_analog_pin) {
- if (!hal.gpio->detach_interrupt(pwm_state.last_rssi_analog_pin)) {
- gcs().send_text(MAV_SEVERITY_WARNING,
- "RSSI: Failed to detach from pin %u",
- pwm_state.last_rssi_analog_pin);
-
- }
- }
- pwm_state.last_rssi_analog_pin = rssi_analog_pin;
- if (!rssi_analog_pin) {
-
- return;
- }
-
- hal.gpio->pinMode(rssi_analog_pin, HAL_GPIO_INPUT);
- if (!hal.gpio->attach_interrupt(
- rssi_analog_pin,
- FUNCTOR_BIND_MEMBER(&AP_RSSI::irq_handler,
- void,
- uint8_t,
- bool,
- uint32_t),
- AP_HAL::GPIO::INTERRUPT_BOTH)) {
-
- gcs().send_text(MAV_SEVERITY_WARNING,
- "RSSI: Failed to attach to pin %u",
- (unsigned int)rssi_analog_pin);
- return;
- }
- }
- float AP_RSSI::read_pwm_pin_rssi()
- {
-
- check_pwm_pin_rssi();
- if (!pwm_state.last_rssi_analog_pin) {
-
- return 0.0f;
- }
-
- void *irqstate = hal.scheduler->disable_interrupts_save();
- const uint32_t irq_value_us = pwm_state.irq_value_us;
- pwm_state.irq_value_us = 0;
- hal.scheduler->restore_interrupts(irqstate);
- const uint32_t now = AP_HAL::millis();
- if (irq_value_us == 0) {
-
- if (now - pwm_state.last_reading_ms > 1000) {
-
- pwm_state.rssi_value = 0.0f;
- }
- } else {
-
- pwm_state.rssi_value = scale_and_constrain_float_rssi(irq_value_us, rssi_channel_low_pwm_value, rssi_channel_high_pwm_value);
- pwm_state.last_reading_ms = now;
- }
- return pwm_state.rssi_value;
- }
- float AP_RSSI::scale_and_constrain_float_rssi(float current_rssi_value, float low_rssi_range, float high_rssi_range)
- {
- float rssi_value_range = fabsf(high_rssi_range - low_rssi_range);
- if (is_zero(rssi_value_range)) {
-
- return 0.0f;
- }
-
-
- bool range_is_inverted = (high_rssi_range < low_rssi_range);
-
- current_rssi_value = constrain_float(current_rssi_value,
- range_is_inverted ? high_rssi_range : low_rssi_range,
- range_is_inverted ? low_rssi_range : high_rssi_range);
- if (range_is_inverted)
- {
-
- current_rssi_value = high_rssi_range + fabsf(current_rssi_value - low_rssi_range);
- std::swap(low_rssi_range, high_rssi_range);
- }
-
- float rssi_value_scaled = (current_rssi_value - low_rssi_range) / rssi_value_range;
-
-
- return constrain_float(rssi_value_scaled, 0.0f, 1.0f);
- }
- void AP_RSSI::irq_handler(uint8_t pin, bool pin_high, uint32_t timestamp_us)
- {
- if (pin_high) {
- pwm_state.pulse_start_us = timestamp_us;
- } else {
- if (pwm_state.pulse_start_us != 0) {
- pwm_state.irq_value_us = timestamp_us - pwm_state.pulse_start_us;
- pwm_state.pulse_start_us = 0;
- }
- }
- }
- AP_RSSI *AP_RSSI::_singleton = nullptr;
- namespace AP {
- AP_RSSI *rssi()
- {
- return AP_RSSI::get_singleton();
- }
- };
|