POSIX: Converted poll to px4_poll

A new poll command was added in accelerometer_calibration.cpp
that needed to be converted to a px4_poll.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois 2015-05-19 12:06:58 -07:00
parent d906fb8f31
commit f44444b7c4
1 changed files with 2 additions and 2 deletions

View File

@ -574,7 +574,7 @@ int do_level_calibration(int mavlink_fd) {
param_set(roll_offset_handler, &zero); param_set(roll_offset_handler, &zero);
param_set(pitch_offset_handler, &zero); param_set(pitch_offset_handler, &zero);
struct pollfd fds[1]; px4_pollfd_struct_t fds[1];
fds[0].fd = att_sub; fds[0].fd = att_sub;
fds[0].events = POLLIN; fds[0].events = POLLIN;
@ -593,7 +593,7 @@ int do_level_calibration(int mavlink_fd) {
start = hrt_absolute_time(); start = hrt_absolute_time();
// average attitude for 5 seconds // average attitude for 5 seconds
while(hrt_elapsed_time(&start) < cal_time * 1000000) { while(hrt_elapsed_time(&start) < cal_time * 1000000) {
poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
roll_mean += att.roll; roll_mean += att.roll;
pitch_mean += att.pitch; pitch_mean += att.pitch;