ArduCopter: allow payload place to be compiled out of code

This commit is contained in:
Peter Barker 2023-10-19 13:34:30 +11:00 committed by Peter Barker
parent 5a65632a2d
commit 6b439bb2f3
4 changed files with 28 additions and 0 deletions

View File

@ -638,3 +638,7 @@
#ifndef AC_CUSTOMCONTROL_MULTI_ENABLED
#define AC_CUSTOMCONTROL_MULTI_ENABLED FRAME_CONFIG == MULTICOPTER_FRAME && AP_CUSTOMCONTROL_ENABLED
#endif
#ifndef AC_PAYLOAD_PLACE_ENABLED
#define AC_PAYLOAD_PLACE_ENABLED 1
#endif

View File

@ -25,7 +25,9 @@ Mode::Mode(void) :
G_Dt(copter.G_Dt)
{ };
#if AC_PAYLOAD_PLACE_ENABLED
PayloadPlace Mode::payload_place;
#endif
// return the static controller object corresponding to supplied mode
Mode *Copter::mode_from_mode_num(const Mode::Number mode)

View File

@ -29,6 +29,7 @@ private:
Vector3p complete_pos; // target takeoff position as offset from ekf origin in cm
};
#if AC_PAYLOAD_PLACE_ENABLED
class PayloadPlace {
public:
void run();
@ -59,6 +60,7 @@ private:
float descent_start_altitude_cm;
float descent_speed_cms;
};
#endif
class Mode {
friend class PayloadPlace;
@ -199,8 +201,10 @@ protected:
land_run_vertical_control(pause_descent);
}
#if AC_PAYLOAD_PLACE_ENABLED
// payload place flight behaviour:
static PayloadPlace payload_place;
#endif
// run normal or precision landing (if enabled)
// pause_descent is true if vehicle should not descend
@ -497,7 +501,9 @@ public:
NAVGUIDED,
LOITER,
LOITER_TO_ALT,
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
NAV_PAYLOAD_PLACE,
#endif
NAV_SCRIPT_TIME,
NAV_ATTITUDE_TIME,
};

View File

@ -149,9 +149,11 @@ void ModeAuto::run()
loiter_to_alt_run();
break;
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
case SubMode::NAV_PAYLOAD_PLACE:
payload_place.run();
break;
#endif
case SubMode::NAV_ATTITUDE_TIME:
nav_attitude_time_run();
@ -539,6 +541,7 @@ bool ModeAuto::is_taking_off() const
return ((_mode == SubMode::TAKEOFF) && !auto_takeoff.complete);
}
#if AC_PAYLOAD_PLACE_ENABLED
// auto_payload_place_start - initialises controller to implement a placing
void PayloadPlace::start_descent()
{
@ -568,6 +571,7 @@ void PayloadPlace::start_descent()
state = PayloadPlace::State::Descent_Start;
}
#endif
// returns true if pilot's yaw input should be used to adjust vehicle's heading
bool ModeAuto::use_pilot_yaw(void) const
@ -657,9 +661,11 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
do_nav_delay(cmd);
break;
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
case MAV_CMD_NAV_PAYLOAD_PLACE: // 94 place at Waypoint
do_payload_place(cmd);
break;
#endif
#if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME:
@ -865,9 +871,11 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
cmd_complete = verify_land();
break;
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
case MAV_CMD_NAV_PAYLOAD_PLACE:
cmd_complete = payload_place.verify();
break;
#endif
case MAV_CMD_NAV_LOITER_UNLIM:
cmd_complete = verify_loiter_unlimited();
@ -1158,6 +1166,7 @@ void ModeAuto::nav_attitude_time_run()
pos_control->update_z_controller();
}
#if AC_PAYLOAD_PLACE_ENABLED
// auto_payload_place_run - places an object in auto mode
// called by auto_run at 100hz or more
void PayloadPlace::run()
@ -1384,6 +1393,7 @@ void PayloadPlace::run()
break;
}
}
#endif
// sets the target_loc's alt to the vehicle's current alt but does not change target_loc's frame
// in the case of terrain altitudes either the terrain database or the rangefinder may be used
@ -1506,11 +1516,13 @@ bool ModeAuto::set_next_wp(const AP_Mission::Mission_Command& current_cmd, const
case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_NAV_LOITER_UNLIM:
case MAV_CMD_NAV_LOITER_TIME:
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
case MAV_CMD_NAV_PAYLOAD_PLACE: {
const Location dest_loc = loc_from_cmd(current_cmd, default_loc);
const Location next_dest_loc = loc_from_cmd(next_cmd, dest_loc);
return wp_nav->set_wp_destination_next_loc(next_dest_loc);
}
#endif
case MAV_CMD_NAV_SPLINE_WAYPOINT: {
// get spline's location and next location from command and send to wp_nav
Location next_dest_loc, next_next_dest_loc;
@ -1911,6 +1923,7 @@ void ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd)
}
#endif
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
// do_payload_place - initiate placing procedure
void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd)
{
@ -1942,6 +1955,7 @@ void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd)
// set submode
set_submode(SubMode::NAV_PAYLOAD_PLACE);
}
#endif // AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
// do_RTL - start Return-to-Launch
void ModeAuto::do_RTL(void)
@ -2011,6 +2025,7 @@ bool ModeAuto::verify_land()
return retval;
}
#if AC_PAYLOAD_PLACE_ENABLED
// verify_payload_place - returns true if placing has been completed
bool PayloadPlace::verify()
{
@ -2030,6 +2045,7 @@ bool PayloadPlace::verify()
// should never get here
return true;
}
#endif
bool ModeAuto::verify_loiter_unlimited()
{