removed comments and fixed some euler bugs

This commit is contained in:
Roman
2016-04-20 22:06:11 +02:00
committed by Lorenz Meier
parent 5e0e522903
commit b8a219d351
6 changed files with 5 additions and 30 deletions
@@ -836,12 +836,6 @@ void AttitudePositionEstimatorEKF::publishAttitude()
_att.q[2] = _ekf->states[2];
_att.q[3] = _ekf->states[3];
_att.q_valid = true;
//_att.R_valid = true;
//_att.timestamp = _last_sensor_timestamp;
//_att.roll = euler(0);
//_att.pitch = euler(1);
//_att.yaw = euler(2);
_att.rollspeed = _ekf->dAngIMU.x / _ekf->dtIMU - _ekf->states[10] / _ekf->dtIMUfilt;
_att.pitchspeed = _ekf->dAngIMU.y / _ekf->dtIMU - _ekf->states[11] / _ekf->dtIMUfilt;
+3 -4
View File
@@ -106,10 +106,9 @@ int px4_simple_app_main(int argc, char *argv[])
(double)raw.accelerometer_m_s2[1],
(double)raw.accelerometer_m_s2[2]);
/* set att and publish this information for other apps */
//att.roll = raw.accelerometer_m_s2[0];
//att.pitch = raw.accelerometer_m_s2[1];
//att.yaw = raw.accelerometer_m_s2[2];
/* set att and publish this information for other apps
the following does not have any meaning, it's just an example
*/
att.q[0] = raw.accelerometer_m_s2[0];
att.q[1] = raw.accelerometer_m_s2[1];
att.q[2] = raw.accelerometer_m_s2[2];