Browse Source

Changes for updated DriverFramework

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
sbg
Mark Charlebois 9 years ago
parent
commit
34410e7ce4
  1. 6
      src/drivers/device/vdev.cpp
  2. 2
      src/lib/DriverFramework
  3. 10
      src/modules/commander/state_machine_helper.cpp
  4. 4
      src/platforms/posix/drivers/barosim/baro.cpp
  5. 1
      src/platforms/posix/drivers/rgbledsim/rgbled.cpp

6
src/drivers/device/vdev.cpp

@ -550,16 +550,16 @@ void VDev::showDevices() @@ -550,16 +550,16 @@ void VDev::showDevices()
pthread_mutex_unlock(&devmutex);
PX4_INFO("DF Devices:");
std::string dev_path, instance_path;
const char *dev_path;
unsigned int index = 0;
i = 0;
do {
// Each look increments index and returns -1 if end reached
i = DevMgr::getNextDevicePath(index, dev_path, instance_path);
i = DevMgr::getNextDeviceName(index, &dev_path);
if (i == 0) {
PX4_INFO(" %s (%s)", dev_path.c_str(), instance_path.c_str());
PX4_INFO(" %s", dev_path);
}
} while (i == 0);
}

2
src/lib/DriverFramework

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit 10bc08d31fe0cddb997b3349f34a7ea38c5c7b9d
Subproject commit e137690747130776b24ace01099d3ba2329cd36a

10
src/modules/commander/state_machine_helper.cpp

@ -496,25 +496,25 @@ transition_result_t hil_state_transition(hil_state_t new_state, orb_advert_t sta @@ -496,25 +496,25 @@ transition_result_t hil_state_transition(hil_state_t new_state, orb_advert_t sta
// Handle DF devices
std::string df_dev_path, df_dev_instance_path;
const char *df_dev_path;
unsigned int index = 0;
for(;;) {
if (DevMgr::getNextDevicePath(index, df_dev_path, df_dev_instance_path) < 0) {
if (DevMgr::getNextDeviceName(index, &df_dev_path) < 0) {
break;
}
DevHandle h;
DevMgr::getHandle(df_dev_path.c_str(), h);
DevMgr::getHandle(df_dev_path, h);
if (!h.isValid()) {
warn("failed opening device %s", df_dev_path.c_str());
warn("failed opening device %s", df_dev_path);
continue;
}
int block_ret = h.ioctl(DEVIOCSPUBBLOCK, 1);
DevMgr::releaseHandle(h);
printf("Disabling %s: %s\n", df_dev_path.c_str(), (block_ret == OK) ? "OK" : "ERROR");
printf("Disabling %s: %s\n", df_dev_path, (block_ret == OK) ? "OK" : "ERROR");
}
ret = TRANSITION_CHANGED;

4
src/platforms/posix/drivers/barosim/baro.cpp

@ -920,7 +920,7 @@ test() @@ -920,7 +920,7 @@ test()
/* read the sensor 5x and report each value */
for (unsigned i = 0; i < 5; i++) {
UpdateList in_set, out_set;
in_set.push_back(&h);
in_set.pushBack(&h);
/* wait for data to be ready */
ret = DevMgr::waitForUpdate(in_set, out_set, 1000);
@ -1029,7 +1029,7 @@ calibrate(unsigned altitude) @@ -1029,7 +1029,7 @@ calibrate(unsigned altitude)
int ret;
ssize_t sz;
UpdateList in_set, out_set;
in_set.push_back(&h);
in_set.pushBack(&h);
/* wait for data to be ready */
ret = DevMgr::waitForUpdate(in_set, out_set, 1000);

1
src/platforms/posix/drivers/rgbledsim/rgbled.cpp

@ -52,6 +52,7 @@ @@ -52,6 +52,7 @@
#include <unistd.h>
#include <stdio.h>
#include <ctype.h>
#include <errno.h>
#include <px4_workqueue.h>

Loading…
Cancel
Save