mirror of https://github.com/ArduPilot/ardupilot
RC_ChannelB rename.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1263 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
935df033b2
commit
dd8c20b03d
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
RC_ChannelB.cpp - Radio library for Arduino
|
||||
AP_RcChannel.cpp - Radio library for Arduino
|
||||
Code by Jason Short, James Goppert. DIYDrones.com
|
||||
|
||||
This library is free software; you can redistribute it and / or
|
||||
|
@ -11,10 +11,10 @@
|
|||
|
||||
#include <math.h>
|
||||
#include <avr/eeprom.h>
|
||||
#include "RC_ChannelB.h"
|
||||
#include "AP_RcChannel.h"
|
||||
#include <AP_Common.h>
|
||||
|
||||
void RC_ChannelB::readRadio(uint16_t pwmRadio) {
|
||||
void AP_RcChannel::readRadio(uint16_t pwmRadio) {
|
||||
// apply reverse
|
||||
if(_reverse) _pwmRadio = (_pwmNeutral - pwmRadio) + _pwmNeutral;
|
||||
else _pwmRadio = pwmRadio;
|
||||
|
@ -23,7 +23,7 @@ void RC_ChannelB::readRadio(uint16_t pwmRadio) {
|
|||
}
|
||||
|
||||
void
|
||||
RC_ChannelB::setPwm(uint16_t pwm)
|
||||
AP_RcChannel::setPwm(uint16_t pwm)
|
||||
{
|
||||
//Serial.printf("reverse: %s\n", (_reverse)?"true":"false");
|
||||
|
||||
|
@ -51,13 +51,13 @@ RC_ChannelB::setPwm(uint16_t pwm)
|
|||
}
|
||||
|
||||
void
|
||||
RC_ChannelB::setPosition(float position)
|
||||
AP_RcChannel::setPosition(float position)
|
||||
{
|
||||
setPwm(_positionToPwm(position));
|
||||
}
|
||||
|
||||
void
|
||||
RC_ChannelB::mixRadio(uint16_t infStart)
|
||||
AP_RcChannel::mixRadio(uint16_t infStart)
|
||||
{
|
||||
float inf = abs( int16_t(_pwmRadio - _pwmNeutral) );
|
||||
inf = min(inf, infStart);
|
||||
|
@ -66,7 +66,7 @@ RC_ChannelB::mixRadio(uint16_t infStart)
|
|||
}
|
||||
|
||||
uint16_t
|
||||
RC_ChannelB::_positionToPwm(const float & position)
|
||||
AP_RcChannel::_positionToPwm(const float & position)
|
||||
{
|
||||
uint16_t pwm;
|
||||
//Serial.printf("position: %f\n", position);
|
||||
|
@ -79,7 +79,7 @@ RC_ChannelB::_positionToPwm(const float & position)
|
|||
}
|
||||
|
||||
float
|
||||
RC_ChannelB::_pwmToPosition(const uint16_t & pwm)
|
||||
AP_RcChannel::_pwmToPosition(const uint16_t & pwm)
|
||||
{
|
||||
float position;
|
||||
if(pwm < _pwmNeutral)
|
|
@ -1,24 +1,24 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/// @file RC_ChannelB.h
|
||||
/// @brief RC_ChannelB manager
|
||||
/// @file AP_RcChannel.h
|
||||
/// @brief AP_RcChannel manager
|
||||
|
||||
#ifndef RC_ChannelB_h
|
||||
#define RC_ChannelB_h
|
||||
#ifndef AP_RcChannel_h
|
||||
#define AP_RcChannel_h
|
||||
|
||||
#include <stdint.h>
|
||||
#include <FastSerial.h>
|
||||
|
||||
/// @class RC_ChannelB
|
||||
/// @class AP_RcChannel
|
||||
/// @brief Object managing one RC channel
|
||||
//
|
||||
class RC_ChannelB{
|
||||
class AP_RcChannel{
|
||||
|
||||
public:
|
||||
|
||||
/// Constructor
|
||||
///
|
||||
RC_ChannelB(const float & scale, const uint16_t & pwmMin, const uint16_t & pwmNeutral,
|
||||
AP_RcChannel(const float & scale, const uint16_t & pwmMin, const uint16_t & pwmNeutral,
|
||||
const uint16_t & pwmMax, const uint16_t & pwmDeadZone,
|
||||
const bool & filter, const bool & reverse) :
|
||||
_scale(scale),
|
|
@ -8,7 +8,7 @@
|
|||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
#include <RC_ChannelB.h> // ArduPilot Mega RC Library
|
||||
#include <AP_RcChannel.h> // ArduPilot Mega RC Library
|
||||
#include <AP_EEProm.h>
|
||||
|
||||
AP_EEPromVar<float> scale(45.0,"RC1_SCALE");
|
||||
|
@ -25,9 +25,9 @@ AP_Var<bool> reverse(false,"RC1_REVERSE");
|
|||
|
||||
FastSerialPort0(Serial);
|
||||
|
||||
RC_ChannelB rc[] =
|
||||
AP_RcChannel rc[] =
|
||||
{
|
||||
RC_ChannelB(scale.get(),pwmMin.get(),pwmNeutral.get(),pwmMax.get(),
|
||||
AP_RcChannel(scale.get(),pwmMin.get(),pwmNeutral.get(),pwmMax.get(),
|
||||
pwmDeadZone.get(),filter.get(),reverse.get())
|
||||
|
||||
};
|
Loading…
Reference in New Issue