Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
7cee3ba2
Commit
7cee3ba2
authored
Aug 31, 2010
by
Bryan Godbolt
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
successfully reading parameters from model
parent
e8b9da14
Changes
9
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
173 additions
and
55 deletions
+173
-55
OpalLink.cc
src/comm/OpalLink.cc
+25
-8
OpalLink.h
src/comm/OpalLink.h
+1
-0
OpalRT.h
src/comm/OpalRT.h
+6
-2
Parameter.cc
src/comm/Parameter.cc
+31
-0
Parameter.h
src/comm/Parameter.h
+29
-23
ParameterList.cc
src/comm/ParameterList.cc
+32
-4
ParameterList.h
src/comm/ParameterList.h
+27
-7
QGCParamID.cc
src/comm/QGCParamID.cc
+11
-9
QGCParamID.h
src/comm/QGCParamID.h
+11
-2
No files found.
src/comm/OpalLink.cc
View file @
7cee3ba2
...
...
@@ -82,15 +82,30 @@ void OpalLink::writeBytes(const char *bytes, qint64 length)
{
qDebug
()
<<
"OpalLink::writeBytes(): request params"
;
// getParameterList();
params
=
new
OpalRT
::
ParameterList
();
mavlink_message_t
param
;
char
paramName
[]
=
"NAV_FILT_INIT"
;
mavlink_msg_param_value_pack
(
systemID
,
componentID
,
&
param
,
(
int8_t
*
)(
paramName
),
0
,
1
,
0
);
receiveMessage
(
param
);
// char paramName[] = "NAV_FILT_INIT";
// mavlink_msg_param_value_pack(systemID, componentID, ¶m,
// (int8_t*)(paramName),
// 0,
// 1,
// 0);
// receiveMessage(param);
OpalRT
::
ParameterList
::
const_iterator
paramIter
;
for
(
paramIter
=
params
->
begin
();
paramIter
!=
params
->
end
();
++
paramIter
)
{
mavlink_msg_param_value_pack
(
systemID
,
(
*
paramIter
).
getComponentID
(),
&
param
,
(
*
paramIter
).
getParamID
().
toInt8_t
(),
(
static_cast
<
OpalRT
::
Parameter
>
(
*
paramIter
)).
getValue
(),
params
->
count
(),
params
->
indexOf
(
*
paramIter
));
receiveMessage
(
param
);
}
}
case
MAVLINK_MSG_ID_PARAM_SET
:
{
...
...
@@ -385,6 +400,8 @@ bool OpalLink::connect()
if
((
OpalConnect
(
101
,
false
,
&
modelState
)
==
EOK
)
&&
(
OpalGetSignalControl
(
0
,
true
)
==
EOK
))
{
connectState
=
true
;
/// \todo try/catch a delete in case params has already been allocated
params
=
new
OpalRT
::
ParameterList
();
emit
connected
();
heartbeatTimer
->
start
(
1000
/
heartbeatRate
);
getSignalsTimer
->
start
(
getSignalsPeriod
);
...
...
src/comm/OpalLink.h
View file @
7cee3ba2
...
...
@@ -49,6 +49,7 @@ This file is part of the QGROUNDCONTROL project
#include "configuration.h"
#include "OpalRT.h"
#include "ParameterList.h"
#include "Parameter.h"
#include "errno.h"
...
...
src/comm/OpalRT.h
View file @
7cee3ba2
...
...
@@ -68,11 +68,15 @@ namespace OpalRT
B_W_2
};
/* Component IDs of the parameters. Currently they are all 1 becuase there is no advantage
to dividing them between component ids. However this syntax is used so that this can
easily be changed in the future.
*/
enum
SubsystemIds
{
NAV_ID
=
1
,
LOG_ID
,
CONTROLLER_ID
LOG_ID
=
1
,
CONTROLLER_ID
=
1
};
}
#endif // OPALRT_H
src/comm/Parameter.cc
View file @
7cee3ba2
...
...
@@ -26,3 +26,34 @@ Parameter::~Parameter()
delete
simulinkName
;
delete
paramID
;
}
bool
Parameter
::
operator
==
(
const
Parameter
&
other
)
const
{
return
(
*
simulinkPath
)
==
*
(
other
.
simulinkPath
)
&&
*
simulinkName
==
*
(
other
.
simulinkName
)
&&
componentID
==
other
.
componentID
&&
*
paramID
==
*
(
other
.
paramID
)
&&
opalID
==
other
.
opalID
;
}
float
Parameter
::
getValue
()
//const
{
unsigned
short
allocatedParams
=
1
;
unsigned
short
numParams
;
// unsigned short allocatedValues;
unsigned
short
numValues
=
1
;
unsigned
short
returnedNumValues
;
double
value
;
int
returnVal
=
OpalGetParameters
(
allocatedParams
,
&
numParams
,
&
opalID
,
numValues
,
&
returnedNumValues
,
&
value
);
if
(
returnVal
!=
EOK
)
{
return
FLT_MAX
;
}
return
static_cast
<
float
>
(
value
);
}
src/comm/Parameter.h
View file @
7cee3ba2
...
...
@@ -27,32 +27,38 @@ This file is part of the QGROUNDCONTROL project
#include <QString>
#include "mavlink_types.h"
#include "QGCParamID.h"
#include "OpalApi.h"
#include <cfloat>
namespace
OpalRT
{
class
Parameter
{
public:
Parameter
(
char
*
simulinkPath
=
""
,
char
*
simulinkName
=
""
,
uint8_t
componentID
=
0
,
QGCParamID
paramID
=
QGCParamID
(),
unsigned
short
opalID
=
0
);
/// \todo Implement copy constructor
Parameter
(
const
Parameter
&
other
);
~
Parameter
();
QGCParamID
getParamID
()
{
return
*
paramID
;}
void
setOpalID
(
unsigned
short
opalID
)
{
this
->
opalID
=
opalID
;}
const
QString
&
getSimulinkPath
()
{
return
*
simulinkPath
;}
const
QString
&
getSimulinkName
()
{
return
*
simulinkName
;}
protected:
QString
*
simulinkPath
;
QString
*
simulinkName
;
uint8_t
componentID
;
QGCParamID
*
paramID
;
unsigned
short
opalID
;
};
class
Parameter
{
public:
Parameter
(
char
*
simulinkPath
=
""
,
char
*
simulinkName
=
""
,
uint8_t
componentID
=
0
,
QGCParamID
paramID
=
QGCParamID
(),
unsigned
short
opalID
=
0
);
Parameter
(
const
Parameter
&
other
);
~
Parameter
();
const
QGCParamID
&
getParamID
()
const
{
return
*
paramID
;}
void
setOpalID
(
unsigned
short
opalID
)
{
this
->
opalID
=
opalID
;}
const
QString
&
getSimulinkPath
()
{
return
*
simulinkPath
;}
const
QString
&
getSimulinkName
()
{
return
*
simulinkName
;}
uint8_t
getComponentID
()
const
{
return
componentID
;}
float
getValue
();
// const;
bool
operator
==
(
const
Parameter
&
other
)
const
;
protected:
QString
*
simulinkPath
;
QString
*
simulinkName
;
uint8_t
componentID
;
QGCParamID
*
paramID
;
unsigned
short
opalID
;
};
}
#endif // PARAMETER_H
src/comm/ParameterList.cc
View file @
7cee3ba2
...
...
@@ -2,8 +2,10 @@
using
namespace
OpalRT
;
ParameterList
::
ParameterList
()
:
params
(
new
QMap
<
int
,
QMap
<
QGCParamID
,
Parameter
>
>
),
paramVector
(
new
QVector
<
Parameter
>
)
{
params
=
new
QMap
<
int
,
QMap
<
QGCParamID
,
Parameter
>
>
;
//
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.
...
...
@@ -50,6 +52,7 @@ ParameterList::ParameterList()
for
(
paramIter
=
(
*
componentIter
).
begin
();
paramIter
!=
(
*
componentIter
).
end
();
++
paramIter
)
{
s
=
(
*
paramIter
).
getSimulinkPath
()
+
(
*
paramIter
).
getSimulinkName
();
paramVector
->
append
((
*
paramIter
));
if
(
opalParams
->
contains
(
s
))
{
(
*
paramIter
).
setOpalID
(
opalParams
->
value
(
s
));
...
...
@@ -68,16 +71,35 @@ ParameterList::ParameterList()
ParameterList
::~
ParameterList
()
{
delete
params
;
delete
paramVector
;
}
ParameterList
::
const_iterator
::
const_iterator
()
ParameterList
::
const_iterator
::
const_iterator
(
QList
<
Parameter
>
paramList
)
{
this
->
paramList
=
QList
<
Parameter
>
(
paramList
);
index
=
0
;
}
ParameterList
::
const_iterator
::
const_iterator
(
const
const_iterator
&
other
)
{
paramList
=
QList
<
Parameter
>
(
other
.
paramList
);
index
=
other
.
index
;
}
const_iterator
ParameterList
::
begin
()
ParameterList
::
const_iterator
ParameterList
::
begin
()
const
{
QList
<
QMap
<
QGCParamID
,
Parameter
>
>
compList
=
params
->
values
();
QList
<
Parameter
>
paramList
;
QList
<
QMap
<
QGCParamID
,
Parameter
>
>::
const_iterator
compIter
;
for
(
compIter
=
compList
.
begin
();
compIter
!=
compList
.
end
();
++
compIter
)
paramList
.
append
((
*
compIter
).
values
());
return
const_iterator
(
paramList
);
}
ParameterList
::
const_iterator
ParameterList
::
end
()
const
{
const_iterator
iter
=
begin
();
return
iter
+=
iter
.
paramList
.
size
();
}
/**
...
...
@@ -161,10 +183,16 @@ void ParameterList::getParameterList(QMap<QString, unsigned short> *opalParams)
else
opalParams
->
insert
(
path
+
'/'
+
name
,
idParam
[
i
]);
}
//
Dump out the list of parameters
//
Dump out the list of parameters
// QMap<QString, unsigned short>::const_iterator paramPrint;
// for (paramPrint = opalParams->begin(); paramPrint != opalParams->end(); ++paramPrint)
// qDebug() << paramPrint.key();
}
int
ParameterList
::
count
()
{
const_iterator
iter
=
begin
();
return
iter
.
paramList
.
count
();
}
src/comm/ParameterList.h
View file @
7cee3ba2
...
...
@@ -29,6 +29,7 @@ This file is part of the QGROUNDCONTROL project
#include "mavlink_types.h"
#include "QGCParamID.h"
#include "Parameter.h"
#include "QVector"
#include "OpalRT.h"
// Forward declare ParameterList before including OpalLink.h because a member of type ParameterList is used in OpalLink
...
...
@@ -45,23 +46,42 @@ namespace OpalRT
class
const_iterator
{
friend
class
ParameterList
;
public:
const_iterator
();
const_iterator
(
const_iterator
&
other
);
inline
const_iterator
()
{}
const_iterator
(
const
const_iterator
&
other
);
const_iterator
&
operator
+=
(
int
i
)
{
index
+=
i
;
return
*
this
;}
bool
operator
<
(
const
const_iterator
&
other
)
{
return
(
this
->
paramList
==
other
.
paramList
)
&&
(
this
->
index
<
other
.
index
);}
bool
operator
==
(
const
const_iterator
&
other
)
{
return
(
this
->
paramList
==
other
.
paramList
)
&&
(
this
->
index
==
other
.
index
);}
bool
operator
!=
(
const
const_iterator
&
other
)
{
return
!
((
*
this
)
==
other
);}
const
Parameter
&
operator
*
()
const
{
return
paramList
[
index
];}
const
Parameter
*
operator
->
()
const
{
return
&
paramList
[
index
];}
const_iterator
&
operator
++
()
{
++
index
;
return
*
this
;}
private:
int
componentID
;
QGCParamID
paramID
;
const_iterator
(
QList
<
Parameter
>
);
QList
<
Parameter
>
paramList
;
int
index
;
};
ParameterList
();
~
ParameterList
();
int
setValue
(
int
compid
,
QGCParamID
paramid
,
float
value
);
float
getValue
(
int
compid
,
QGCParamID
paramid
);
int
count
();
int
indexOf
(
const
Parameter
&
p
)
{
return
paramVector
->
indexOf
(
p
);}
const_iterator
begin
()
const
;
const_iterator
end
()
const
;
// const_iterator begin() const;
// const_iterator end() const;
protected:
QMap
<
int
,
QMap
<
QGCParamID
,
Parameter
>
>
*
params
;
QVector
<
Parameter
>
*
paramVector
;
void
getParameterList
(
QMap
<
QString
,
unsigned
short
>*
);
...
...
src/comm/QGCParamID.cc
View file @
7cee3ba2
#include "QGCParamID.h"
using
namespace
OpalRT
;
QGCParamID
::
QGCParamID
(
const
char
*
paramid
)
:
QString
(
paramid
)
QGCParamID
::
QGCParamID
(
const
char
*
paramid
)
:
data
(
paramid
)
{
}
QGCParamID
::
QGCParamID
(
const
Q
GCParamID
&
other
)
:
QString
(
other
)
QGCParamID
::
QGCParamID
(
const
Q
String
s
)
:
data
(
s
)
{
}
/*
bool QGCParamID::operator<(const QGCParamID& other)
QGCParamID
::
QGCParamID
(
const
QGCParamID
&
other
)
:
data
(
other
.
data
)
{
const QString *lefthand, *righthand;
lefthand = this;
righthand = &other;
return lefthand < righthand;
}
*/
//int8_t* QGCParamID::toInt8_t()
//{
// int8_t
// for (int i=0; ((i < data.size()) && (i < 15)); ++i)
//
//}
src/comm/QGCParamID.h
View file @
7cee3ba2
...
...
@@ -25,18 +25,27 @@ This file is part of the QGROUNDCONTROL project
#define QGCPARAMID_H
#include <QString>
#include "mavlink_types.h"
namespace
OpalRT
{
class
QGCParamID
:
public
QString
class
QGCParamID
{
public:
QGCParamID
(
const
char
*
paramid
);
QGCParamID
(
const
QString
);
QGCParamID
()
{}
QGCParamID
(
const
QGCParamID
&
other
);
// bool operator<(const QGCParamID& other);
bool
operator
<
(
const
QGCParamID
&
other
)
const
{
return
data
<
other
.
data
;}
bool
operator
==
(
const
QGCParamID
&
other
)
const
{
return
data
==
other
.
data
;}
const
QString
getParamString
()
const
{
return
static_cast
<
const
QString
>
(
data
);}
int8_t
*
toInt8_t
()
const
{
return
(
int8_t
*
)
data
.
toAscii
().
data
();}
protected:
QString
data
;
};
}
#endif // QGCPARAMID_H
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment