forked from Archive/PX4-Autopilot
Merge branch 'px4io-i2c-memory-squeeze' of https://github.com/PX4/Firmware into px4io-i2c-memory-squeeze
This commit is contained in:
commit
8c7c6b201c
|
@ -96,6 +96,8 @@ public:
|
|||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
virtual ssize_t write(file *filp, const char *buffer, size_t len);
|
||||
|
||||
void print_status();
|
||||
|
||||
private:
|
||||
// XXX
|
||||
unsigned _max_actuators;
|
||||
|
@ -459,7 +461,7 @@ PX4IO::init()
|
|||
PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK |
|
||||
PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK, 0);
|
||||
|
||||
/* publish RC config to IO */
|
||||
/* publish RC config to IO */
|
||||
ret = io_set_rc_config();
|
||||
if (ret != OK) {
|
||||
log("failed to update RC input config");
|
||||
|
@ -1141,18 +1143,28 @@ PX4IO::mixer_send(const char *buf, unsigned buflen)
|
|||
|
||||
} while (buflen > 0);
|
||||
|
||||
debug("mixer upload OK");
|
||||
|
||||
/* check for the mixer-OK flag */
|
||||
if (io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS) & PX4IO_P_STATUS_FLAGS_MIXER_OK)
|
||||
if (io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS) & PX4IO_P_STATUS_FLAGS_MIXER_OK) {
|
||||
debug("mixer upload OK");
|
||||
return 0;
|
||||
|
||||
debug("mixer rejected by IO");
|
||||
} else {
|
||||
debug("mixer rejected by IO");
|
||||
}
|
||||
|
||||
/* load must have failed for some reason */
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
void
|
||||
PX4IO::print_status()
|
||||
{
|
||||
printf("\tRC status:\t%s\n", (_status & PX4IO_P_STATUS_FLAGS_RC_OK) ? "OK" : "LOST");
|
||||
if (_status & PX4IO_P_STATUS_FLAGS_RC_OK) {
|
||||
printf("\tRC type:\t%s\n", (_status & PX4IO_P_STATUS_FLAGS_RC_SBUS) ? "S.BUS" : ((_status & PX4IO_P_STATUS_FLAGS_RC_DSM) ? "DSM" : "PPM"));
|
||||
// printf("\tRC chans:\t%d\n", xxx);
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
|
@ -1294,7 +1306,7 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
|
|||
}
|
||||
|
||||
default:
|
||||
/* not a recognised value */
|
||||
/* not a recognized value */
|
||||
ret = -ENOTTY;
|
||||
}
|
||||
|
||||
|
@ -1458,10 +1470,12 @@ px4io_main(int argc, char *argv[])
|
|||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
|
||||
if (g_dev != nullptr)
|
||||
if (g_dev != nullptr) {
|
||||
printf("[px4io] loaded\n");
|
||||
else
|
||||
g_dev->print_status();
|
||||
} else {
|
||||
printf("[px4io] not loaded\n");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
|
|
@ -247,8 +247,8 @@ void KalmanNav::update()
|
|||
// output
|
||||
if (newTimeStamp - _outTimeStamp > 10e6) { // 0.1 Hz
|
||||
_outTimeStamp = newTimeStamp;
|
||||
printf("nav: %4d Hz, miss #: %4d\n",
|
||||
_navFrames / 10, _miss / 10);
|
||||
//printf("nav: %4d Hz, miss #: %4d\n",
|
||||
// _navFrames / 10, _miss / 10);
|
||||
_navFrames = 0;
|
||||
_miss = 0;
|
||||
}
|
||||
|
|
|
@ -1074,36 +1074,6 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
|
|||
void
|
||||
Sensors::ppm_poll()
|
||||
{
|
||||
/* fake low-level driver, directly pulling from driver variables */
|
||||
static orb_advert_t rc_input_pub = -1;
|
||||
struct rc_input_values raw;
|
||||
|
||||
raw.timestamp = ppm_last_valid_decode;
|
||||
/* we are accepting this message */
|
||||
_ppm_last_valid = ppm_last_valid_decode;
|
||||
|
||||
/*
|
||||
* relying on two decoded channels is very noise-prone,
|
||||
* in particular if nothing is connected to the pins.
|
||||
* requiring a minimum of four channels
|
||||
*/
|
||||
if (ppm_decoded_channels > 4 && hrt_absolute_time() - _ppm_last_valid < PPM_INPUT_TIMEOUT_INTERVAL) {
|
||||
|
||||
for (unsigned i = 0; i < ppm_decoded_channels; i++) {
|
||||
raw.values[i] = ppm_buffer[i];
|
||||
}
|
||||
|
||||
raw.channel_count = ppm_decoded_channels;
|
||||
|
||||
/* publish to object request broker */
|
||||
if (rc_input_pub <= 0) {
|
||||
rc_input_pub = orb_advertise(ORB_ID(input_rc), &raw);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(input_rc), rc_input_pub, &raw);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
|
||||
bool rc_updated;
|
||||
|
|
Loading…
Reference in New Issue