Skip to content

Commit

Permalink
Add "reserved_val" as argument to set_as_reserved()
Browse files Browse the repository at this point in the history
Most of the "Reserved" values in MAVLink spec are NAN. However, in
some cases "Reserved" value could be "0". This utility method supplied
can be used to set any value to mark as "Reserved". For.eg: For commands
`MAV_CMD_LOGGING_START`, `MAV_CMD_LOGGING_STOP` etc, "Reserved" value is 0.
  • Loading branch information
Shakthi Prashanth M committed Apr 6, 2018
1 parent c67db7a commit 7538d52
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 18 deletions.
31 changes: 17 additions & 14 deletions core/mavlink_commands.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ class MAVLinkCommands
uint16_t command;
bool current = 0;
bool autocontinue = false;
// Most of the "Reserved" values in MAVLink spec are NAN.
struct Params {
float param1 = NAN;
float param2 = NAN;
Expand All @@ -48,15 +49,17 @@ class MAVLinkCommands
float z = NAN;
} params;

static void set_as_reserved(Params &params)
// In some cases "Reserved" value could be "0".
// This utility method can be used in such case.
static void set_as_reserved(Params &params, float reserve_val = NAN)
{
params.param1 = 0.f;
params.param2 = 0.f;
params.param3 = 0.f;
params.param4 = 0.f;
params.param1 = reserve_val;
params.param2 = reserve_val;
params.param3 = reserve_val;
params.param4 = reserve_val;
params.x = 0;
params.y = 0;
params.z = 0.f;
params.z = reserve_val;
}
};

Expand All @@ -75,15 +78,15 @@ class MAVLinkCommands
float param7 = NAN;
} params;

static void set_as_reserved(Params &params)
static void set_as_reserved(Params &params, float reserve_val = NAN)
{
params.param1 = 0.f;
params.param2 = 0.f;
params.param3 = 0.f;
params.param4 = 0.f;
params.param5 = 0.f;
params.param6 = 0.f;
params.param7 = 0.f;
params.param1 = reserve_val;
params.param2 = reserve_val;
params.param3 = reserve_val;
params.param4 = reserve_val;
params.param5 = reserve_val;
params.param6 = reserve_val;
params.param7 = reserve_val;
}
};

Expand Down
8 changes: 4 additions & 4 deletions plugins/logging/logging_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ Logging::Result LoggingImpl::start_logging() const
MAVLinkCommands::CommandLong cmd {};

cmd.command = MAV_CMD_LOGGING_START;
MAVLinkCommands::CommandLong::set_as_reserved(cmd.params);
MAVLinkCommands::CommandLong::set_as_reserved(cmd.params, 0.f);
cmd.target_component_id = _parent->get_autopilot_id();

return logging_result_from_command_result(_parent->send_command(cmd));
Expand All @@ -54,7 +54,7 @@ Logging::Result LoggingImpl::stop_logging() const
MAVLinkCommands::CommandLong cmd {};

cmd.command = MAV_CMD_LOGGING_STOP;
MAVLinkCommands::CommandLong::set_as_reserved(cmd.params);
MAVLinkCommands::CommandLong::set_as_reserved(cmd.params, 0.f);
cmd.target_component_id = _parent->get_autopilot_id();

return logging_result_from_command_result(_parent->send_command(cmd));
Expand All @@ -65,7 +65,7 @@ void LoggingImpl::start_logging_async(const Logging::result_callback_t &callback
MAVLinkCommands::CommandLong cmd {};

cmd.command = MAV_CMD_LOGGING_START;
MAVLinkCommands::CommandLong::set_as_reserved(cmd.params);
MAVLinkCommands::CommandLong::set_as_reserved(cmd.params, 0.f);
cmd.target_component_id = _parent->get_autopilot_id();

_parent->send_command_async(cmd, std::bind(&LoggingImpl::command_result_callback,
Expand All @@ -78,7 +78,7 @@ void LoggingImpl::stop_logging_async(const Logging::result_callback_t &callback)
MAVLinkCommands::CommandLong cmd {};

cmd.command = MAV_CMD_LOGGING_STOP;
MAVLinkCommands::CommandLong::set_as_reserved(cmd.params);
MAVLinkCommands::CommandLong::set_as_reserved(cmd.params, 0.f);
cmd.target_component_id = _parent->get_autopilot_id();

_parent->send_command_async(cmd, std::bind(&LoggingImpl::command_result_callback,
Expand Down

0 comments on commit 7538d52

Please sign in to comment.