mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Winch: add and use AP_WINCH_ENABLED
This commit is contained in:
parent
f47e60d1ea
commit
8ccd0ccd3a
@ -1,4 +1,7 @@
|
|||||||
#include "AP_Winch.h"
|
#include "AP_Winch.h"
|
||||||
|
|
||||||
|
#if AP_WINCH_ENABLED
|
||||||
|
|
||||||
#include "AP_Winch_PWM.h"
|
#include "AP_Winch_PWM.h"
|
||||||
#include "AP_Winch_Daiwa.h"
|
#include "AP_Winch_Daiwa.h"
|
||||||
|
|
||||||
@ -157,3 +160,5 @@ AP_Winch *winch()
|
|||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_WINCH_ENABLED
|
||||||
|
@ -15,6 +15,10 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_Winch_config.h"
|
||||||
|
|
||||||
|
#if AP_WINCH_ENABLED
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
@ -103,3 +107,5 @@ private:
|
|||||||
namespace AP {
|
namespace AP {
|
||||||
AP_Winch *winch();
|
AP_Winch *winch();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_WINCH_ENABLED
|
||||||
|
@ -1,5 +1,7 @@
|
|||||||
#include <AP_Winch/AP_Winch_Backend.h>
|
#include <AP_Winch/AP_Winch_Backend.h>
|
||||||
|
|
||||||
|
#if AP_WINCH_ENABLED
|
||||||
|
|
||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
|
|
||||||
@ -67,3 +69,5 @@ float AP_Winch_Backend::get_rate_limited_by_accel(float rate, float dt)
|
|||||||
|
|
||||||
return rate_limited;
|
return rate_limited;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_WINCH_ENABLED
|
||||||
|
@ -17,6 +17,8 @@
|
|||||||
|
|
||||||
#include <AP_Winch/AP_Winch.h>
|
#include <AP_Winch/AP_Winch.h>
|
||||||
|
|
||||||
|
#if AP_WINCH_ENABLED
|
||||||
|
|
||||||
class AP_Winch_Backend {
|
class AP_Winch_Backend {
|
||||||
public:
|
public:
|
||||||
AP_Winch_Backend(struct AP_Winch::Backend_Config &_config) :
|
AP_Winch_Backend(struct AP_Winch::Backend_Config &_config) :
|
||||||
@ -58,3 +60,5 @@ protected:
|
|||||||
int16_t previous_radio_in = -1; // previous RC input from pilot, used to ignore small changes
|
int16_t previous_radio_in = -1; // previous RC input from pilot, used to ignore small changes
|
||||||
float previous_rate; // previous rate used for acceleration limiting
|
float previous_rate; // previous rate used for acceleration limiting
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_WINCH_ENABLED
|
||||||
|
@ -1,5 +1,7 @@
|
|||||||
#include <AP_Winch/AP_Winch_Daiwa.h>
|
#include <AP_Winch/AP_Winch_Daiwa.h>
|
||||||
|
|
||||||
|
#if AP_WINCH_DAIWA_ENABLED
|
||||||
|
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
@ -223,3 +225,5 @@ void AP_Winch_Daiwa::control_winch()
|
|||||||
}
|
}
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_winch, scaled_output);
|
SRV_Channels::set_output_scaled(SRV_Channel::k_winch, scaled_output);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_WINCH_DAIWA_ENABLED
|
||||||
|
@ -30,6 +30,8 @@
|
|||||||
|
|
||||||
#include <AP_Winch/AP_Winch_Backend.h>
|
#include <AP_Winch/AP_Winch_Backend.h>
|
||||||
|
|
||||||
|
#if AP_WINCH_DAIWA_ENABLED
|
||||||
|
|
||||||
class AP_Winch_Daiwa : public AP_Winch_Backend {
|
class AP_Winch_Daiwa : public AP_Winch_Backend {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
@ -105,3 +107,5 @@ private:
|
|||||||
WAITING_FOR_MOTOR_TEMP
|
WAITING_FOR_MOTOR_TEMP
|
||||||
} parse_state;
|
} parse_state;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_WINCH_DAIWA_ENABLED
|
||||||
|
@ -1,5 +1,7 @@
|
|||||||
#include "AP_Winch_PWM.h"
|
#include "AP_Winch_PWM.h"
|
||||||
|
|
||||||
|
#if AP_WINCH_PWM_ENABLED
|
||||||
|
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
@ -106,3 +108,5 @@ void AP_Winch_PWM::write_log()
|
|||||||
0, // voltage (unsupported)
|
0, // voltage (unsupported)
|
||||||
0); // temp (unsupported)
|
0); // temp (unsupported)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_WINCH_PWM_ENABLED
|
||||||
|
@ -17,6 +17,8 @@
|
|||||||
|
|
||||||
#include <AP_Winch/AP_Winch_Backend.h>
|
#include <AP_Winch/AP_Winch_Backend.h>
|
||||||
|
|
||||||
|
#if AP_WINCH_PWM_ENABLED
|
||||||
|
|
||||||
class AP_Winch_PWM : public AP_Winch_Backend {
|
class AP_Winch_PWM : public AP_Winch_Backend {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
@ -45,3 +47,5 @@ private:
|
|||||||
uint32_t control_update_ms; // last time control_winch was called
|
uint32_t control_update_ms; // last time control_winch was called
|
||||||
float line_length; // estimated length of line in meters
|
float line_length; // estimated length of line in meters
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_WINCH_PWM_ENABLED
|
||||||
|
19
libraries/AP_Winch/AP_Winch_config.h
Normal file
19
libraries/AP_Winch/AP_Winch_config.h
Normal file
@ -0,0 +1,19 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
||||||
|
#ifndef AP_WINCH_ENABLED
|
||||||
|
#define AP_WINCH_ENABLED 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_WINCH_BACKEND_DEFAULT_ENABLED
|
||||||
|
#define AP_WINCH_BACKEND_DEFAULT_ENABLED AP_WINCH_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_WINCH_DAIWA_ENABLED
|
||||||
|
#define AP_WINCH_DAIWA_ENABLED AP_WINCH_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_WINCH_PWM_ENABLED
|
||||||
|
#define AP_WINCH_PWM_ENABLED AP_WINCH_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
Loading…
Reference in New Issue
Block a user