Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add support for COMMAND_INT and abstraction for the same including COMMAND_LONG #351

Merged
merged 5 commits into from
Apr 9, 2018

Conversation

shakthi-prashanth-m
Copy link
Contributor

Adds new types MAVLinkCommands::CmdInt and MAVLinkCommands::CmdLong types that abstract to those of MAVLink protocol:

Also includes the changes in core and plugins, wherever these commands are used. COMMAND_INT is used only in Gimbal plugin as of now for MAV_CMD_DO_SET_ROI_LOCATION.

Adds new types `MAVLinkCommands::CmdInt` and `MAVLinkCommands::CmdLong`
types that abstract to those of MAVLink protocol:
http://mavlink.org/messages/common/#COMMAND_INT
http://mavlink.org/messages/common/#COMMAND_LONG

Also includes the changes in core and plugins, wherever these
commands are used. `COMMAND_INT` is used only in Gimbal plugin as of
now for `MAV_CMD_DO_SET_ROI_LOCATION`.
@shakthi-prashanth-m shakthi-prashanth-m self-assigned this Apr 6, 2018
@shakthi-prashanth-m shakthi-prashanth-m changed the title core, plugins: Add support for COMMAND_INT #326 Add support for COMMAND_INT and abstraction for the same including COMMAND_LONG Apr 6, 2018
float param4 = NAN;
int32_t lat_deg = 0;
int32_t lon_deg = 0;
float alt_m = NAN;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This would be called param7 I'd say.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I just realized, we better name last 3 members as x, y and z., x could be in meters also in case of Local position. So, _deg would mislead. Right ?

x int32_t PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
y int32_t PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
z float PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, makes sense then

cmd.params.param1 = float(mode);
cmd.params.param2 = float(custom_mode);
cmd.params.param3 = float(custom_sub_mode);
cmd.target_component_id = get_autopilot_id();
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think that's actually nicer!

@@ -30,20 +31,65 @@ class MAVLinkCommands

typedef std::function<void(Result, float)> command_result_callback_t;

struct Params {
float v[7];
struct CmdInt {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would call it CommandInt because we use command everywhere, and not cmd, right?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Right. I'll change.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

cmd in argument should be fine, I think. Right ?

MAVLinkCommands::Result
MAVLinkSystem::send_command(MAVLinkCommands::CommandInt &cmd)
{...}

@@ -6,6 +6,7 @@
#include <string>
#include <functional>
#include <mutex>
#include <memory>
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What's this include for? Shouldn't it be in mavlink_commands.cpp?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah, forgot to remove. I wanted to use unique_ptr but realized its an overkill. :)

command_result_callback_t callback,
uint8_t component_id = 0);
// FIXME: I tried to use templates for these;
// but I get undefined reference. Need to dig it later.
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think like this is fine. I'd even tend to:

send_command_int(...);
send_command_long(...);

Copy link
Contributor Author

@shakthi-prashanth-m shakthi-prashanth-m Apr 6, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK. I am encouraging compile-time polymorphism :-)

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok sure.

MAVLinkCommands::CmdLong cmd {};

cmd.command = MAV_CMD_NAV_LAND;
cmd.target_component_id = _parent->get_autopilot_id();
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Note that the behavior here could potentially change because we switch from having all params as NAN to 0.f. I would vote to set all reserved as NAN.

Copy link
Contributor Author

@shakthi-prashanth-m shakthi-prashanth-m Apr 6, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would vote to set all reserved as NAN.

OK.
So what should they be initialized by default ?

Shakthi Prashanth M added 3 commits April 6, 2018 18:39
MAVLinkCommands:CmdInt -> MAVLinkCommands::CommandInt
MAVLinkCommands:CmdLong -> MAVLinkCommands::CommandLong
In MAVLink spec for `COMMAND_INT` last 3 params are named as x, y and z.
Units of these would vary from meteres (Local pos) to degrees (Global pos).
Hence renamed as x, y and z.
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.
Correct param name "reserved_value" in set_as_reserved().
Copy link
Collaborator

@julianoes julianoes left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks good to me now.

@julianoes julianoes merged commit 849c3ec into develop Apr 9, 2018
@julianoes julianoes deleted the 326-add-support-for-COMMAND_INT branch April 9, 2018 07:59
rt-2pm2 pushed a commit to rt-2pm2/DronecodeSDK that referenced this pull request Nov 27, 2018
…MAND_INT

Add support for COMMAND_INT and abstraction for the same including `COMMAND_LONG`
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants