mavlink: address review comments

This commit is contained in:
Julian Oes 2020-05-29 11:53:31 +02:00
parent 7d1b451e39
commit efb10a2fbc
3 changed files with 11 additions and 8 deletions

View File

@ -517,7 +517,7 @@ uint8_t MavlinkReceiver::handle_request_message_command(uint16_t message_id, flo
{
bool stream_found = false;
for (const auto stream : _mavlink->get_streams()) {
for (const auto &stream : _mavlink->get_streams()) {
if (stream->get_id() == message_id) {
stream_found = stream->request_message(param2, param3, param4, param5, param6, param7);
break;
@ -532,7 +532,7 @@ uint8_t MavlinkReceiver::handle_request_message_command(uint16_t message_id, flo
_mavlink->configure_stream_threadsafe(stream_name, 0.0f);
// Now we try again to send it.
for (const auto stream : _mavlink->get_streams()) {
for (const auto &stream : _mavlink->get_streams()) {
if (stream->get_id() == message_id) {
stream_found = stream->request_message(param2, param3, param4, param5, param6, param7);
break;

View File

@ -71,13 +71,17 @@ public:
}
private:
uORB::Subscription _armed_sub{ORB_ID(actuator_armed)};
param_t _param_com_flight_uuid;
/* do not allow top copying this class */
MavlinkStreamFlightInformation(MavlinkStreamFlightInformation &) = delete;
MavlinkStreamFlightInformation &operator = (const MavlinkStreamFlightInformation &) = delete;
protected:
explicit MavlinkStreamFlightInformation(Mavlink *mavlink) : MavlinkStream(mavlink)
{}
{
_param_com_flight_uuid = param_find("COM_FLIGHT_UUID");
}
bool send(const hrt_abstime t) override
{
@ -85,9 +89,8 @@ protected:
bool ret = _armed_sub.copy(&actuator_armed);
if (ret && actuator_armed.timestamp != 0) {
const param_t param_com_flight_uuid = param_find("COM_FLIGHT_UUID");
int32_t flight_uuid;
param_get(param_com_flight_uuid, &flight_uuid);
param_get(_param_com_flight_uuid, &flight_uuid);
mavlink_flight_information_t flight_info{};
flight_info.flight_uuid = static_cast<uint64_t>(flight_uuid);

View File

@ -80,11 +80,11 @@ public:
bool request_message(float param2, float param3, float param4,
float param5, float param6, float param7) override
{
storage_id = (int)roundf(param2);
_storage_id = (int)roundf(param2);
return send(hrt_absolute_time());
}
private:
int storage_id = 0;
int _storage_id = 0;
/* do not allow top copying this class */
MavlinkStreamStorageInformation(MavlinkStreamStorageInformation &) = delete;
@ -100,7 +100,7 @@ protected:
mavlink_storage_information_t storage_info{};
const char *microsd_dir = PX4_STORAGEDIR;
if (storage_id == 0 || storage_id == 1) { // request is for all or the first storage
if (_storage_id == 0 || _storage_id == 1) { // request is for all or the first storage
storage_info.storage_id = 1;
struct statfs statfs_buf;