mirror of https://github.com/ArduPilot/ardupilot
Use AP_Var to store channel calibration.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1651 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
ddfab124cd
commit
8e7301b4d3
|
@ -79,14 +79,14 @@ RC_Channel::set_pwm(int pwm)
|
|||
//Serial.print("range ");
|
||||
control_in = pwm_to_range();
|
||||
control_in = (control_in < dead_zone) ? 0 : control_in;
|
||||
if(scale_output){
|
||||
if (fabs(scale_output) > 0){
|
||||
control_in *= scale_output;
|
||||
}
|
||||
|
||||
}else{
|
||||
control_in = pwm_to_angle();
|
||||
control_in = (abs(control_in) < dead_zone) ? 0 : control_in;
|
||||
if(scale_output){
|
||||
if (fabs(scale_output) > 0){
|
||||
control_in *= scale_output;
|
||||
}
|
||||
}
|
||||
|
@ -117,7 +117,7 @@ RC_Channel::calc_pwm(void)
|
|||
pwm_out = angle_to_pwm();
|
||||
radio_out = pwm_out + radio_trim;
|
||||
}
|
||||
radio_out = constrain(radio_out,radio_min, radio_max);
|
||||
radio_out = constrain(radio_out, radio_min.get(), radio_max.get());
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
@ -125,32 +125,21 @@ RC_Channel::calc_pwm(void)
|
|||
void
|
||||
RC_Channel::load_eeprom(void)
|
||||
{
|
||||
radio_min = eeprom_read_word((uint16_t *) _address);
|
||||
radio_max = eeprom_read_word((uint16_t *) (_address + 2));
|
||||
radio_trim = eeprom_read_word((uint16_t *) (_address + 4));
|
||||
//radio_min = _ee.read_int(_address);
|
||||
//radio_max = _ee.read_int(_address + 2);
|
||||
//radio_trim = _ee.read_int(_address + 4);
|
||||
_group.load();
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::save_eeprom(void)
|
||||
{
|
||||
eeprom_write_word((uint16_t *) _address, radio_min);
|
||||
eeprom_write_word((uint16_t *) (_address + 2), radio_max);
|
||||
eeprom_write_word((uint16_t *) (_address + 4), radio_trim);
|
||||
|
||||
//_ee.write_int(_address, radio_min);
|
||||
//_ee.write_int((_address + 2), radio_max);
|
||||
//_ee.write_int((_address + 4), radio_trim);
|
||||
_group.save();
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
//XXX is this still in use?
|
||||
void
|
||||
RC_Channel::save_trim(void)
|
||||
{
|
||||
eeprom_write_word((uint16_t *) (_address + 4), radio_trim);
|
||||
//_ee.write_int((_address + 4), radio_trim);
|
||||
_group.save();
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
@ -158,14 +147,14 @@ RC_Channel::save_trim(void)
|
|||
void
|
||||
RC_Channel::zero_min_max()
|
||||
{
|
||||
radio_min = radio_min = radio_in;
|
||||
radio_min = radio_max = radio_in;
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::update_min_max()
|
||||
{
|
||||
radio_min = min(radio_min, radio_in);
|
||||
radio_max = max(radio_max, radio_in);
|
||||
radio_min = min(radio_min.get(), radio_in);
|
||||
radio_max = max(radio_max.get(), radio_in);
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
|
|
@ -6,6 +6,7 @@
|
|||
#ifndef RC_Channel_h
|
||||
#define RC_Channel_h
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/// @class RC_Channel
|
||||
|
@ -14,23 +15,14 @@ class RC_Channel{
|
|||
public:
|
||||
/// Constructor
|
||||
///
|
||||
/// A RC_Channel constructed in this fashion does not support save/restore.
|
||||
/// @param key EEPROM storage key for the channel trim parameters.
|
||||
/// @param name Optional name for the group.
|
||||
///
|
||||
RC_Channel() :
|
||||
_address(0),
|
||||
_reverse(1),
|
||||
dead_zone(0),
|
||||
scale_output(1.0)
|
||||
{}
|
||||
|
||||
/// Constructor
|
||||
///
|
||||
/// @param address EEPROM base address at which RC_Channel parameters
|
||||
/// are stored. Zero if the RC_Channel does not support
|
||||
/// save/restore.
|
||||
///
|
||||
RC_Channel(uint16_t address) :
|
||||
_address(address),
|
||||
RC_Channel(AP_Var::Key key, const prog_char *name) :
|
||||
_group(key, name),
|
||||
radio_min (&_group, 0, 1500, name ? "MIN" : 0), // suppress name if group has no name
|
||||
radio_trim(&_group, 1, 1500, name ? "TRIM" : 0),
|
||||
radio_max (&_group, 2, 1500, name ? "MAX" : 0),
|
||||
_high(1),
|
||||
_filter(true),
|
||||
_reverse(1),
|
||||
|
@ -82,9 +74,9 @@ class RC_Channel{
|
|||
int16_t pwm_out;
|
||||
int16_t radio_out;
|
||||
|
||||
int16_t radio_min;
|
||||
int16_t radio_trim;
|
||||
int16_t radio_max;
|
||||
AP_Int16 radio_min;
|
||||
AP_Int16 radio_trim;
|
||||
AP_Int16 radio_max;
|
||||
|
||||
// includes offset from PWM
|
||||
//int16_t get_radio_out(void);
|
||||
|
@ -99,10 +91,10 @@ class RC_Channel{
|
|||
float scale_output;
|
||||
|
||||
private:
|
||||
AP_Var_group _group;
|
||||
bool _filter;
|
||||
int8_t _reverse;
|
||||
|
||||
int16_t _address; ///< EEPROM address for save/restore of P/I/D
|
||||
bool _type;
|
||||
int16_t _high;
|
||||
int16_t _low;
|
||||
|
|
Loading…
Reference in New Issue