Browse Source

AP_Mission: support DO_ENGINE_CONTROL

mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
37f71bc6d6
  1. 8
      ArduPlane/commands_logic.cpp
  2. 16
      libraries/AP_Mission/AP_Mission.cpp
  3. 10
      libraries/AP_Mission/AP_Mission.h

8
ArduPlane/commands_logic.cpp

@ -227,9 +227,9 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) @@ -227,9 +227,9 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
break;
case MAV_CMD_DO_ENGINE_CONTROL:
plane.ice_control.engine_control(cmd.content.do_engine_control.start_control,
cmd.content.do_engine_control.cold_start,
cmd.content.do_engine_control.height_delay_cm*0.01f);
plane.g2.ice_control.engine_control(cmd.content.do_engine_control.start_control,
cmd.content.do_engine_control.cold_start,
cmd.content.do_engine_control.height_delay_cm*0.01f);
break;
}
@ -316,6 +316,8 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret @@ -316,6 +316,8 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
case MAV_CMD_DO_LAND_START:
case MAV_CMD_DO_FENCE_ENABLE:
case MAV_CMD_DO_AUTOTUNE_ENABLE:
case MAV_CMD_DO_VTOL_TRANSITION:
case MAV_CMD_DO_ENGINE_CONTROL:
return true;
default:

16
libraries/AP_Mission/AP_Mission.cpp

@ -757,11 +757,17 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ @@ -757,11 +757,17 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
case MAV_CMD_DO_VTOL_TRANSITION:
cmd.content.do_vtol_transition.target_state = packet.param1;
break;
case MAV_CMD_DO_SET_REVERSE:
cmd.p1 = packet.param1; // 0 = forward, 1 = reverse
break;
case MAV_CMD_DO_ENGINE_CONTROL:
cmd.content.do_engine_control.start_control = (packet.param1>0);
cmd.content.do_engine_control.cold_start = (packet.param2>0);
cmd.content.do_engine_control.height_delay_cm = packet.param3*100;
break;
default:
// unrecognised command
return MAV_MISSION_UNSUPPORTED;
@ -1200,7 +1206,13 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c @@ -1200,7 +1206,13 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
case MAV_CMD_DO_VTOL_TRANSITION:
packet.param1 = cmd.content.do_vtol_transition.target_state;
break;
case MAV_CMD_DO_ENGINE_CONTROL:
packet.param1 = cmd.content.do_engine_control.start_control?1:0;
packet.param2 = cmd.content.do_engine_control.cold_start?1:0;
packet.param3 = cmd.content.do_engine_control.height_delay_cm*0.01f;
break;
default:
// unrecognised command
return false;

10
libraries/AP_Mission/AP_Mission.h

@ -169,6 +169,13 @@ public: @@ -169,6 +169,13 @@ public:
int8_t sec_utc; // absolute time's sec (utc)
};
// DO_ENGINE_CONTROL support
struct PACKED Do_Engine_Control {
bool start_control; // start or stop engine
bool cold_start; // use cold start procedure
uint16_t height_delay_cm; // height delay for start
};
union PACKED Content {
// jump structure
Jump_Command jump;
@ -220,6 +227,9 @@ public: @@ -220,6 +227,9 @@ public:
// do vtol transition
Do_VTOL_Transition do_vtol_transition;
// DO_ENGINE_CONTROL
Do_Engine_Control do_engine_control;
// location
Location location; // Waypoint location

Loading…
Cancel
Save