mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Frsky_SPort: correct handling of RPM sensor data
Nails support down to just two RPM sensors for the time being. Simplifies things (there was an issue here when I corrected RPM-in-SITL)
This commit is contained in:
parent
370db00096
commit
4d2cf8c95b
@ -9173,7 +9173,7 @@ switch value'''
|
|||||||
while len(wants):
|
while len(wants):
|
||||||
self.progress("Still wanting (%s)" % ",".join([("0x%02x" % x) for x in wants.keys()]))
|
self.progress("Still wanting (%s)" % ",".join([("0x%02x" % x) for x in wants.keys()]))
|
||||||
wants_copy = copy.copy(wants)
|
wants_copy = copy.copy(wants)
|
||||||
t2 = self.get_sim_time_cached()
|
t2 = self.get_sim_time()
|
||||||
if t2 - tstart > 300:
|
if t2 - tstart > 300:
|
||||||
self.progress("Failed to get frsky passthrough data")
|
self.progress("Failed to get frsky passthrough data")
|
||||||
self.progress("Counts of sensor_id polls sent:")
|
self.progress("Counts of sensor_id polls sent:")
|
||||||
@ -9193,7 +9193,7 @@ switch value'''
|
|||||||
|
|
||||||
def test_frsky_passthrough(self):
|
def test_frsky_passthrough(self):
|
||||||
self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough
|
self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough
|
||||||
self.set_parameter("RPM_TYPE", 1) # enable RPM output
|
self.set_parameter("RPM_TYPE", 10) # enable RPM output
|
||||||
self.customise_SITL_commandline([
|
self.customise_SITL_commandline([
|
||||||
"--uartF=tcp:6735" # serial5 spews to localhost:6735
|
"--uartF=tcp:6735" # serial5 spews to localhost:6735
|
||||||
])
|
])
|
||||||
|
@ -109,7 +109,8 @@ protected:
|
|||||||
static const uint8_t BYTESTUFF_D = 0x5D;
|
static const uint8_t BYTESTUFF_D = 0x5D;
|
||||||
|
|
||||||
// FrSky data IDs;
|
// FrSky data IDs;
|
||||||
static const uint16_t RPM_LAST_ID = 0x050F;
|
static const uint16_t RPM1_ID = 0x050E;
|
||||||
|
static const uint16_t RPM2_ID = 0x050F;
|
||||||
static const uint16_t GPS_LONG_LATI_FIRST_ID = 0x0800;
|
static const uint16_t GPS_LONG_LATI_FIRST_ID = 0x0800;
|
||||||
static const uint16_t DIY_FIRST_ID = 0x5000;
|
static const uint16_t DIY_FIRST_ID = 0x5000;
|
||||||
|
|
||||||
|
@ -126,9 +126,14 @@ void AP_Frsky_SPort::send(void)
|
|||||||
int32_t value;
|
int32_t value;
|
||||||
if (calc_rpm(_SPort.rpm_call, value)) {
|
if (calc_rpm(_SPort.rpm_call, value)) {
|
||||||
// use high numbered frsky sensor ids to leave low numbered free for externally attached physical frsky sensors
|
// use high numbered frsky sensor ids to leave low numbered free for externally attached physical frsky sensors
|
||||||
send_sport_frame(SPORT_DATA_FRAME, 1+RPM_LAST_ID-(rpm->num_sensors()-_SPort.rpm_call), value);
|
uint16_t id = RPM1_ID;
|
||||||
|
if (_SPort.rpm_call != 0) {
|
||||||
|
// only two sensors are currently supported
|
||||||
|
id = RPM2_ID;
|
||||||
|
}
|
||||||
|
send_sport_frame(SPORT_DATA_FRAME, id, value);
|
||||||
}
|
}
|
||||||
if (++_SPort.rpm_call > (rpm->num_sensors()-1)) {
|
if (++_SPort.rpm_call > MIN(rpm->num_sensors()-1, 1)) {
|
||||||
_SPort.rpm_call = 0;
|
_SPort.rpm_call = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user