Skip to content

Commit

Permalink
Merge pull request #1152 from mavlink/pr-fix-1.11
Browse files Browse the repository at this point in the history
docker: use PX4 master for now
  • Loading branch information
julianoes authored Jul 28, 2020
2 parents dc529f8 + 0bf4fc5 commit a1e8314
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 20 deletions.
2 changes: 1 addition & 1 deletion docker/Dockerfile-Ubuntu-20.04-PX4-SITL-v1.11
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ ENV LANGUAGE en_US:en
ENV LC_ALL en_US.UTF-8

RUN git clone https://github.com/PX4/Firmware.git ${FIRMWARE_DIR}
RUN git -C ${FIRMWARE_DIR} checkout v1.11.0-rc1
RUN git -C ${FIRMWARE_DIR} checkout master # later: v1.11.0
RUN git -C ${FIRMWARE_DIR} submodule update --init --recursive
RUN cd ${FIRMWARE_DIR} && Tools/setup/ubuntu.sh --no-nuttx
RUN cd ${FIRMWARE_DIR} && DONT_RUN=1 make px4_sitl gazebo && DONT_RUN=1 make px4_sitl gazebo
25 changes: 6 additions & 19 deletions src/integration_tests/mavlink_passthrough.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include <atomic>
#include <iostream>
#include <future>
#include "log.h"
Expand Down Expand Up @@ -47,33 +48,19 @@ TEST_F(SitlTest, MavlinkPassthrough)
}

{
std::promise<void> prom;
std::future<void> fut = prom.get_future();
unsigned counter = 0;
bool stopped = false;
std::atomic<unsigned> counter{0};

mavlink_passthrough->subscribe_message_async(
MAVLINK_MSG_ID_HIGHRES_IMU,
[&prom, &counter, &stopped, mavlink_passthrough](const mavlink_message_t& message) {
MAVLINK_MSG_ID_HIGHRES_IMU, [&counter](const mavlink_message_t& message) {
mavlink_highres_imu_t highres_imu;
mavlink_msg_highres_imu_decode(&message, &highres_imu);

LogInfo() << "HIGHRES_IMU.temperature [1] (" << counter << ")"
<< highres_imu.temperature << " degrees C";
if (++counter == 100) {
EXPECT_FALSE(stopped);
if (!stopped) {
stopped = true;
// Unsubscribe again
mavlink_passthrough->subscribe_message_async(
MAVLINK_MSG_ID_HIGHRES_IMU, nullptr);
prom.set_value();
}
};
++counter;
});

// At 50 Hz we should have received 100 temperature measurements in 2 seconds.
// After 3 seconds we give up.
EXPECT_EQ(fut.wait_for(std::chrono::seconds(3)), std::future_status::ready);
std::this_thread::sleep_for(std::chrono::seconds(3));
EXPECT_GT(counter, 100);
}
}

0 comments on commit a1e8314

Please sign in to comment.