forked from Archive/PX4-Autopilot
sdp3x_airspeed posix port
This commit is contained in:
parent
9cd25d604b
commit
641a90708c
|
@ -20,6 +20,7 @@ set(config_module_list
|
|||
drivers/airspeed
|
||||
drivers/ms4525_airspeed
|
||||
drivers/ms5525_airspeed
|
||||
drivers/sdp3x_airspeed
|
||||
|
||||
modules/sensors
|
||||
platforms/posix/drivers/df_mpu9250_wrapper
|
||||
|
|
|
@ -13,6 +13,7 @@ set(config_module_list
|
|||
drivers/airspeed
|
||||
drivers/ms4525_airspeed
|
||||
drivers/ms5525_airspeed
|
||||
drivers/sdp3x_airspeed
|
||||
|
||||
modules/sensors
|
||||
platforms/posix/drivers/accelsim
|
||||
|
|
|
@ -107,7 +107,6 @@ private:
|
|||
*/
|
||||
int write_command(uint16_t command);
|
||||
|
||||
bool _inited{false};
|
||||
uint16_t _scale{0};
|
||||
};
|
||||
|
||||
|
|
|
@ -88,17 +88,17 @@ start(int i2c_bus)
|
|||
}
|
||||
|
||||
/* set the poll rate to default, starts automatic data collection */
|
||||
fd = open(PATH_SDP3X, O_RDONLY);
|
||||
fd = px4_open(PATH_SDP3X, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
|
||||
if (px4_ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
exit(0);
|
||||
return;
|
||||
|
||||
fail:
|
||||
|
||||
|
@ -108,7 +108,6 @@ fail:
|
|||
}
|
||||
|
||||
PX4_WARN("no SDP3X airspeed sensor connected");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
// stop the driver
|
||||
|
@ -119,10 +118,8 @@ void stop()
|
|||
g_dev = nullptr;
|
||||
|
||||
} else {
|
||||
errx(1, "driver not running");
|
||||
PX4_ERR("driver not running");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
// perform some basic functional tests on the driver;
|
||||
|
@ -130,49 +127,49 @@ void stop()
|
|||
// and automatic modes.
|
||||
void test()
|
||||
{
|
||||
int fd = open(PATH_SDP3X, O_RDONLY);
|
||||
int fd = px4_open(PATH_SDP3X, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
PX4_WARN("%s open failed (try 'sdp3x_airspeed start' if the driver is not running", PATH_SDP3X);
|
||||
exit(1);
|
||||
return;
|
||||
}
|
||||
|
||||
// do a simple demand read
|
||||
differential_pressure_s report;
|
||||
ssize_t sz = read(fd, &report, sizeof(report));
|
||||
ssize_t sz = px4_read(fd, &report, sizeof(report));
|
||||
|
||||
if (sz != sizeof(report)) {
|
||||
PX4_WARN("immediate read failed");
|
||||
exit(1);
|
||||
return;
|
||||
}
|
||||
|
||||
PX4_WARN("single read");
|
||||
PX4_WARN("diff pressure: %d pa", (int)report.differential_pressure_filtered_pa);
|
||||
|
||||
/* start the sensor polling at 2Hz */
|
||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
|
||||
if (OK != px4_ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
|
||||
PX4_WARN("failed to set 2Hz poll rate");
|
||||
exit(1);
|
||||
return;
|
||||
}
|
||||
|
||||
/* read the sensor 5x and report each value */
|
||||
for (unsigned i = 0; i < 5; i++) {
|
||||
struct pollfd fds;
|
||||
px4_pollfd_struct_t fds;
|
||||
|
||||
/* wait for data to be ready */
|
||||
fds.fd = fd;
|
||||
fds.events = POLLIN;
|
||||
int ret = poll(&fds, 1, 2000);
|
||||
int ret = px4_poll(&fds, 1, 2000);
|
||||
|
||||
if (ret != 1) {
|
||||
errx(1, "timed out");
|
||||
PX4_ERR("timed out");
|
||||
}
|
||||
|
||||
/* now go get it */
|
||||
sz = read(fd, &report, sizeof(report));
|
||||
sz = px4_read(fd, &report, sizeof(report));
|
||||
|
||||
if (sz != sizeof(report)) {
|
||||
err(1, "periodic read failed");
|
||||
PX4_ERR("periodic read failed");
|
||||
}
|
||||
|
||||
PX4_WARN("periodic read %u", i);
|
||||
|
@ -181,32 +178,31 @@ void test()
|
|||
}
|
||||
|
||||
/* reset the sensor polling to its default rate */
|
||||
if (PX4_OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
|
||||
if (PX4_OK != px4_ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
|
||||
PX4_WARN("failed to set default rate");
|
||||
exit(1);
|
||||
return;
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
// reset the driver
|
||||
void reset()
|
||||
{
|
||||
int fd = open(PATH_SDP3X, O_RDONLY);
|
||||
int fd = px4_open(PATH_SDP3X, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
err(1, "failed ");
|
||||
PX4_ERR("failed ");
|
||||
return;
|
||||
}
|
||||
|
||||
if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
|
||||
err(1, "driver reset failed");
|
||||
if (px4_ioctl(fd, SENSORIOCRESET, 0) < 0) {
|
||||
PX4_ERR("driver reset failed");
|
||||
return;
|
||||
}
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
|
||||
err(1, "driver poll restart failed");
|
||||
if (px4_ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
|
||||
PX4_ERR("driver poll restart failed");
|
||||
return;
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
// print a little info about the driver
|
||||
|
@ -214,13 +210,11 @@ void
|
|||
info()
|
||||
{
|
||||
if (g_dev == nullptr) {
|
||||
errx(1, "driver not running");
|
||||
PX4_ERR("driver not running");
|
||||
}
|
||||
|
||||
printf("state @ %p\n", g_dev);
|
||||
PX4_INFO("state @ %p", g_dev);
|
||||
g_dev->print_info();
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
} // namespace sdp3x_airspeed
|
||||
|
@ -285,5 +279,6 @@ sdp3x_airspeed_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
sdp3x_airspeed_usage();
|
||||
exit(0);
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue