mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: allow payload place to be compiled out of code
This commit is contained in:
parent
bf59fbc6d9
commit
5a65632a2d
|
@ -1250,9 +1250,11 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
||||||
cmd.content.do_engine_control.allow_disarmed_start = (((uint32_t)packet.param4) & ENGINE_CONTROL_OPTIONS_ALLOW_START_WHILE_DISARMED) != 0;
|
cmd.content.do_engine_control.allow_disarmed_start = (((uint32_t)packet.param4) & ENGINE_CONTROL_OPTIONS_ALLOW_START_WHILE_DISARMED) != 0;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
|
||||||
case MAV_CMD_NAV_PAYLOAD_PLACE:
|
case MAV_CMD_NAV_PAYLOAD_PLACE:
|
||||||
cmd.p1 = packet.param1*100; // copy max-descend parameter (m->cm)
|
cmd.p1 = packet.param1*100; // copy max-descend parameter (m->cm)
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
case MAV_CMD_NAV_SET_YAW_SPEED:
|
case MAV_CMD_NAV_SET_YAW_SPEED:
|
||||||
cmd.content.set_yaw_speed.angle_deg = packet.param1; // target angle in degrees
|
cmd.content.set_yaw_speed.angle_deg = packet.param1; // target angle in degrees
|
||||||
|
@ -1757,9 +1759,11 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
|
||||||
case MAV_CMD_NAV_PAYLOAD_PLACE:
|
case MAV_CMD_NAV_PAYLOAD_PLACE:
|
||||||
packet.param1 = cmd.p1/100.0f; // copy max-descend parameter (cm->m)
|
packet.param1 = cmd.p1/100.0f; // copy max-descend parameter (cm->m)
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
case MAV_CMD_NAV_SET_YAW_SPEED:
|
case MAV_CMD_NAV_SET_YAW_SPEED:
|
||||||
packet.param1 = cmd.content.set_yaw_speed.angle_deg; // target angle in degrees
|
packet.param1 = cmd.content.set_yaw_speed.angle_deg; // target angle in degrees
|
||||||
|
@ -2617,8 +2621,10 @@ const char *AP_Mission::Mission_Command::type() const
|
||||||
case MAV_CMD_DO_GRIPPER:
|
case MAV_CMD_DO_GRIPPER:
|
||||||
return "Gripper";
|
return "Gripper";
|
||||||
#endif
|
#endif
|
||||||
|
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
|
||||||
case MAV_CMD_NAV_PAYLOAD_PLACE:
|
case MAV_CMD_NAV_PAYLOAD_PLACE:
|
||||||
return "PayloadPlace";
|
return "PayloadPlace";
|
||||||
|
#endif
|
||||||
case MAV_CMD_DO_PARACHUTE:
|
case MAV_CMD_DO_PARACHUTE:
|
||||||
return "Parachute";
|
return "Parachute";
|
||||||
case MAV_CMD_DO_SPRAYER:
|
case MAV_CMD_DO_SPRAYER:
|
||||||
|
|
|
@ -3,3 +3,7 @@
|
||||||
#ifndef AP_MISSION_ENABLED
|
#ifndef AP_MISSION_ENABLED
|
||||||
#define AP_MISSION_ENABLED 1
|
#define AP_MISSION_ENABLED 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
|
||||||
|
#define AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED 1
|
||||||
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue