mirror of https://github.com/ArduPilot/ardupilot
Copter: use AP_WINCH_ENABLED in place of WINCH_ENABLED
This commit is contained in:
parent
8ccd0ccd3a
commit
ade654b251
|
@ -11,7 +11,6 @@
|
|||
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
|
||||
//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor
|
||||
//#define BEACON_ENABLED DISABLED // disable beacon support
|
||||
//#define WINCH_ENABLED DISABLED // disable winch support
|
||||
//#define STATS_ENABLED DISABLED // disable statistics support
|
||||
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
|
||||
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
|
||||
|
|
|
@ -536,7 +536,7 @@ bool AP_Arming_Copter::gcs_failsafe_check(bool display_failure)
|
|||
// check winch
|
||||
bool AP_Arming_Copter::winch_checks(bool display_failure) const
|
||||
{
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
// pass if parameter or all arming checks disabled
|
||||
if (!check_enabled(ARMING_CHECK_PARAMETERS)) {
|
||||
return true;
|
||||
|
|
|
@ -230,7 +230,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
#if AP_GRIPPER_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Gripper, &copter.g2.gripper, update, 10, 75, 147),
|
||||
#endif
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Winch, &copter.g2.winch, update, 50, 50, 150),
|
||||
#endif
|
||||
#ifdef USERHOOK_FASTLOOP
|
||||
|
@ -555,7 +555,7 @@ void Copter::ten_hz_logging_loop()
|
|||
#if FRAME_CONFIG == HELI_FRAME
|
||||
Log_Write_Heli();
|
||||
#endif
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
g2.winch.write_log();
|
||||
}
|
||||
|
|
|
@ -147,7 +147,7 @@
|
|||
#if TOY_MODE_ENABLED == ENABLED
|
||||
# include "toy_mode.h"
|
||||
#endif
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
# include <AP_Winch/AP_Winch.h>
|
||||
#endif
|
||||
#include <AP_RPM/AP_RPM.h>
|
||||
|
|
|
@ -314,7 +314,7 @@ void GCS_MAVLINK_Copter::send_pid_tuning()
|
|||
// send winch status message
|
||||
void GCS_MAVLINK_Copter::send_winch_status() const
|
||||
{
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
AP_Winch *winch = AP::winch();
|
||||
if (winch == nullptr) {
|
||||
return;
|
||||
|
@ -914,7 +914,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||
packet.param4,
|
||||
(uint8_t)packet.param5);
|
||||
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
case MAV_CMD_DO_WINCH:
|
||||
// param1 : winch number (ignored)
|
||||
// param2 : action (0=relax, 1=relative length control, 2=rate control). See WINCH_ACTIONS enum.
|
||||
|
|
|
@ -852,7 +852,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
AP_SUBGROUPINFO(smart_rtl, "SRTL_", 21, ParametersG2, AP_SmartRTL),
|
||||
#endif
|
||||
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
// 22 was AP_WheelEncoder
|
||||
|
||||
// @Group: WINCH
|
||||
|
|
|
@ -565,7 +565,7 @@ public:
|
|||
#endif
|
||||
|
||||
// wheel encoder and winch
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
AP_Winch winch;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -433,7 +433,7 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
|
|||
break;
|
||||
|
||||
case AUX_FUNC::WINCH_ENABLE:
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
switch (ch_flag) {
|
||||
case AuxSwitchPos::HIGH:
|
||||
// high switch position stops winch using rate control
|
||||
|
|
|
@ -144,12 +144,6 @@
|
|||
# define PRECISION_LANDING ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// winch support
|
||||
#ifndef WINCH_ENABLED
|
||||
# define WINCH_ENABLED AP_WINCH_ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Parachute release
|
||||
#ifndef PARACHUTE
|
||||
|
|
|
@ -585,7 +585,7 @@ private:
|
|||
#if PARACHUTE == ENABLED
|
||||
void do_parachute(const AP_Mission::Mission_Command& cmd);
|
||||
#endif
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
void do_winch(const AP_Mission::Mission_Command& cmd);
|
||||
#endif
|
||||
void do_payload_place(const AP_Mission::Mission_Command& cmd);
|
||||
|
|
|
@ -725,7 +725,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
case MAV_CMD_DO_WINCH: // Mission command to control winch
|
||||
do_winch(cmd);
|
||||
break;
|
||||
|
@ -1901,7 +1901,7 @@ void ModeAuto::do_mount_control(const AP_Mission::Mission_Command& cmd)
|
|||
#endif
|
||||
}
|
||||
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
// control winch based on mission command
|
||||
void ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
|
|
|
@ -32,7 +32,7 @@ void Copter::init_ardupilot()
|
|||
#endif
|
||||
|
||||
// init winch
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
#if AP_WINCH_ENABLED
|
||||
g2.winch.init();
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue