mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Frsky_Telem: add and use AP_RPM_ENABLED
... and backend-specific equivalents
This commit is contained in:
parent
4fc4e7c532
commit
7eedc88646
@ -148,6 +148,7 @@ void AP_Frsky_Backend::calc_gps_position(void)
|
|||||||
*/
|
*/
|
||||||
bool AP_Frsky_Backend::calc_rpm(const uint8_t instance, int32_t &value) const
|
bool AP_Frsky_Backend::calc_rpm(const uint8_t instance, int32_t &value) const
|
||||||
{
|
{
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
const AP_RPM* rpm = AP::rpm();
|
const AP_RPM* rpm = AP::rpm();
|
||||||
if (rpm == nullptr) {
|
if (rpm == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
@ -159,4 +160,7 @@ bool AP_Frsky_Backend::calc_rpm(const uint8_t instance, int32_t &value) const
|
|||||||
}
|
}
|
||||||
value = static_cast<int32_t>(roundf(rpm_value));
|
value = static_cast<int32_t>(roundf(rpm_value));
|
||||||
return true;
|
return true;
|
||||||
|
#else
|
||||||
|
return false;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -113,6 +113,7 @@ void AP_Frsky_SPort::send(void)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case SENSOR_ID_RPM: // Sensor ID 4
|
case SENSOR_ID_RPM: // Sensor ID 4
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
{
|
{
|
||||||
const AP_RPM* rpm = AP::rpm();
|
const AP_RPM* rpm = AP::rpm();
|
||||||
if (rpm == nullptr) {
|
if (rpm == nullptr) {
|
||||||
@ -132,6 +133,7 @@ void AP_Frsky_SPort::send(void)
|
|||||||
_SPort.rpm_call = 0;
|
_SPort.rpm_call = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // AP_RPM_ENABLED
|
||||||
break;
|
break;
|
||||||
case SENSOR_ID_SP2UR: // Sensor ID 6
|
case SENSOR_ID_SP2UR: // Sensor ID 6
|
||||||
switch (_SPort.various_call) {
|
switch (_SPort.various_call) {
|
||||||
|
@ -222,11 +222,13 @@ bool AP_Frsky_SPort_Passthrough::is_packet_ready(uint8_t idx, bool queue_empty)
|
|||||||
case RPM:
|
case RPM:
|
||||||
{
|
{
|
||||||
packet_ready = false;
|
packet_ready = false;
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
const AP_RPM *rpm = AP::rpm();
|
const AP_RPM *rpm = AP::rpm();
|
||||||
if (rpm == nullptr) {
|
if (rpm == nullptr) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
packet_ready = rpm->num_sensors() > 0;
|
packet_ready = rpm->num_sensors() > 0;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case TERRAIN:
|
case TERRAIN:
|
||||||
@ -697,6 +699,7 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_attiandrng(void)
|
|||||||
*/
|
*/
|
||||||
uint32_t AP_Frsky_SPort_Passthrough::calc_rpm(void)
|
uint32_t AP_Frsky_SPort_Passthrough::calc_rpm(void)
|
||||||
{
|
{
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
const AP_RPM *ap_rpm = AP::rpm();
|
const AP_RPM *ap_rpm = AP::rpm();
|
||||||
if (ap_rpm == nullptr) {
|
if (ap_rpm == nullptr) {
|
||||||
return 0;
|
return 0;
|
||||||
@ -713,6 +716,9 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_rpm(void)
|
|||||||
value |= (int16_t)roundf(rpm * 0.1) << 16;
|
value |= (int16_t)roundf(rpm * 0.1) << 16;
|
||||||
}
|
}
|
||||||
return value;
|
return value;
|
||||||
|
#else
|
||||||
|
return 0;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user