Skip to content

Commit

Permalink
backend: add battery to telemetry
Browse files Browse the repository at this point in the history
  • Loading branch information
JonasVautherin committed Apr 26, 2018
1 parent 553c476 commit 95aa71d
Show file tree
Hide file tree
Showing 5 changed files with 141 additions and 1 deletion.
18 changes: 18 additions & 0 deletions backend/src/plugins/telemetry/telemetry_service_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,24 @@ class TelemetryServiceImpl final : public dronecore::rpc::telemetry::TelemetrySe
}
}

grpc::Status SubscribeBattery(grpc::ServerContext * /* context */,
const dronecore::rpc::telemetry::SubscribeBatteryRequest * /* request */,
grpc::ServerWriter<rpc::telemetry::BatteryResponse> *writer) override
{
_telemetry.battery_async([this, &writer](dronecore::Telemetry::Battery battery) {
auto rpc_battery = new dronecore::rpc::telemetry::Battery();
rpc_battery->set_voltage_v(battery.voltage_v);
rpc_battery->set_remaining_percent(battery.remaining_percent);

dronecore::rpc::telemetry::BatteryResponse rpc_battery_response;
rpc_battery_response.set_allocated_battery(rpc_battery);
writer->Write(rpc_battery_response);
});

_stop_future.wait();
return grpc::Status::OK;
}

void stop()
{
_stop_promise.set_value();
Expand Down
108 changes: 107 additions & 1 deletion backend/test/telemetry_service_impl_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@ using Health = dronecore::Telemetry::Health;
using GPSInfo = dronecore::Telemetry::GPSInfo;
using FixType = dronecore::rpc::telemetry::FixType;

using Battery = dronecore::Telemetry::Battery;

class TelemetryServiceImplTest : public ::testing::Test
{
protected:
Expand Down Expand Up @@ -77,6 +79,10 @@ class TelemetryServiceImplTest : public ::testing::Test
std::future<void> subscribeGPSInfoAsync(std::vector<GPSInfo> &gps_info_events) const;
int translateRPCGPSFixType(const FixType rpc_fix_type) const;

void checkSendsBatteryEvents(const std::vector<Battery> &battery_events) const;
Battery createBattery(const float voltage_v, const float remaining_percent) const;
std::future<void> subscribeBatteryAsync(std::vector<Battery> &battery_events) const;

std::unique_ptr<grpc::Server> _server;
std::unique_ptr<TelemetryService::Stub> _stub;
std::unique_ptr<MockTelemetry> _telemetry;
Expand Down Expand Up @@ -537,7 +543,7 @@ TEST_F(TelemetryServiceImplTest, sendsOneArmedEvent)
std::vector<bool> armed_events;
armed_events.push_back(generateRandomBool());

checkSendsInAirEvents(armed_events);
checkSendsArmedEvents(armed_events);
}

void TelemetryServiceImplTest::checkSendsArmedEvents(const std::vector<bool> &armed_events) const
Expand Down Expand Up @@ -697,4 +703,104 @@ TEST_F(TelemetryServiceImplTest, sendsMultipleGPSInfoEvents)
checkSendsGPSInfoEvents(gps_info_events);
}

TEST_F(TelemetryServiceImplTest, registersToTelemetryBatteryAsync)
{
EXPECT_CALL(*_telemetry, battery_async(_))
.Times(1);

std::vector<Battery> battery_events;
auto battery_stream_future = subscribeBatteryAsync(battery_events);

_telemetry_service->stop();
battery_stream_future.wait();
}

std::future<void>
TelemetryServiceImplTest::subscribeBatteryAsync(std::vector<Battery> &battery_events) const
{
return std::async(std::launch::async, [&]() {
grpc::ClientContext context;
dronecore::rpc::telemetry::SubscribeBatteryRequest request;
auto response_reader = _stub->SubscribeBattery(&context, request);

dronecore::rpc::telemetry::BatteryResponse response;
while (response_reader->Read(&response)) {
auto battery_rpc = response.battery();

Battery battery;
battery.voltage_v = battery_rpc.voltage_v();
battery.remaining_percent = battery_rpc.remaining_percent();

battery_events.push_back(battery);
}

response_reader->Finish();
});
}

