mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: support DO_ENGINE_CONTROL
This commit is contained in:
parent
327a057ee0
commit
37f71bc6d6
|
@ -227,9 +227,9 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_ENGINE_CONTROL:
|
case MAV_CMD_DO_ENGINE_CONTROL:
|
||||||
plane.ice_control.engine_control(cmd.content.do_engine_control.start_control,
|
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.cold_start,
|
||||||
cmd.content.do_engine_control.height_delay_cm*0.01f);
|
cmd.content.do_engine_control.height_delay_cm*0.01f);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -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_LAND_START:
|
||||||
case MAV_CMD_DO_FENCE_ENABLE:
|
case MAV_CMD_DO_FENCE_ENABLE:
|
||||||
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
||||||
|
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||||
|
case MAV_CMD_DO_ENGINE_CONTROL:
|
||||||
return true;
|
return true;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
|
|
|
@ -757,11 +757,17 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
||||||
case MAV_CMD_DO_VTOL_TRANSITION:
|
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||||
cmd.content.do_vtol_transition.target_state = packet.param1;
|
cmd.content.do_vtol_transition.target_state = packet.param1;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_SET_REVERSE:
|
case MAV_CMD_DO_SET_REVERSE:
|
||||||
cmd.p1 = packet.param1; // 0 = forward, 1 = reverse
|
cmd.p1 = packet.param1; // 0 = forward, 1 = reverse
|
||||||
break;
|
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:
|
default:
|
||||||
// unrecognised command
|
// unrecognised command
|
||||||
return MAV_MISSION_UNSUPPORTED;
|
return MAV_MISSION_UNSUPPORTED;
|
||||||
|
@ -1200,7 +1206,13 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
|
||||||
case MAV_CMD_DO_VTOL_TRANSITION:
|
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||||
packet.param1 = cmd.content.do_vtol_transition.target_state;
|
packet.param1 = cmd.content.do_vtol_transition.target_state;
|
||||||
break;
|
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:
|
default:
|
||||||
// unrecognised command
|
// unrecognised command
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -169,6 +169,13 @@ public:
|
||||||
int8_t sec_utc; // absolute time's sec (utc)
|
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 {
|
union PACKED Content {
|
||||||
// jump structure
|
// jump structure
|
||||||
Jump_Command jump;
|
Jump_Command jump;
|
||||||
|
@ -220,6 +227,9 @@ public:
|
||||||
|
|
||||||
// do vtol transition
|
// do vtol transition
|
||||||
Do_VTOL_Transition do_vtol_transition;
|
Do_VTOL_Transition do_vtol_transition;
|
||||||
|
|
||||||
|
// DO_ENGINE_CONTROL
|
||||||
|
Do_Engine_Control do_engine_control;
|
||||||
|
|
||||||
// location
|
// location
|
||||||
Location location; // Waypoint location
|
Location location; // Waypoint location
|
||||||
|
|
Loading…
Reference in New Issue