mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: use battery singleton
This commit is contained in:
parent
53111129f2
commit
4776183554
|
@ -23,6 +23,7 @@
|
||||||
#include "AP_Frsky_Telem.h"
|
#include "AP_Frsky_Telem.h"
|
||||||
|
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
|
@ -33,8 +34,7 @@ extern const AP_HAL::HAL& hal;
|
||||||
ObjectArray<mavlink_statustext_t> AP_Frsky_Telem::_statustext_queue(FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY);
|
ObjectArray<mavlink_statustext_t> AP_Frsky_Telem::_statustext_queue(FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY);
|
||||||
|
|
||||||
//constructor
|
//constructor
|
||||||
AP_Frsky_Telem::AP_Frsky_Telem(const AP_BattMonitor &battery, const RangeFinder &rng) :
|
AP_Frsky_Telem::AP_Frsky_Telem(const RangeFinder &rng) :
|
||||||
_battery(battery),
|
|
||||||
_rng(rng)
|
_rng(rng)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
@ -139,7 +139,7 @@ void AP_Frsky_Telem::send_SPort_Passthrough(void)
|
||||||
_passthrough.batt_timer = AP_HAL::millis();
|
_passthrough.batt_timer = AP_HAL::millis();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (_battery.num_instances() > 1) {
|
if (AP::battery().num_instances() > 1) {
|
||||||
if ((now - _passthrough.batt_timer2) >= 1000) {
|
if ((now - _passthrough.batt_timer2) >= 1000) {
|
||||||
send_uint32(DIY_FIRST_ID+8, calc_batt(1));
|
send_uint32(DIY_FIRST_ID+8, calc_batt(1));
|
||||||
_passthrough.batt_timer2 = AP_HAL::millis();
|
_passthrough.batt_timer2 = AP_HAL::millis();
|
||||||
|
@ -202,6 +202,7 @@ void AP_Frsky_Telem::send_SPort(void)
|
||||||
_SPort.sport_status = true;
|
_SPort.sport_status = true;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
|
const AP_BattMonitor &_battery = AP::battery();
|
||||||
switch(readbyte) {
|
switch(readbyte) {
|
||||||
case SENSOR_ID_FAS:
|
case SENSOR_ID_FAS:
|
||||||
switch (_SPort.fas_call) {
|
switch (_SPort.fas_call) {
|
||||||
|
@ -294,6 +295,7 @@ void AP_Frsky_Telem::send_SPort(void)
|
||||||
void AP_Frsky_Telem::send_D(void)
|
void AP_Frsky_Telem::send_D(void)
|
||||||
{
|
{
|
||||||
const AP_AHRS &_ahrs = AP::ahrs();
|
const AP_AHRS &_ahrs = AP::ahrs();
|
||||||
|
const AP_BattMonitor &_battery = AP::battery();
|
||||||
|
|
||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
// send frame1 every 200ms
|
// send frame1 every 200ms
|
||||||
|
@ -589,6 +591,8 @@ void AP_Frsky_Telem::check_ekf_status(void)
|
||||||
*/
|
*/
|
||||||
uint32_t AP_Frsky_Telem::calc_param(void)
|
uint32_t AP_Frsky_Telem::calc_param(void)
|
||||||
{
|
{
|
||||||
|
const AP_BattMonitor &_battery = AP::battery();
|
||||||
|
|
||||||
uint32_t param = 0;
|
uint32_t param = 0;
|
||||||
|
|
||||||
// cycle through paramIDs
|
// cycle through paramIDs
|
||||||
|
@ -674,6 +678,8 @@ uint32_t AP_Frsky_Telem::calc_gps_status(void)
|
||||||
*/
|
*/
|
||||||
uint32_t AP_Frsky_Telem::calc_batt(uint8_t instance)
|
uint32_t AP_Frsky_Telem::calc_batt(uint8_t instance)
|
||||||
{
|
{
|
||||||
|
const AP_BattMonitor &_battery = AP::battery();
|
||||||
|
|
||||||
uint32_t batt;
|
uint32_t batt;
|
||||||
|
|
||||||
// battery voltage in decivolts, can have up to a 12S battery (4.25Vx12S = 51.0V)
|
// battery voltage in decivolts, can have up to a 12S battery (4.25Vx12S = 51.0V)
|
||||||
|
|
|
@ -15,7 +15,6 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
|
||||||
#include <AP_Notify/AP_Notify.h>
|
#include <AP_Notify/AP_Notify.h>
|
||||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||||
#include <AP_SerialManager/AP_SerialManager.h>
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
|
@ -115,7 +114,7 @@ for FrSky SPort Passthrough
|
||||||
|
|
||||||
class AP_Frsky_Telem {
|
class AP_Frsky_Telem {
|
||||||
public:
|
public:
|
||||||
AP_Frsky_Telem(const AP_BattMonitor &battery, const RangeFinder &rng);
|
AP_Frsky_Telem(const RangeFinder &rng);
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
AP_Frsky_Telem(const AP_Frsky_Telem &other) = delete;
|
AP_Frsky_Telem(const AP_Frsky_Telem &other) = delete;
|
||||||
|
@ -147,7 +146,6 @@ public:
|
||||||
void set_frame_string(const char *string) { _frame_string = string; }
|
void set_frame_string(const char *string) { _frame_string = string; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_BattMonitor &_battery;
|
|
||||||
const RangeFinder &_rng;
|
const RangeFinder &_rng;
|
||||||
AP_HAL::UARTDriver *_port; // UART used to send data to FrSky receiver
|
AP_HAL::UARTDriver *_port; // UART used to send data to FrSky receiver
|
||||||
AP_SerialManager::SerialProtocol _protocol; // protocol used - detected using SerialManager's SERIAL#_PROTOCOL parameter
|
AP_SerialManager::SerialProtocol _protocol; // protocol used - detected using SerialManager's SERIAL#_PROTOCOL parameter
|
||||||
|
|
Loading…
Reference in New Issue