mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
RC_Channel: add support for RunCam camera control
make read_3pos_switch and enum public
This commit is contained in:
parent
93abfdb905
commit
3cba76123b
@ -32,6 +32,7 @@ extern const AP_HAL::HAL& hal;
|
||||
#include <AC_Avoidance/AC_Avoid.h>
|
||||
#include <AC_Sprayer/AC_Sprayer.h>
|
||||
#include <AP_Camera/AP_Camera.h>
|
||||
#include <AP_Camera/AP_RunCam.h>
|
||||
#include <AP_Gripper/AP_Gripper.h>
|
||||
#include <AP_ADSB/AP_ADSB.h>
|
||||
#include <AP_LandingGear/AP_LandingGear.h>
|
||||
@ -91,7 +92,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
||||
// @Description: Function assigned to this RC channel
|
||||
// @Values{Copter}: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 37:Throw, 38:ADSB Avoidance En, 39:PrecLoiter, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 52:Acro, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66:Relay5, 67:Relay6, 68:Stabilize, 69:PosHold, 70:AltHold, 71:FlowHold, 72:Circle, 73:Drift, 76:Standby Mode, 100:KillIMU1, 101:KillIMU2
|
||||
// @Values{Rover}: 0:Do Nothing, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 11:Fence, 16:Auto, 19:Gripper, 24:Auto Mission Reset, 28:Relay On/Off, 30:Lost Rover Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 46:RC Override Enable, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 59:Simple Mode, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66:Relay5, 67:Relay6, 74:Sailboat motoring 3pos, 100:KillIMU1, 101:KillIMU2, 207:MainSail
|
||||
// @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 16:ModeAuto, 24:Auto Mission Reset, 28:Relay On/Off, 29:Landing Gear, 34:Relay2 On/Off, 30:Lost Plane Sound, 31:Motor Emergency Stop, 35:Relay3 On/Off, 36:Relay4 On/Off, 38:ADSB Avoidance En, 41:ArmDisarm, 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 55:ModeGuided, 56:ModeLoiter, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5, 67:Relay6, 72:ModeCircle, 77:ModeTakeoff, 100:KillIMU1, 101:KillIMU2
|
||||
// @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 16:ModeAuto, 24:Auto Mission Reset, 28:Relay On/Off, 29:Landing Gear, 34:Relay2 On/Off, 30:Lost Plane Sound, 31:Motor Emergency Stop, 35:Relay3 On/Off, 36:Relay4 On/Off, 38:ADSB Avoidance En, 41:ArmDisarm, 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 55:ModeGuided, 56:ModeLoiter, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5, 67:Relay6, 72:ModeCircle, 77:ModeTakeoff, 78:RunCam Control, 100:KillIMU1, 101:KillIMU2
|
||||
// @User: Standard
|
||||
AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER|AP_PARAM_FRAME_PLANE),
|
||||
|
||||
@ -473,6 +474,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
|
||||
case AUX_FUNC::MISSION_RESET:
|
||||
case AUX_FUNC::MOTOR_ESTOP:
|
||||
case AUX_FUNC::RC_OVERRIDE_ENABLE:
|
||||
case AUX_FUNC::RUNCAM_CONTROL:
|
||||
case AUX_FUNC::SPRAYER:
|
||||
do_aux_function(ch_option, ch_flag);
|
||||
break;
|
||||
@ -572,6 +574,26 @@ void RC_Channel::do_aux_function_camera_trigger(const aux_switch_pos_t ch_flag)
|
||||
}
|
||||
}
|
||||
|
||||
void RC_Channel::do_aux_function_runcam_control(const aux_switch_pos_t ch_flag)
|
||||
{
|
||||
#if HAL_RUNCAM_ENABLED
|
||||
AP_RunCam *runcam = AP::runcam();
|
||||
if (runcam == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (ch_flag) {
|
||||
case HIGH:
|
||||
runcam->start_recording();
|
||||
break;
|
||||
case LOW:
|
||||
case MIDDLE:
|
||||
runcam->stop_recording();
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// enable or disable the fence
|
||||
void RC_Channel::do_aux_function_fence(const aux_switch_pos_t ch_flag)
|
||||
{
|
||||
@ -732,6 +754,11 @@ void RC_Channel::do_aux_function(const aux_func_t ch_option, const aux_switch_po
|
||||
case AUX_FUNC::RELAY6:
|
||||
do_aux_function_relay(5, ch_flag == HIGH);
|
||||
break;
|
||||
|
||||
case AUX_FUNC::RUNCAM_CONTROL:
|
||||
do_aux_function_runcam_control(ch_flag);
|
||||
break;
|
||||
|
||||
case AUX_FUNC::CLEAR_WP:
|
||||
do_aux_function_clear_wp(ch_flag);
|
||||
break;
|
||||
|
@ -175,6 +175,7 @@ public:
|
||||
SURFACE_TRACKING = 75, // Surface tracking upwards or downwards
|
||||
STANDBY = 76, // Standby mode
|
||||
TAKEOFF = 77, // takeoff
|
||||
RUNCAM_CONTROL = 78, // control RunCam device
|
||||
KILL_IMU1 = 100, // disable first IMU (for IMU failure testing)
|
||||
KILL_IMU2 = 101, // disable second IMU (for IMU failure testing)
|
||||
// if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
|
||||
@ -185,8 +186,6 @@ public:
|
||||
};
|
||||
typedef enum AUX_FUNC aux_func_t;
|
||||
|
||||
protected:
|
||||
|
||||
// auxillary switch handling (n.b.: we store this as 2-bits!):
|
||||
enum aux_switch_pos_t : uint8_t {
|
||||
LOW, // indicates auxiliary switch is in the low position (pwm <1200)
|
||||
@ -194,12 +193,17 @@ protected:
|
||||
HIGH // indicates auxiliary switch is in the high position (pwm >1800)
|
||||
};
|
||||
|
||||
bool read_3pos_switch(aux_switch_pos_t &ret) const WARN_IF_UNUSED;
|
||||
|
||||
protected:
|
||||
|
||||
virtual void init_aux_function(aux_func_t ch_option, aux_switch_pos_t);
|
||||
virtual void do_aux_function(aux_func_t ch_option, aux_switch_pos_t);
|
||||
|
||||
void do_aux_function_avoid_adsb(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_avoid_proximity(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_camera_trigger(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_runcam_control(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_fence(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_clear_wp(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_gripper(const aux_switch_pos_t ch_flag);
|
||||
@ -247,7 +251,6 @@ private:
|
||||
static const uint16_t AUX_PWM_TRIGGER_HIGH = 1800;
|
||||
// pwm value below which the option will be disabled:
|
||||
static const uint16_t AUX_PWM_TRIGGER_LOW = 1200;
|
||||
bool read_3pos_switch(aux_switch_pos_t &ret) const WARN_IF_UNUSED;
|
||||
|
||||
// Structure used to detect and debounce switch changes
|
||||
struct {
|
||||
|
Loading…
Reference in New Issue
Block a user