intel / mavlink-vehicles

A Mavlink wrapper dedicated to the most common messages that are exchanged between an air vehicle and a ground station
Apache License 2.0
6 stars 9 forks source link

Fix mapping of MAV_STATE #13

Closed guiccbr closed 8 years ago

guiccbr commented 8 years ago

closes #12

Previously, mavlink_vehicles was mapping the more specific mavlink MAV_STATE enum to a more generic STATUS enum as follows:

MAV_STATE_UNINIT -> mavlink_vehicles::status::STANDBY MAV_STATE_BOOT -> mavlink_vehicles::status::STANDBY MAV_STATE_CALIBRATING -> mavlink_vehicles::status::STANDBY MAV_STATE_ACTIVE -> mavlink_vehicles::status::ACTIVE MAV_STATE_CRITICAL -> mavlink_vehicles::status::STANDBY MAV_STATE_EMERGENCY -> mavlink_vehicles::status::STANDBY MAV_STATE_POWEROFF -> mavlink_vehicles::status::STANDBY

This simplification has been placed taking in consideration only a specific use case: determine whether the vehicle is already flying (ACTIVE) or not (STANDBY). While testing It has been noted that the states STATE_CRITICAL and STATE_EMERGENCY might also be set during flight, and so, those should also be mapped to mavlink_vehicles::status::ACTIVE.

This is what this patch does:

MAV_STATE_UNINIT -> mavlink_vehicles::status::STANDBY MAV_STATE_BOOT -> mavlink_vehicles::status::STANDBY MAV_STATE_CALIBRATING -> mavlink_vehicles::status::STANDBY MAV_STATE_ACTIVE -> mavlink_vehicles::status::ACTIVE MAV_STATE_CRITICAL -> mavlink_vehicles::status::ACTIVE MAV_STATE_EMERGENCY -> mavlink_vehicles::status::ACTIVE MAV_STATE_POWEROFF -> mavlink_vehicles::status::STANDBY

Signed-off-by: Guilherme Campos Camargo guilherme.campos.camargo@intel.com

rchiossi commented 8 years ago

Can Emergency and Critical be set while the vehicle is not flying? If so, won't this generate any problem? If not, LGTM.

guiccbr commented 8 years ago

I have noticed that those states might be set in some specific cases when the vehicle is not flying: for example when the default gcs (255), for some reason, connects to the ardupilot bu then, for some reason, stops sending heartbeats.

In our use-case this will not happen since the FS_GCS_ENABLE parameter is set to 0 in the SITL EEPROM, however I agree that we must take a closer look into it to properly solve this problem.

I will merge this PR now, since it is critical to have our use-case working properly, however I'll leave an Issue open explaining the problem.