Commit fa567258 authored by Bryan Godbolt's avatar Bryan Godbolt

Added angular velocities.

Changed NUM_OUTPUT_SIGNALS to an const unsigned short from a #define and moved its definition into OpalRT.h from OpalLink.h so that the configuration would all be in one place.
parent 4355b8e7
......@@ -196,16 +196,15 @@ void OpalLink::getSignals()
{
unsigned long timeout = 0;
unsigned short acqGroup = 0; //this is actually group 1 in the model
unsigned short allocatedSignals = NUM_OUTPUT_SIGNALS;
unsigned short *numSignals = new unsigned short(0);
double *timestep = new double(0);
double values[NUM_OUTPUT_SIGNALS] = {};
double values[OpalRT::NUM_OUTPUT_SIGNALS] = {};
unsigned short *lastValues = new unsigned short(false);
unsigned short *decimation = new unsigned short(0);
while (!(*lastValues))
{
int returnVal = OpalGetSignals(timeout, acqGroup, allocatedSignals, numSignals, timestep,
int returnVal = OpalGetSignals(timeout, acqGroup, OpalRT::NUM_OUTPUT_SIGNALS, numSignals, timestep,
values, lastValues, decimation);
if (returnVal == EOK )
......@@ -229,9 +228,9 @@ void OpalLink::getSignals()
values[OpalRT::ROLL],
values[OpalRT::PITCH],
values[OpalRT::YAW],
0, // rollspeed
0, // pitchspeed
0 // yawspeed
values[OpalRT::ROLL_SPEED],
values[OpalRT::PITCH_SPEED],
values[OpalRT::YAW_SPEED]
);
receiveMessage(attitude);
......
......@@ -54,12 +54,6 @@ This file is part of the QGROUNDCONTROL project
#include "errno.h"
#include "string.h"
/*
Configuration info for the model
*/
#define NUM_OUTPUT_SIGNALS 36
/**
* @brief Interface to OpalRT targets
*
......
......@@ -37,16 +37,22 @@ This file is part of the QGROUNDCONTROL project
namespace OpalRT
{
/**
Configuration info for the model
*/
const unsigned short NUM_OUTPUT_SIGNALS=39;
/* ------------------------------ Outputs ------------------------------
*
* Copied from Mag_GPS_aided_INS.c Aug 20, 2010
* Port 1: Navigation state estimates
* 1 t [s] time elapsed since INS mode started
* 2-4 p^n [m] navigation frame position (N,E,D)
* 5-7 v^n [m/s] navigation frame velocity (N,E,D)
* 8-10 Euler angles [rad] (roll, pitch, yaw)
* 11-13 b_f [m/s^2] accelerometer biases
* 14-16 b_w [rad/s] gyro biases
* 11-13 Angular rates
* 14-16 b_f [m/s^2] accelerometer biases
* 17-19 b_w [rad/s] gyro biases
*
* Port 2: Navigation system status
* 1 mode (0: initialization, 1: INS)
......@@ -71,6 +77,9 @@ namespace OpalRT
ROLL,
PITCH,
YAW,
ROLL_SPEED,
PITCH_SPEED,
YAW_SPEED,
B_F_0,
B_F_1,
B_F_2,
......@@ -79,7 +88,7 @@ namespace OpalRT
B_W_2
};
/* Component IDs of the parameters. Currently they are all 1 becuase there is no advantage
/** 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.
*/
......
......@@ -45,6 +45,8 @@ namespace OpalRT
{
/** Stores a param_id for the mavlink parameter packets. This class adds the convenience
of storing the id as a string (e.g., easy comparison).
\todo Fix: warning: deprecated conversion from string constant to 'char*'
*/
class QGCParamID
{
......
......@@ -13,7 +13,6 @@ class OpalLinkConfigurationWindow : public QWidget
Q_OBJECT
public:
explicit OpalLinkConfigurationWindow(OpalLink* link, QWidget *parent = 0, Qt::WindowFlags flags = Qt::Sheet);
signals:
public slots:
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment