10 changed files with 369 additions and 28 deletions
@ -1,6 +1,28 @@
@@ -1,6 +1,28 @@
|
||||
#include "Parameter.h" |
||||
using namespace OpalRT; |
||||
|
||||
Parameter::Parameter() |
||||
Parameter::Parameter(char *simulinkPath, char *simulinkName, uint8_t componentID, |
||||
QGCParamID paramID, unsigned short opalID) |
||||
: simulinkPath(new QString(simulinkPath)), |
||||
simulinkName(new QString(simulinkName)), |
||||
componentID(componentID), |
||||
paramID(new QGCParamID(paramID)), |
||||
opalID(opalID) |
||||
|
||||
{ |
||||
} |
||||
Parameter::Parameter(const Parameter &other) |
||||
: componentID(other.componentID), |
||||
opalID(other.opalID) |
||||
{ |
||||
simulinkPath = new QString(*other.simulinkPath); |
||||
simulinkName = new QString(*other.simulinkName); |
||||
paramID = new QGCParamID(*other.paramID); |
||||
} |
||||
|
||||
Parameter::~Parameter() |
||||
{ |
||||
delete simulinkPath; |
||||
delete simulinkName; |
||||
delete paramID; |
||||
} |
||||
|
@ -0,0 +1,159 @@
@@ -0,0 +1,159 @@
|
||||
#include "ParameterList.h" |
||||
using namespace OpalRT; |
||||
|
||||
ParameterList::ParameterList() |
||||
{ |
||||
params = new QMap<int, QMap<QGCParamID, Parameter> >; |
||||
|
||||
/* Populate the map with parameter names. There is no elegant way of doing this so all
|
||||
parameter paths and names must be known at compile time and defined here. |
||||
Note: This function is written in a way that calls a lot of copy constructors and is |
||||
therefore not particularly efficient. However since it is only called once memory |
||||
and computation time are sacrificed for code clarity when adding and modifying |
||||
parameters. |
||||
When defining the path, the trailing slash is necessary |
||||
*/ |
||||
Parameter *p; |
||||
/* Component: Navigation Filter */ |
||||
p = new Parameter("avionics_src/sm_ampro/NAV_FILT_INIT/", |
||||
"Value", |
||||
OpalRT::NAV_ID, |
||||
QGCParamID("NAV_FILT_INIT")); |
||||
(*params)[OpalRT::NAV_ID].insert(p->getParamID(), *p); |
||||
delete p; |
||||
|
||||
p = new Parameter("avionics_src/sm_ampro/Gain/", |
||||
"Gain", |
||||
OpalRT::NAV_ID, |
||||
QGCParamID("TEST_OUTP_GAIN")); |
||||
(*params)[OpalRT::NAV_ID].insert(p->getParamID(), *p); |
||||
delete p; |
||||
|
||||
/* Component: Log Facility */ |
||||
p = new Parameter("avionics_src/sm_ampro/LOG_FILE_ON/", |
||||
"Value", |
||||
OpalRT::LOG_ID, |
||||
QGCParamID("LOG_FILE_ON")); |
||||
(*params)[OpalRT::LOG_ID].insert(p->getParamID(), *p); |
||||
delete p; |
||||
|
||||
/* Get a list of the available parameters from opal-rt */ |
||||
QMap<QString, unsigned short> *opalParams = new QMap<QString, unsigned short>; |
||||
getParameterList(opalParams); |
||||
|
||||
/* Iterate over the parameters we want to use in qgc and populate their ids */ |
||||
QMap<int, QMap<QGCParamID, Parameter> >::iterator componentIter; |
||||
QMap<QGCParamID, Parameter>::iterator paramIter; |
||||
QString s; |
||||
for (componentIter = params->begin(); componentIter != params->end(); ++componentIter) |
||||
{ |
||||
for (paramIter = (*componentIter).begin(); paramIter != (*componentIter).end(); ++paramIter) |
||||
{ |
||||
s = (*paramIter).getSimulinkPath() + (*paramIter).getSimulinkName(); |
||||
if (opalParams->contains(s)) |
||||
{ |
||||
(*paramIter).setOpalID(opalParams->value(s)); |
||||
qDebug() << __FILE__ << " Line:" << __LINE__ << ": Successfully added " << s; |
||||
} |
||||
else |
||||
{ |
||||
qDebug() << __FILE__ << " Line:" << __LINE__ << ": " << s << " was not found in param list"; |
||||
} |
||||
} |
||||
} |
||||
delete opalParams; |
||||
|
||||
} |
||||
|
||||
ParameterList::~ParameterList() |
||||
{ |
||||
delete params; |
||||
} |
||||
/**
|
||||
Get the list of parameters in the simulink model. This function does not require |
||||
any prior knowlege of the parameters. It works by first calling OpalGetParameterList to |
||||
get the number of paramters, then allocates the required amount of memory and then gets |
||||
the paramter list using a second call to OpalGetParameterList. |
||||
*/ |
||||
void ParameterList::getParameterList(QMap<QString, unsigned short> *opalParams) |
||||
{ |
||||
/* inputs */ |
||||
unsigned short allocatedParams=0; |
||||
unsigned short allocatedPathLen=0; |
||||
unsigned short allocatedNameLen=0; |
||||
unsigned short allocatedVarLen=0; |
||||
|
||||
/* outputs */ |
||||
unsigned short numParams; |
||||
unsigned short *idParam=NULL; |
||||
unsigned short maxPathLen; |
||||
char **paths=NULL; |
||||
unsigned short maxNameLen; |
||||
char **names=NULL; |
||||
unsigned short maxVarLen; |
||||
char **var=NULL; |
||||
|
||||
int returnValue; |
||||
|
||||
returnValue = OpalGetParameterList(allocatedParams, &numParams, idParam, |
||||
allocatedPathLen, &maxPathLen, paths, |
||||
allocatedNameLen, &maxNameLen, names, |
||||
allocatedVarLen, &maxVarLen, var); |
||||
if (returnValue!=E2BIG) |
||||
{ |
||||
OpalLink::setLastErrorMsg(); |
||||
OpalLink::displayLastErrorMsg(); |
||||
return; |
||||
} |
||||
|
||||
// allocate memory for parameter list
|
||||
|
||||
idParam = new unsigned short[numParams]; |
||||
allocatedParams = numParams; |
||||
|
||||
paths = new char*[numParams]; |
||||
for (int i=0; i<numParams; i++) |
||||
paths[i]=new char[maxPathLen]; |
||||
allocatedPathLen = maxPathLen; |
||||
|
||||
names = new char*[numParams]; |
||||
for (int i=0; i<numParams; i++) |
||||
names[i] = new char[maxNameLen]; |
||||
allocatedNameLen = maxNameLen; |
||||
|
||||
var = new char*[numParams]; |
||||
for (int i=0; i<numParams; i++) |
||||
var[i] = new char[maxVarLen]; |
||||
allocatedVarLen = maxVarLen; |
||||
|
||||
returnValue = OpalGetParameterList(allocatedParams, &numParams, idParam, |
||||
allocatedPathLen, &maxPathLen, paths, |
||||
allocatedNameLen, &maxNameLen, names, |
||||
allocatedVarLen, &maxVarLen, var); |
||||
|
||||
if (returnValue != EOK) |
||||
{ |
||||
OpalLink::setLastErrorMsg(); |
||||
OpalLink::displayLastErrorMsg(); |
||||
return; |
||||
} |
||||
|
||||
QString path, name; |
||||
for (int i=0; i<numParams; ++i) |
||||
{ |
||||
path.clear(); |
||||
path.append(paths[i]); |
||||
name.clear(); |
||||
name.append(names[i]); |
||||
if (path[path.size()-1] == '/') |
||||
opalParams->insert(path+name, idParam[i]); |
||||
else |
||||
opalParams->insert(path+'/'+name, idParam[i]); |
||||
} |
||||
// Dump out the list of parameters
|
||||
// QMap<QString, unsigned short>::const_iterator paramPrint;
|
||||
// for (paramPrint = opalParams->begin(); paramPrint != opalParams->end(); ++paramPrint)
|
||||
// qDebug() << paramPrint.key();
|
||||
|
||||
|
||||
} |
@ -0,0 +1,55 @@
@@ -0,0 +1,55 @@
|
||||
/*=====================================================================
|
||||
|
||||
QGroundControl Open Source Ground Control Station |
||||
|
||||
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
|
||||
This file is part of the QGROUNDCONTROL project |
||||
|
||||
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||
it under the terms of the GNU General Public License as published by |
||||
the Free Software Foundation, either version 3 of the License, or |
||||
(at your option) any later version. |
||||
|
||||
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||
GNU General Public License for more details. |
||||
|
||||
You should have received a copy of the GNU General Public License |
||||
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
======================================================================*/ |
||||
|
||||
#ifndef PARAMETERLIST_H |
||||
#define PARAMETERLIST_H |
||||
|
||||
#include <QMap> |
||||
|
||||
#include "mavlink_types.h" |
||||
#include "QGCParamID.h" |
||||
#include "Parameter.h" |
||||
#include "OpalRT.h" |
||||
|
||||
// Forward declare ParameterList before including OpalLink.h because a member of type ParameterList is used in OpalLink
|
||||
namespace OpalRT |
||||
{ |
||||
class ParameterList; |
||||
} |
||||
#include "OpalLink.h" |
||||
namespace OpalRT{ |
||||
class ParameterList |
||||
{ |
||||
public: |
||||
ParameterList(); |
||||
~ParameterList(); |
||||
int setValue(int compid, QGCParamID paramid, float value); |
||||
float getValue(int compid, QGCParamID paramid); |
||||
protected: |
||||
QMap<int, QMap<QGCParamID, Parameter> > *params; |
||||
|
||||
void getParameterList(QMap<QString, unsigned short>*); |
||||
|
||||
}; |
||||
} |
||||
#endif // PARAMETERLIST_H
|
@ -1,6 +1,21 @@
@@ -1,6 +1,21 @@
|
||||
#include "QGCParamID.h" |
||||
using namespace OpalRT; |
||||
|
||||
QGCParamID::QGCParamID() |
||||
QGCParamID::QGCParamID(const char *paramid):QString(paramid) |
||||
{ |
||||
} |
||||
|
||||
QGCParamID::QGCParamID(const QGCParamID &other):QString(other) |
||||
{ |
||||
|
||||
} |
||||
|
||||
/*
|
||||
bool QGCParamID::operator<(const QGCParamID& other) |
||||
{ |
||||
const QString *lefthand, *righthand; |
||||
lefthand = this; |
||||
righthand = &other; |
||||
return lefthand < righthand; |
||||
} |
||||
*/ |
||||
|
Loading…
Reference in new issue