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

Set Flight Mode using new interface set_flight_mode in DeviceImpl #206

Merged
merged 4 commits into from
Jan 15, 2018

Conversation

Rjasuja
Copy link
Contributor

@Rjasuja Rjasuja commented Dec 22, 2017

Modifies plugins to use set_flight_mode instead of using MAV_CMD_DO_SET_MODE
Issue : #193

@@ -443,6 +444,40 @@ void DeviceImpl::get_param_float_async(const std::string &name,
callback));
}

MavlinkCommands::Result DeviceImpl::set_flight_mode(uint8_t custom_sub_mode, uint8_t custom_mode)
Copy link
Contributor

@shakthi-prashanth-m shakthi-prashanth-m Dec 29, 2017

Choose a reason for hiding this comment

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

Lets have DeviceImpl::FlightMode similar to Telemetry::FlightMode. Telemetry flight mode methods shall uses the services of those in DeviceImpl. We should have simple signature of set_flight_mode as below:

MavlinkCommands::Result DeviceImpl::set_flight_mode(DeviceImpl::FlightMode flight_mode);

I believe we can deduce custom_sub_mode and custom_mode from DeviceImpl::FlightMode.

@@ -443,6 +444,40 @@ void DeviceImpl::get_param_float_async(const std::string &name,
callback));
}

MavlinkCommands::Result DeviceImpl::set_flight_mode(uint8_t custom_sub_mode, uint8_t custom_mode)
{
uint8_t flag_safety_armed = DeviceImpl::is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
Copy link
Contributor

Choose a reason for hiding this comment

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

is_armed() doesn't require explicit qualification, as it's a non-static method of DeviceImpl.

Copy link
Contributor

@shakthi-prashanth-m shakthi-prashanth-m left a comment

Choose a reason for hiding this comment

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

@Rjasuja as mentioned in review comments, we can simplify set_flight_mode signature. Also add get_flight_mode method too. These will also result changes in Telemetry plug-in as well.
Thanks.

class DeviceImpl
{
public:
enum FLIGHT_MODE {
Copy link
Contributor

@shakthi-prashanth-m shakthi-prashanth-m Jan 3, 2018

Choose a reason for hiding this comment

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

it should be

enum FlightMode {
    HOLD = 0,
    TAKEOFF,
    LAND,
    RETURN_TO_LAUNCH,
    MISSION,
    OFFBOARD,
    FOLLOW_ME,
}

Copy link
Collaborator

Choose a reason for hiding this comment

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

And I'll add: it should be:

enum class FlightMode {
    ...
}

@@ -110,6 +119,8 @@ class DeviceImpl
DeviceImpl(const DeviceImpl &) = delete;
const DeviceImpl &operator=(const DeviceImpl &) = delete;


Copy link
Contributor

@shakthi-prashanth-m shakthi-prashanth-m Jan 3, 2018

Choose a reason for hiding this comment

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

Please remove extra lines.

ret = action_result_from_command_result(
_parent->set_flight_mode(custom_sub_mode, custom_mode));
_parent->set_flight_mode(DeviceImpl::HOLD));
Copy link
Contributor

Choose a reason for hiding this comment

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

Flight modes are accessed as DeviceImpl::FlightMode::HOLD, etc.


return action_result_from_command_result(_parent->set_flight_mode(
custom_sub_mode,
custom_mode));
DeviceImpl::RETURN_TO_LAUNCH));
Copy link
Contributor

Choose a reason for hiding this comment

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

Flight modes are accessed as DeviceImpl::FlightMode::RETURN_TO_LAUNCH, etc.

