mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
New Relay class and the subclasses for APM1 and APM2.
Updated AP_Camera class.
This commit is contained in:
parent
393c893cdb
commit
cc7f26a99b
@ -60,9 +60,7 @@ AP_Camera::servo_pic()
|
|||||||
void
|
void
|
||||||
AP_Camera::relay_pic()
|
AP_Camera::relay_pic()
|
||||||
{
|
{
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
_apm_relay->on();
|
||||||
relay.on();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// leave a message that it should be active for this many loops (assumes 50hz loops)
|
// leave a message that it should be active for this many loops (assumes 50hz loops)
|
||||||
_trigger_counter = constrain_int16(_trigger_duration*5,0,255);
|
_trigger_counter = constrain_int16(_trigger_duration*5,0,255);
|
||||||
@ -142,7 +140,7 @@ AP_Camera::trigger_pic_cleanup()
|
|||||||
break;
|
break;
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
case AP_CAMERA_TRIGGER_TYPE_RELAY:
|
case AP_CAMERA_TRIGGER_TYPE_RELAY:
|
||||||
relay.off();
|
_apm_relay->off();
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
case AP_CAMERA_TRIGGER_TYPE_TRANSISTOR:
|
case AP_CAMERA_TRIGGER_TYPE_TRANSISTOR:
|
||||||
@ -162,7 +160,8 @@ AP_Camera::configure_msg(mavlink_message_t* msg)
|
|||||||
// not for us
|
// not for us
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// TODO do something with these values
|
// This values may or not be used by APM
|
||||||
|
// They are bypassed as "echo" to a external specialized board
|
||||||
/*
|
/*
|
||||||
* packet.aperture
|
* packet.aperture
|
||||||
* packet.command_id
|
* packet.command_id
|
||||||
@ -190,7 +189,8 @@ AP_Camera::control_msg(mavlink_message_t* msg)
|
|||||||
// not for us
|
// not for us
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// TODO do something with these values
|
// This values may or not be used by APM (the shot is)
|
||||||
|
// They are bypassed as "echo" to a external specialized board
|
||||||
/*
|
/*
|
||||||
* packet.command_id
|
* packet.command_id
|
||||||
* packet.extra_param
|
* packet.extra_param
|
||||||
|
@ -2,7 +2,6 @@
|
|||||||
|
|
||||||
/// @file AP_Camera.h
|
/// @file AP_Camera.h
|
||||||
/// @brief Photo or video camera manager, with EEPROM-backed storage of constants.
|
/// @brief Photo or video camera manager, with EEPROM-backed storage of constants.
|
||||||
/// @author Amilcar Lucas
|
|
||||||
|
|
||||||
#ifndef AP_CAMERA_H
|
#ifndef AP_CAMERA_H
|
||||||
#define AP_CAMERA_H
|
#define AP_CAMERA_H
|
||||||
@ -10,6 +9,7 @@
|
|||||||
#include <AP_Param.h>
|
#include <AP_Param.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <GCS_MAVLink.h>
|
#include <GCS_MAVLink.h>
|
||||||
|
#include <AP_Relay.h>
|
||||||
|
|
||||||
#define AP_CAMERA_TRIGGER_TYPE_SERVO 0
|
#define AP_CAMERA_TRIGGER_TYPE_SERVO 0
|
||||||
#define AP_CAMERA_TRIGGER_TYPE_RELAY 1
|
#define AP_CAMERA_TRIGGER_TYPE_RELAY 1
|
||||||
@ -35,11 +35,12 @@ class AP_Camera {
|
|||||||
public:
|
public:
|
||||||
/// Constructor
|
/// Constructor
|
||||||
///
|
///
|
||||||
AP_Camera() :
|
AP_Camera(AP_Relay *obj_relay) :
|
||||||
_trigger_counter(0), // count of number of cycles shutter has been held open
|
_trigger_counter(0), // count of number of cycles shutter has been held open
|
||||||
_thr_pic_counter(0) // timer variable for throttle_pic
|
_thr_pic_counter(0) // timer variable for throttle_pic
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
_apm_relay = obj_relay;
|
||||||
}
|
}
|
||||||
|
|
||||||
// single entry point to take pictures
|
// single entry point to take pictures
|
||||||
@ -62,6 +63,7 @@ private:
|
|||||||
AP_Int16 _servo_off_pwm; // PWM value to move servo to when shutter is deactivated
|
AP_Int16 _servo_off_pwm; // PWM value to move servo to when shutter is deactivated
|
||||||
uint8_t _trigger_counter; // count of number of cycles shutter has been held open
|
uint8_t _trigger_counter; // count of number of cycles shutter has been held open
|
||||||
uint8_t _thr_pic_counter; // timer variable for throttle_pic
|
uint8_t _thr_pic_counter; // timer variable for throttle_pic
|
||||||
|
AP_Relay *_apm_relay; // pointer to relay object from the base class Relay. The subclasses could be AP_Relay_APM1 or AP_Relay_APM2
|
||||||
|
|
||||||
void servo_pic(); // Servo operated camera
|
void servo_pic(); // Servo operated camera
|
||||||
void relay_pic(); // basic relay activation
|
void relay_pic(); // basic relay activation
|
||||||
|
@ -12,7 +12,13 @@
|
|||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
#define RELAY_PIN 47
|
#define RELAY_PIN 47
|
||||||
|
#else CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
#define RELAY_PIN 26
|
||||||
|
#else
|
||||||
|
#error "no RELAY_PIN defined for this board"
|
||||||
|
#endif
|
||||||
|
|
||||||
void AP_Relay::init() {
|
void AP_Relay::init() {
|
||||||
hal.gpio->pinMode(RELAY_PIN, GPIO_OUTPUT);
|
hal.gpio->pinMode(RELAY_PIN, GPIO_OUTPUT);
|
||||||
|
@ -36,5 +36,4 @@ public:
|
|||||||
bool get();
|
bool get();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#endif /* AP_RELAY_H_ */
|
#endif /* AP_RELAY_H_ */
|
||||||
|
Loading…
Reference in New Issue
Block a user