1
0
Fork 0

Autopilot: fix configuration to prevent false warnings.

This commit is contained in:
Thomas Geymayer 2014-02-24 23:19:50 +01:00
parent 99fd9513d9
commit f1e0206f30
9 changed files with 121 additions and 163 deletions

View file

@ -53,16 +53,6 @@ bool AnalogComponent::configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root )
{
SG_LOG
(
SG_AUTOPILOT,
SG_BULK,
"AnalogComponent::configure(" << cfg_name << ")"
);
if( Component::configure(cfg_node, cfg_name, prop_root) )
return true;
if( cfg_name == "feedback-if-disabled" )
{
_feedback_if_disabled = cfg_node.getBoolValue();
@ -126,11 +116,5 @@ bool AnalogComponent::configure( SGPropertyNode& cfg_node,
return true;
}
SG_LOG
(
SG_AUTOPILOT,
SG_BULK,
"AnalogComponent::configure(" << cfg_name << ") [unhandled]"
);
return false;
return Component::configure(cfg_node, cfg_name, prop_root);
}

View file

@ -49,7 +49,9 @@ bool Component::configure( SGPropertyNode& prop_root,
SGPropertyNode_ptr child = cfg.getChild(i);
std::string cname(child->getName());
if( !configure(*child, cname, prop_root) )
if( !configure(*child, cname, prop_root)
&& cname != "params" ) // 'params' is usually used to specify parameters
// in PropertList files.
SG_LOG
(
SG_AUTOPILOT,
@ -66,24 +68,20 @@ bool Component::configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root )
{
SG_LOG
(
SG_AUTOPILOT,
SG_BULK,
"Component::configure(" << cfg_name << ")"
);
if ( cfg_name == "name" ) {
if ( cfg_name == "name" )
{
_name = cfg_node.getStringValue();
return true;
}
if ( cfg_name == "debug" ) {
if ( cfg_name == "debug" )
{
_debug = cfg_node.getBoolValue();
return true;
}
if ( cfg_name == "enable" ) {
if ( cfg_name == "enable" )
{
SGPropertyNode_ptr prop;
if( (prop = cfg_node.getChild("condition")) != NULL ) {
@ -108,17 +106,12 @@ bool Component::configure( SGPropertyNode& cfg_node,
}
return true;
} // enable
}
SG_LOG
(
SG_AUTOPILOT,
SG_BULK,
"Component::configure(" << cfg_name << ") [unhandled]"
);
return false;
}
//------------------------------------------------------------------------------
bool Component::isPropertyEnabled()
{
if( _condition )

View file

@ -105,8 +105,8 @@ public:
* @param prop_root Property root for all relative paths
* @param cfg Property node containing the configuration
*/
bool configure( SGPropertyNode& prop_root,
SGPropertyNode& cfg );
virtual bool configure( SGPropertyNode& prop_root,
SGPropertyNode& cfg );
/**
* @brief getter for the name property

View file

@ -60,9 +60,6 @@ bool DigitalComponent::configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root )
{
if( Component::configure(cfg_node, cfg_name, prop_root) )
return true;
if (cfg_name == "input") {
SGPropertyNode_ptr nameNode = cfg_node.getNode("name");
string name;
@ -108,5 +105,5 @@ bool DigitalComponent::configure( SGPropertyNode& cfg_node,
return true;
}
return false;
return Component::configure(cfg_node, cfg_name, prop_root);
}

View file

@ -26,37 +26,31 @@
//
#include "digitalfilter.hxx"
#include "functor.hxx"
#include <deque>
using std::map;
using std::string;
using std::endl;
using std::cout;
namespace FGXMLAutopilot {
namespace FGXMLAutopilot
{
/**
*
*
*/
class DigitalFilterImplementation : public SGReferenced {
protected:
virtual bool configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root ) = 0;
public:
virtual ~DigitalFilterImplementation() {}
DigitalFilterImplementation();
virtual void initialize( double initvalue ) {}
virtual double compute( double dt, double input ) = 0;
bool configure( SGPropertyNode& cfg,
SGPropertyNode& prop_root );
class DigitalFilterImplementation:
public SGReferenced
{
public:
virtual ~DigitalFilterImplementation() {}
DigitalFilterImplementation();
virtual void initialize( double initvalue ) {}
virtual double compute( double dt, double input ) = 0;
virtual bool configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root ) = 0;
void setDigitalFilter( DigitalFilter * digitalFilter ) { _digitalFilter = digitalFilter; }
void setDigitalFilter( DigitalFilter * digitalFilter ) { _digitalFilter = digitalFilter; }
protected:
DigitalFilter * _digitalFilter;
protected:
DigitalFilter * _digitalFilter;
};
/* --------------------------------------------------------------------------------- */
@ -194,31 +188,14 @@ public:
using namespace FGXMLAutopilot;
/* --------------------------------------------------------------------------------- */
/* --------------------------------------------------------------------------------- */
//------------------------------------------------------------------------------
DigitalFilterImplementation::DigitalFilterImplementation() :
_digitalFilter(NULL)
{
}
//------------------------------------------------------------------------------
bool DigitalFilterImplementation::configure( SGPropertyNode& cfg,
SGPropertyNode& prop_root )
{
for (int i = 0; i < cfg.nChildren(); ++i )
{
SGPropertyNode_ptr child = cfg.getChild(i);
if( configure(*child, child->getNameString(), prop_root) )
continue;
}
return true;
}
/* --------------------------------------------------------------------------------- */
/* --------------------------------------------------------------------------------- */
double GainFilterImplementation::compute( double dt, double input )
{
return _gainInput.get_value() * input;
@ -412,6 +389,7 @@ bool RateLimitFilterImplementation::configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root )
{
std::cout << "RateLimitFilterImplementation " << cfg_name << std::endl;
if (cfg_name == "max-rate-of-change" ) {
_rateOfChangeMax.push_back( new InputValue(prop_root, cfg_node, 1) );
return true;
@ -476,7 +454,7 @@ bool ExponentialFilterImplementation::configure( SGPropertyNode& cfg_node,
}
if (cfg_name == "type" ) {
string type(cfg_node.getStringValue());
std::string type(cfg_node.getStringValue());
_isSecondOrder = type == "double-exponential";
}
@ -642,67 +620,96 @@ DigitalFilter::~DigitalFilter()
{
}
//------------------------------------------------------------------------------
template<class DigitalFilterType>
DigitalFilterImplementation* digitalFilterFactory()
{
return new DigitalFilterType();
}
static map<string,FunctorBase<DigitalFilterImplementation> *> componentForge;
typedef std::map<std::string, DigitalFilterImplementation*(*)()>
DigitalFilterMap;
static DigitalFilterMap componentForge;
//------------------------------------------------------------------------------
bool DigitalFilter::configure( SGPropertyNode& prop_root,
SGPropertyNode& cfg )
{
if( componentForge.empty() )
{
componentForge["gain" ] = digitalFilterFactory<GainFilterImplementation>;
componentForge["exponential" ] = digitalFilterFactory<ExponentialFilterImplementation>;
componentForge["double-exponential" ] = digitalFilterFactory<ExponentialFilterImplementation>;
componentForge["moving-average" ] = digitalFilterFactory<MovingAverageFilterImplementation>;
componentForge["noise-spike" ] = digitalFilterFactory<NoiseSpikeFilterImplementation>;
componentForge["rate-limit" ] = digitalFilterFactory<RateLimitFilterImplementation>;
componentForge["reciprocal" ] = digitalFilterFactory<ReciprocalFilterImplementation>;
componentForge["derivative" ] = digitalFilterFactory<DerivativeFilterImplementation>;
componentForge["high-pass" ] = digitalFilterFactory<HighPassFilterImplementation>;
componentForge["lead-lag" ] = digitalFilterFactory<LeadLagFilterImplementation>;
componentForge["integrator" ] = digitalFilterFactory<IntegratorFilterImplementation>;
}
const std::string type = cfg.getStringValue("type");
DigitalFilterMap::iterator component_factory = componentForge.find(type);
if( component_factory == componentForge.end() )
{
SG_LOG(SG_AUTOPILOT, SG_WARN, "unhandled filter type '" << type << "'");
return false;
}
_implementation = (*component_factory->second)();
_implementation->setDigitalFilter( this );
for( int i = 0; i < cfg.nChildren(); ++i )
{
SGPropertyNode_ptr child = cfg.getChild(i);
std::string cname(child->getName());
if( !_implementation->configure(*child, cname, prop_root)
&& !configure(*child, cname, prop_root)
&& cname != "type"
&& cname != "params" ) // 'params' is usually used to specify parameters
// in PropertList files.
SG_LOG
(
SG_AUTOPILOT,
SG_WARN,
"DigitalFilter: unknown config node: " << cname
);
}
return true;
}
//------------------------------------------------------------------------------
bool DigitalFilter::configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root )
{
if( componentForge.empty() ) {
componentForge["gain"] = new CreateAndConfigureFunctor<GainFilterImplementation,DigitalFilterImplementation>();
componentForge["exponential"] = new CreateAndConfigureFunctor<ExponentialFilterImplementation,DigitalFilterImplementation>();
componentForge["double-exponential"] = new CreateAndConfigureFunctor<ExponentialFilterImplementation,DigitalFilterImplementation>();
componentForge["moving-average"] = new CreateAndConfigureFunctor<MovingAverageFilterImplementation,DigitalFilterImplementation>();
componentForge["noise-spike"] = new CreateAndConfigureFunctor<NoiseSpikeFilterImplementation,DigitalFilterImplementation>();
componentForge["rate-limit"] = new CreateAndConfigureFunctor<RateLimitFilterImplementation,DigitalFilterImplementation>();
componentForge["reciprocal"] = new CreateAndConfigureFunctor<ReciprocalFilterImplementation,DigitalFilterImplementation>();
componentForge["derivative"] = new CreateAndConfigureFunctor<DerivativeFilterImplementation,DigitalFilterImplementation>();
componentForge["high-pass"] = new CreateAndConfigureFunctor<HighPassFilterImplementation,DigitalFilterImplementation>();
componentForge["lead-lag"] = new CreateAndConfigureFunctor<LeadLagFilterImplementation,DigitalFilterImplementation>();
componentForge["integrator"] = new CreateAndConfigureFunctor<IntegratorFilterImplementation,DigitalFilterImplementation>();
}
SG_LOG(SG_AUTOPILOT, SG_BULK, "DigitalFilter::configure(" << cfg_name << ")");
if( AnalogComponent::configure(cfg_node, cfg_name, prop_root) )
return true;
if (cfg_name == "type" ) {
string type( cfg_node.getStringValue() );
if( componentForge.count(type) == 0 ) {
SG_LOG( SG_AUTOPILOT, SG_BULK, "unhandled filter type <" << type << ">" << endl );
return true;
}
_implementation = (*componentForge[type])(*cfg_node.getParent(), prop_root);
_implementation->setDigitalFilter( this );
return true;
}
if( cfg_name == "initialize-to" ) {
string s( cfg_node.getStringValue() );
if( s == "input" ) {
if( cfg_name == "initialize-to" )
{
std::string s( cfg_node.getStringValue() );
if( s == "input" )
_initializeTo = INITIALIZE_INPUT;
} else if( s == "output" ) {
else if( s == "output" )
_initializeTo = INITIALIZE_OUTPUT;
} else if( s == "none" ) {
else if( s == "none" )
_initializeTo = INITIALIZE_NONE;
} else {
SG_LOG( SG_AUTOPILOT, SG_WARN, "unhandled initialize-to value '" << s << "' ignored" );
}
else
SG_LOG
(
SG_AUTOPILOT,
SG_WARN, "DigitalFilter: initialize-to (" << s << ") ignored"
);
return true;
}
SG_LOG
(
SG_AUTOPILOT,
SG_BULK,
"DigitalFilter::configure(" << cfg_name << ") [unhandled]"
);
return false; // not handled by us, let the base class try
return AnalogComponent::configure(cfg_node, cfg_name, prop_root);
}
//------------------------------------------------------------------------------
void DigitalFilter::update( bool firstTime, double dt)
{
if( _implementation == NULL ) return;
@ -732,7 +739,7 @@ void DigitalFilter::update( bool firstTime, double dt)
set_output_value( output );
if(_debug) {
cout << "input:" << input
<< "\toutput:" << output << endl;
std::cout << "input:" << input
<< "\toutput:" << output << std::endl;
}
}

View file

@ -37,7 +37,7 @@ namespace FGXMLAutopilot {
*/
class DigitalFilter : public AnalogComponent
{
private:
private:
SGSharedPtr<class DigitalFilterImplementation> _implementation;
enum InitializeTo {
@ -46,7 +46,7 @@ private:
INITIALIZE_NONE
};
protected:
protected:
virtual bool configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root );
@ -62,6 +62,9 @@ public:
DigitalFilter();
~DigitalFilter();
virtual bool configure( SGPropertyNode& prop_root,
SGPropertyNode& cfg );
};
} // namespace FGXMLAutopilot

View file

@ -198,11 +198,6 @@ bool PIDController::configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root )
{
SG_LOG(SG_AUTOPILOT, SG_BULK, "PIDController::configure(" << cfg_name << ")");
if( AnalogComponent::configure(cfg_node, cfg_name, prop_root) )
return true;
if( cfg_name == "config" ) {
Component::configure(prop_root, cfg_node);
return true;
@ -241,14 +236,7 @@ bool PIDController::configure( SGPropertyNode& cfg_node,
if (cfg_name == "gamma") {
gamma = cfg_node.getDoubleValue();
return true;
}
}
SG_LOG
(
SG_AUTOPILOT,
SG_BULK,
"PIDController::configure(" << cfg_name << ") [unhandled]"
);
return false;
return AnalogComponent::configure(cfg_node, cfg_name, prop_root);
}

View file

@ -37,9 +37,6 @@ bool PISimpleController::configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root )
{
if( AnalogComponent::configure(cfg_node, cfg_name, prop_root) )
return true;
if( cfg_name == "config" ) {
Component::configure(prop_root, cfg_node);
return true;
@ -55,7 +52,7 @@ bool PISimpleController::configure( SGPropertyNode& cfg_node,
return true;
}
return false;
return AnalogComponent::configure(cfg_node, cfg_name, prop_root);
}
void PISimpleController::update( bool firstTime, double dt )

View file

@ -38,11 +38,6 @@ bool Predictor::configure( SGPropertyNode& cfg_node,
const std::string& cfg_name,
SGPropertyNode& prop_root )
{
SG_LOG( SG_AUTOPILOT, SG_BULK, "Predictor::configure(" << cfg_name << ")");
if( AnalogComponent::configure(cfg_node, cfg_name, prop_root) )
return true;
if( cfg_name == "config" ) {
Component::configure(prop_root, cfg_node);
return true;
@ -58,13 +53,7 @@ bool Predictor::configure( SGPropertyNode& cfg_node,
return true;
}
SG_LOG
(
SG_AUTOPILOT,
SG_BULK,
"Predictor::configure(" << cfg_name << ") [unhandled]"
);
return false;
return AnalogComponent::configure(cfg_node, cfg_name, prop_root);
}
//------------------------------------------------------------------------------