TEST_F(TelemetryServiceImplTest, doesNotSendBatteryIfCallbackNotCalled)
{
std::vector<Battery> battery_events;
auto battery_stream_future = subscribeBatteryAsync(battery_events);

_telemetry_service->stop();
battery_stream_future.wait();

EXPECT_EQ(0, battery_events.size());
}

TEST_F(TelemetryServiceImplTest, sendsOneBatteryEvent)
{
std::vector<Battery> battery_events;
battery_events.push_back(createBattery(4.2f, 0.63f));

checkSendsBatteryEvents(battery_events);
}

Battery TelemetryServiceImplTest::createBattery(const float voltage_v,
const float remaining_percent) const
{
Battery battery;
battery.voltage_v = voltage_v;
battery.remaining_percent = remaining_percent;

return battery;
}

void TelemetryServiceImplTest::checkSendsBatteryEvents(const std::vector<Battery> &battery_events)
const
{
std::promise<void> subscription_promise;
auto subscription_future = subscription_promise.get_future();
dronecore::Telemetry::battery_callback_t battery_callback;
EXPECT_CALL(*_telemetry, battery_async(_))
.WillOnce(SaveCallback(&battery_callback, &subscription_promise));

std::vector<Battery> received_battery_events;
auto battery_stream_future = subscribeBatteryAsync(received_battery_events);
subscription_future.wait();
for (const auto battery : battery_events) {
battery_callback(battery);
}
_telemetry_service->stop();
battery_stream_future.wait();

ASSERT_EQ(battery_events.size(), received_battery_events.size());
for (size_t i = 0; i < battery_events.size(); i++) {
EXPECT_EQ(battery_events.at(i), received_battery_events.at(i));
}
}

TEST_F(TelemetryServiceImplTest, sendsMultipleBatteryEvents)
{
std::vector<Battery> battery_events;

battery_events.push_back(createBattery(4.1f, 0.34f));
battery_events.push_back(createBattery(5.1f, 0.12f));
battery_events.push_back(createBattery(2.4f, 0.99f));
battery_events.push_back(createBattery(5.7f, 1.0f));

checkSendsBatteryEvents(battery_events);
}

} // namespace
1 change: 1 addition & 0 deletions plugins/telemetry/mocks/telemetry_mock.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ class MockTelemetry
MOCK_CONST_METHOD1(in_air_async, void(Telemetry::in_air_callback_t));
MOCK_CONST_METHOD1(armed_async, void(Telemetry::armed_callback_t));
MOCK_CONST_METHOD1(gps_info_async, void(Telemetry::gps_info_callback_t));
MOCK_CONST_METHOD1(battery_async, void(Telemetry::battery_callback_t));
};

} // namespace testing
Expand Down
12 changes: 12 additions & 0 deletions plugins/telemetry/telemetry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -350,4 +350,16 @@ std::ostream &operator<<(std::ostream &str, Telemetry::GPSInfo const &gps_info)
<< ", fix_type: " << gps_info.fix_type << "]";
}

bool operator==(const Telemetry::Battery &lhs, const Telemetry::Battery &rhs)
{
return lhs.voltage_v == rhs.voltage_v
&& lhs.remaining_percent == rhs.remaining_percent;
}

std::ostream &operator<<(std::ostream &str, Telemetry::Battery const &battery)
{
return str << "[voltage_v: " << battery.voltage_v
<< ", remaining_percent: " << battery.remaining_percent << "]";
}

} // namespace dronecore
3 changes: 3 additions & 0 deletions plugins/telemetry/telemetry.h
Original file line number Diff line number Diff line change
Expand Up @@ -646,4 +646,7 @@ std::ostream &operator<<(std::ostream &str, Telemetry::Health const &health);
bool operator==(const Telemetry::GPSInfo &lhs, const Telemetry::GPSInfo &rhs);
std::ostream &operator<<(std::ostream &str, Telemetry::GPSInfo const &gps_info);

bool operator==(const Telemetry::Battery &lhs, const Telemetry::Battery &rhs);
std::ostream &operator<<(std::ostream &str, Telemetry::Battery const &battery);

} // namespace dronecore

0 comments on commit 95aa71d

Please sign in to comment.