_parent->set_flight_mode_async(
custom_sub_mode, custom_mode,
DeviceImpl::HOLD,
Copy link
Contributor

Choose a reason for hiding this comment

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

We can rename HOLD flight mode to FlightMode::LOITER to be consistent with method name; or vice-versa.

Copy link
Collaborator

Choose a reason for hiding this comment

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

The public name of the mode in PX4 is "Hold". The names from DroneCore should match what PX4 uses, which tends to also match what QGC uses in selection lists.


_activity = Activity::SEND_COMMAND;

_parent->set_flight_mode_async(
custom_sub_mode, custom_mode,
DeviceImpl::MISSION,
Copy link
Contributor

Choose a reason for hiding this comment

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

DeviceImpl::MISSION -> DeviceImpl::FlightMode::MISSION

uint8_t custom_sub_mode = 0;

switch (device_mode) {
case HOLD: custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
Copy link
Contributor

Choose a reason for hiding this comment

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

Please add custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER; next line for uniformity with other case values.

Copy link
Collaborator

Choose a reason for hiding this comment

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

Names like loiter I believe may be used by the internal state machine, but are not the public facing names.

Copy link
Contributor

Choose a reason for hiding this comment

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

OK..

break;
case OFFBOARD : custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
break;
default : return ;
Copy link
Contributor

Choose a reason for hiding this comment

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

We need to handle for unsupported mode, like it is handled here.

@@ -117,14 +117,9 @@ FollowMe::Result FollowMeImpl::start()
{
// Note: the safety flag is not needed in future versions of the PX4 Firmware
Copy link
Contributor

Choose a reason for hiding this comment

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

These comments do not make sense now :) It will be in set_flight_mode().

@@ -149,13 +144,9 @@ FollowMe::Result FollowMeImpl::stop()
}
// Note: the safety flag is not needed in future versions of the PX4 Firmware
Copy link
Contributor

Choose a reason for hiding this comment

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

I think you can remove this comment everywhere it appeared other than in set_flight_mode().

Copy link
Contributor

@shakthi-prashanth-m shakthi-prashanth-m left a comment

Choose a reason for hiding this comment

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

Its simplified now except for some minor changes that I requested.
Thanks

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.

This is going to be handy, thanks for the changes.

class DeviceImpl
{
public:
enum FLIGHT_MODE {
Copy link
Collaborator

Choose a reason for hiding this comment

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

And I'll add: it should be:

enum class FlightMode {
    ...
}

@@ -443,6 +444,86 @@ void DeviceImpl::get_param_float_async(const std::string &name,
callback));
}

MavlinkCommands::Result DeviceImpl::set_flight_mode(FLIGHT_MODE device_mode)
Copy link
Collaborator

Choose a reason for hiding this comment

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

I'm not sure if MavlinkCommands::Result is the correct result for a flight mode change. I vote that this has its own return type, and then map the CommandResult to a SetFlightMode result.

Copy link
Contributor

Choose a reason for hiding this comment

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

@julianoes As flight mode change is merely a MAVLink command operation, its result remains same; except for checking unsupported mode. Plugins should only use supported modes; but we are handling anyway for unsupported mode before sending command further. I think it should be fine. What do you think ?

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 vote to just return MavlinkCommand::ERROR for the case of an unsupported mode, and add a `LogErr() << "Unsupported mode".

The reason is that any plugin using any kind of command, now needs to catch the command error UNSUPPORTED_MODE even for commands that have nothing to do with mode, and that is not intuitive.

@julianoes
Copy link
Collaborator

@Rjasuja can you try to rebase on top of develop?

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.

Sorry, one more small thing.

case FlightMode::OFFBOARD:
custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
break;
default :
Copy link
Collaborator

Choose a reason for hiding this comment

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

In this case it would be helpful to add a LogErr() << "Unknown Flight mode chosen.";

@julianoes
Copy link
Collaborator

@Rjasuja thanks, I only have one minor comment, then please do a rebase. You can do this as follows (assuming origin is dronecore/DroneCore):

git checkout upstream3
git fetch origin
git rebase origin/develop
git push --force

@Rjasuja
Copy link
Contributor Author

Rjasuja commented Jan 12, 2018

Updated and Rebased

@julianoes
Copy link
Collaborator

Thanks @Rjasuja!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants