From 1caddb7bbb53f3017e2ee67742531b2159999658 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Tue, 21 May 2013 16:11:03 +1000 Subject: Initial work of so3 nonlinear complementary filter --- .../attitude_estimator_so3_comp_main.cpp | 610 +++++++++++++++++++++ .../attitude_estimator_so3_comp_params.c | 44 ++ .../attitude_estimator_so3_comp_params.h | 32 ++ src/modules/attitude_estimator_so3_comp/module.mk | 8 + 4 files changed, 694 insertions(+) create mode 100755 src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp create mode 100755 src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c create mode 100755 src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h create mode 100644 src/modules/attitude_estimator_so3_comp/module.mk (limited to 'src') diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp new file mode 100755 index 000000000..381b0df75 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -0,0 +1,610 @@ +/* + * @file attitude_estimator_so3_comp_main.c + * + * Nonlinear SO3 filter for Attitude Estimation. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif +#include "attitude_estimator_so3_comp_params.h" +#ifdef __cplusplus +} +#endif + +extern "C" __EXPORT int attitude_estimator_so3_comp_main(int argc, char *argv[]); + +static bool thread_should_exit = false; /**< Deamon exit flag */ +static bool thread_running = false; /**< Deamon status flag */ +static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ +volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame + +/** + * Mainloop of attitude_estimator_so3_comp. + */ +int attitude_estimator_so3_comp_thread_main(int argc, char *argv[]); + +/** + * Print the correct usage. + */ +static void usage(const char *reason); + +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + + fprintf(stderr, "usage: attitude_estimator_so3_comp {start|stop|status} [-p ]\n\n"); + exit(1); +} + +/** + * The attitude_estimator_so3_comp app only briefly exists to start + * the background job. The stack size assigned in the + * Makefile does only apply to this management task. + * + * The actual stack size should be set in the call + * to task_create(). + */ +int attitude_estimator_so3_comp_main(int argc, char *argv[]) +{ + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + printf("attitude_estimator_so3_comp already running\n"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + attitude_estimator_so3_comp_task = task_spawn("attitude_estimator_so3_comp", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 5, + 12400, + attitude_estimator_so3_comp_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + printf("\tattitude_estimator_so3_comp app is running\n"); + + } else { + printf("\tattitude_estimator_so3_comp app not started\n"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +//--------------------------------------------------------------------------------------------------- +// Fast inverse square-root +// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root +float invSqrt(float x) { + float halfx = 0.5f * x; + float y = x; + long i = *(long*)&y; + i = 0x5f3759df - (i>>1); + y = *(float*)&i; + y = y * (1.5f - (halfx * y * y)); + return y; +} + +void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az, float twoKp, float twoKi, float dt) { + float recipNorm; + float halfvx, halfvy, halfvz; + float halfex, halfey, halfez; + float qa, qb, qc; + + // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) + if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Estimated direction of gravity and vector perpendicular to magnetic flux + halfvx = q1 * q3 - q0 * q2; + halfvy = q0 * q1 + q2 * q3; + halfvz = q0 * q0 - 0.5f + q3 * q3; + + // Error is sum of cross product between estimated and measured direction of gravity + halfex = (ay * halfvz - az * halfvy); + halfey = (az * halfvx - ax * halfvz); + halfez = (ax * halfvy - ay * halfvx); + + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + integralFBx += twoKi * halfex * dt; // integral error scaled by Ki + integralFBy += twoKi * halfey * dt; + integralFBz += twoKi * halfez * dt; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } + else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } + + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; + } + + // Integrate rate of change of quaternion + gx *= (0.5f * dt); // pre-multiply common factors + gy *= (0.5f * dt); + gz *= (0.5f * dt); + qa = q0; + qb = q1; + qc = q2; + q0 += (-qb * gx - qc * gy - q3 * gz); + q1 += (qa * gx + qc * gz - q3 * gy); + q2 += (qa * gy - qb * gz + q3 * gx); + q3 += (qa * gz + qb * gy - qc * gx); + + // Normalise quaternion + recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; +} + +void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { + float recipNorm; + float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; + float hx, hy, bx, bz; + float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; + float halfex, halfey, halfez; + float qa, qb, qc; + + // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) + if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { + MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az, twoKp, twoKi, dt); + return; + } + + // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) + if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Normalise magnetometer measurement + recipNorm = invSqrt(mx * mx + my * my + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; + + // Reference direction of Earth's magnetic field + hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); + hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); + bx = sqrt(hx * hx + hy * hy); + bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); + + // Estimated direction of gravity and magnetic field + halfvx = q1q3 - q0q2; + halfvy = q0q1 + q2q3; + halfvz = q0q0 - 0.5f + q3q3; + halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); + halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); + halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); + + // Error is sum of cross product between estimated direction and measured direction of field vectors + halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); + halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); + halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); + + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + integralFBx += twoKi * halfex * dt; // integral error scaled by Ki + integralFBy += twoKi * halfey * dt; + integralFBz += twoKi * halfez * dt; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } + else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } + + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; + } + + // Integrate rate of change of quaternion + gx *= (0.5f * dt); // pre-multiply common factors + gy *= (0.5f * dt); + gz *= (0.5f * dt); + qa = q0; + qb = q1; + qc = q2; + q0 += (-qb * gx - qc * gy - q3 * gz); + q1 += (qa * gx + qc * gz - q3 * gy); + q2 += (qa * gy - qb * gz + q3 * gx); + q3 += (qa * gz + qb * gy - qc * gx); + + // Normalise quaternion + recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; +} + +/* + * [Rot_matrix,x_aposteriori,P_aposteriori] = attitudeKalmanfilter(dt,z_k,x_aposteriori_k,P_aposteriori_k,knownConst) + */ + +/* + * EKF Attitude Estimator main function. + * + * Estimates the attitude recursively once started. + * + * @param argc number of commandline arguments (plus command name) + * @param argv strings containing the arguments + */ +int attitude_estimator_so3_comp_thread_main(int argc, char *argv[]) +{ + +const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds + + float dt = 0.005f; + + /* output euler angles */ + float euler[3] = {0.0f, 0.0f, 0.0f}; + + float Rot_matrix[9] = {1.f, 0, 0, + 0, 1.f, 0, + 0, 0, 1.f + }; /**< init: identity matrix */ + + float acc[3] = {0.0f, 0.0f, 0.0f}; + float gyro[3] = {0.0f, 0.0f, 0.0f}; + float mag[3] = {0.0f, 0.0f, 0.0f}; + + // print text + printf("Nonlinear SO3 Attitude Estimator initialized..\n\n"); + fflush(stdout); + + int overloadcounter = 19; + + /* store start time to guard against too slow update rates */ + uint64_t last_run = hrt_absolute_time(); + + struct sensor_combined_s raw; + memset(&raw, 0, sizeof(raw)); + struct vehicle_attitude_s att; + memset(&att, 0, sizeof(att)); + struct vehicle_status_s state; + memset(&state, 0, sizeof(state)); + + uint64_t last_data = 0; + uint64_t last_measurement = 0; + + /* subscribe to raw data */ + int sub_raw = orb_subscribe(ORB_ID(sensor_combined)); + /* rate-limit raw data updates to 200Hz */ + orb_set_interval(sub_raw, 4); + + /* subscribe to param changes */ + int sub_params = orb_subscribe(ORB_ID(parameter_update)); + + /* subscribe to system state*/ + int sub_state = orb_subscribe(ORB_ID(vehicle_status)); + + /* advertise attitude */ + orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att); + + int loopcounter = 0; + int printcounter = 0; + + thread_running = true; + + /* advertise debug value */ + // struct debug_key_value_s dbg = { .key = "", .value = 0.0f }; + // orb_advert_t pub_dbg = -1; + + float sensor_update_hz[3] = {0.0f, 0.0f, 0.0f}; + // XXX write this out to perf regs + + /* keep track of sensor updates */ + uint32_t sensor_last_count[3] = {0, 0, 0}; + uint64_t sensor_last_timestamp[3] = {0, 0, 0}; + + struct attitude_estimator_so3_comp_params so3_comp_params; + struct attitude_estimator_so3_comp_param_handles so3_comp_param_handles; + + /* initialize parameter handles */ + parameters_init(&so3_comp_param_handles); + + uint64_t start_time = hrt_absolute_time(); + bool initialized = false; + + float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f }; + unsigned offset_count = 0; + + /* register the perf counter */ + perf_counter_t so3_comp_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_so3_comp"); + + /* Main loop*/ + while (!thread_should_exit) { + + struct pollfd fds[2]; + fds[0].fd = sub_raw; + fds[0].events = POLLIN; + fds[1].fd = sub_params; + fds[1].events = POLLIN; + int ret = poll(fds, 2, 1000); + + if (ret < 0) { + /* XXX this is seriously bad - should be an emergency */ + } else if (ret == 0) { + /* check if we're in HIL - not getting sensor data is fine then */ + orb_copy(ORB_ID(vehicle_status), sub_state, &state); + + if (!state.flag_hil_enabled) { + fprintf(stderr, + "[att so3_comp] WARNING: Not getting sensors - sensor app running?\n"); + } + + } else { + + /* only update parameters if they changed */ + if (fds[1].revents & POLLIN) { + /* read from param to clear updated flag */ + struct parameter_update_s update; + orb_copy(ORB_ID(parameter_update), sub_params, &update); + + /* update parameters */ + parameters_update(&so3_comp_param_handles, &so3_comp_params); + } + + /* only run filter if sensor values changed */ + if (fds[0].revents & POLLIN) { + + /* get latest measurements */ + orb_copy(ORB_ID(sensor_combined), sub_raw, &raw); + + if (!initialized) { + + gyro_offsets[0] += raw.gyro_rad_s[0]; + gyro_offsets[1] += raw.gyro_rad_s[1]; + gyro_offsets[2] += raw.gyro_rad_s[2]; + offset_count++; + + if (hrt_absolute_time() - start_time > 3000000LL) { + initialized = true; + gyro_offsets[0] /= offset_count; + gyro_offsets[1] /= offset_count; + gyro_offsets[2] /= offset_count; + } + + } else { + + perf_begin(so3_comp_loop_perf); + + /* Calculate data time difference in seconds */ + dt = (raw.timestamp - last_measurement) / 1000000.0f; + last_measurement = raw.timestamp; + uint8_t update_vect[3] = {0, 0, 0}; + + /* Fill in gyro measurements */ + if (sensor_last_count[0] != raw.gyro_counter) { + update_vect[0] = 1; + sensor_last_count[0] = raw.gyro_counter; + sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]); + sensor_last_timestamp[0] = raw.timestamp; + } + + gyro[0] = raw.gyro_rad_s[0] - gyro_offsets[0]; + gyro[1] = raw.gyro_rad_s[1] - gyro_offsets[1]; + gyro[2] = raw.gyro_rad_s[2] - gyro_offsets[2]; + + /* update accelerometer measurements */ + if (sensor_last_count[1] != raw.accelerometer_counter) { + update_vect[1] = 1; + sensor_last_count[1] = raw.accelerometer_counter; + sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]); + sensor_last_timestamp[1] = raw.timestamp; + } + + acc[0] = raw.accelerometer_m_s2[0]; + acc[1] = raw.accelerometer_m_s2[1]; + acc[2] = raw.accelerometer_m_s2[2]; + + /* update magnetometer measurements */ + if (sensor_last_count[2] != raw.magnetometer_counter) { + update_vect[2] = 1; + sensor_last_count[2] = raw.magnetometer_counter; + sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]); + sensor_last_timestamp[2] = raw.timestamp; + } + + mag[0] = raw.magnetometer_ga[0]; + mag[1] = raw.magnetometer_ga[1]; + mag[2] = raw.magnetometer_ga[2]; + + uint64_t now = hrt_absolute_time(); + unsigned int time_elapsed = now - last_run; + last_run = now; + + if (time_elapsed > loop_interval_alarm) { + //TODO: add warning, cpu overload here + // if (overloadcounter == 20) { + // printf("CPU OVERLOAD DETECTED IN ATTITUDE ESTIMATOR EKF (%lu > %lu)\n", time_elapsed, loop_interval_alarm); + // overloadcounter = 0; + // } + + overloadcounter++; + } + + static bool const_initialized = false; + + /* initialize with good values once we have a reasonable dt estimate */ + if (!const_initialized && dt < 0.05f && dt > 0.005f) { + dt = 0.005f; + parameters_update(&so3_comp_param_handles, &so3_comp_params); + const_initialized = true; + } + + /* do not execute the filter if not initialized */ + if (!const_initialized) { + continue; + } + + uint64_t timing_start = hrt_absolute_time(); + + MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],acc[0],acc[1],acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); + + float aSq = q0*q0; + float bSq = q1*q1; + float cSq = q2*q2; + float dSq = q3*q3; + + Rot_matrix[0] = aSq + bSq - cSq - dSq; + Rot_matrix[1] = 2.0 * (b * c - a * d); + Rot_matrix[2] = 2.0 * (a * c + b * d); + Rot_matrix[3] = 2.0 * (b * c + a * d); + Rot_matrix[4] = aSq - bSq + cSq - dSq; + Rot_matrix[5] = 2.0 * (c * d - a * b); + Rot_matrix[6] = 2.0 * (b * d - a * c); + Rot_matrix[7] = 2.0 * (a * b + c * d); + Rot_matrix[8] = aSq - bSq - cSq + dSq; + + /* Compute Euler angle */ + float theta = asinf(-Rot_matrix[6]); + euler[1] = theta; + + if(fabsf(theta - M_PI_2_F) < 1.0e-3f){ + euler[0] = 0.0f; + euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]); + } else if (fabsf(theta + M_PI_2_F) < 1.0e-3f) { + euler[0] = 0.0f; + euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]); + } else { + euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); + euler[2] = atan2f(Rot_matrix[3], Rot_matrix[0]); + } + + /* swap values for next iteration, check for fatal inputs */ + if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { + /* Do something */ + } else { + /* due to inputs or numerical failure the output is invalid, skip it */ + continue; + } + + if (last_data > 0 && raw.timestamp - last_data > 12000) printf("[attitude estimator so3_comp] sensor data missed! (%llu)\n", raw.timestamp - last_data); + + last_data = raw.timestamp; + + /* send out */ + att.timestamp = raw.timestamp; + + // XXX Apply the same transformation to the rotation matrix + att.roll = euler[0] - so3_comp_params.roll_off; + att.pitch = euler[1] - so3_comp_params.pitch_off; + att.yaw = euler[2] - so3_comp_params.yaw_off; + + /* FIXME : This can be a problem for rate controller. Rate in body or inertial? + att.rollspeed = x_aposteriori[0]; + att.pitchspeed = x_aposteriori[1]; + att.yawspeed = x_aposteriori[2]; + att.rollacc = x_aposteriori[3]; + att.pitchacc = x_aposteriori[4]; + att.yawacc = x_aposteriori[5]; + */ + + //att.yawspeed =z_k[2] ; + /* copy offsets */ + //memcpy(&att.rate_offsets, &(x_aposteriori[3]), sizeof(att.rate_offsets)); + + /* copy rotation matrix */ + memcpy(&att.R, Rot_matrix, sizeof(Rot_matrix)); + att.R_valid = true; + + if (isfinite(att.roll) && isfinite(att.pitch) && isfinite(att.yaw)) { + // Broadcast + orb_publish(ORB_ID(vehicle_attitude), pub_att, &att); + + } else { + warnx("NaN in roll/pitch/yaw estimate!"); + } + + perf_end(so3_comp_loop_perf); + } + } + } + + loopcounter++; + } + + thread_running = false; + + return 0; +} diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c new file mode 100755 index 000000000..bf0f49db8 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -0,0 +1,44 @@ +/* + * @file attitude_estimator_so3_comp_params.c + * + * Parameters for SO3 complementary filter + */ + +#include "attitude_estimator_so3_comp_params.h" + +/* This is filter gain for nonlinear SO3 complementary filter */ +PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f); +PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.0f); + +/* offsets in roll, pitch and yaw of sensor plane and body */ +PARAM_DEFINE_FLOAT(ATT_ROLL_OFFS, 0.0f); +PARAM_DEFINE_FLOAT(ATT_PITCH_OFFS, 0.0f); +PARAM_DEFINE_FLOAT(ATT_YAW_OFFS, 0.0f); + +int parameters_init(struct attitude_estimator_ekf_param_handles *h) +{ + /* Filter gain parameters */ + h->Kp = param_find("SO3_COMP_KP"); + h->Ki = param_find("SO3_COMP_KI"); + + /* Attitude offset (WARNING: Do not change if you do not know what exactly this variable wil lchange) */ + h->roll_off = param_find("ATT_ROLL_OFFS"); + h->pitch_off = param_find("ATT_PITCH_OFFS"); + h->yaw_off = param_find("ATT_YAW_OFFS"); + + return OK; +} + +int parameters_update(const struct attitude_estimator_ekf_param_handles *h, struct attitude_estimator_ekf_params *p) +{ + /* Update filter gain */ + param_get(h->Kp, &(p->Kp)); + param_get(h->Ki, &(p->Ki)); + + /* Update attitude offset */ + param_get(h->roll_off, &(p->roll_off)); + param_get(h->pitch_off, &(p->pitch_off)); + param_get(h->yaw_off, &(p->yaw_off)); + + return OK; +} diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h new file mode 100755 index 000000000..2fccec61c --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h @@ -0,0 +1,32 @@ +/* + * @file attitude_estimator_so3_comp_params.h + * + * Parameters for EKF filter + */ + +#include + +struct attitude_estimator_so3_comp_params { + float Kp; + float Ki; + float roll_off; + float pitch_off; + float yaw_off; +}; + +struct attitude_estimator_so3_comp_param_handles { + param_t Kp, Ki; + param_t roll_off, pitch_off, yaw_off; +}; + +/** + * Initialize all parameter handles and values + * + */ +int parameters_init(struct attitude_estimator_so3_comp_param_handles *h); + +/** + * Update all parameters + * + */ +int parameters_update(const struct attitude_estimator_so3_comp_param_handles *h, struct attitude_estimator_so3_comp_params *p); diff --git a/src/modules/attitude_estimator_so3_comp/module.mk b/src/modules/attitude_estimator_so3_comp/module.mk new file mode 100644 index 000000000..92f43d920 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/module.mk @@ -0,0 +1,8 @@ +# +# Attitude estimator (Nonlinear SO3 complementary Filter) +# + +MODULE_COMMAND = attitude_estimator_so3_comp + +SRCS = attitude_estimator_so3_comp_main.cpp \ + attitude_estimator_so3_comp_params.c -- cgit v1.2.3 From 0c3412223b0961798e0fa9c27042132ebdfc0bdb Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Tue, 21 May 2013 16:17:20 +1000 Subject: Fixed few minor bug --- .../attitude_estimator_so3_comp_main.cpp | 6 ++++++ .../attitude_estimator_so3_comp_params.c | 4 ++-- 2 files changed, 8 insertions(+), 2 deletions(-) (limited to 'src') diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 381b0df75..81a5e5b07 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -7,6 +7,7 @@ #include #include #include +#include #include #include #include @@ -44,6 +45,7 @@ static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame +volatile float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki /** * Mainloop of attitude_estimator_so3_comp. @@ -525,6 +527,10 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds float bSq = q1*q1; float cSq = q2*q2; float dSq = q3*q3; + float a = q0; + float b = q1; + float c = q2; + float d = q3; Rot_matrix[0] = aSq + bSq - cSq - dSq; Rot_matrix[1] = 2.0 * (b * c - a * d); diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c index bf0f49db8..158eb1972 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -15,7 +15,7 @@ PARAM_DEFINE_FLOAT(ATT_ROLL_OFFS, 0.0f); PARAM_DEFINE_FLOAT(ATT_PITCH_OFFS, 0.0f); PARAM_DEFINE_FLOAT(ATT_YAW_OFFS, 0.0f); -int parameters_init(struct attitude_estimator_ekf_param_handles *h) +int parameters_init(struct attitude_estimator_so3_comp_param_handles *h) { /* Filter gain parameters */ h->Kp = param_find("SO3_COMP_KP"); @@ -29,7 +29,7 @@ int parameters_init(struct attitude_estimator_ekf_param_handles *h) return OK; } -int parameters_update(const struct attitude_estimator_ekf_param_handles *h, struct attitude_estimator_ekf_params *p) +int parameters_update(const struct attitude_estimator_so3_comp_param_handles *h, struct attitude_estimator_so3_comp_params *p) { /* Update filter gain */ param_get(h->Kp, &(p->Kp)); -- cgit v1.2.3 From 32bace0824ca37c424cc98ecca6ced86cfe10149 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Tue, 21 May 2013 17:52:12 +1000 Subject: I do not know why roll angle is not correct. But system looks okay --- .../attitude_estimator_so3_comp_main.cpp | 72 ++++++++++++---------- 1 file changed, 38 insertions(+), 34 deletions(-) (limited to 'src') diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 81a5e5b07..a8561a078 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -44,8 +44,8 @@ extern "C" __EXPORT int attitude_estimator_so3_comp_main(int argc, char *argv[]) static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ -volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame -volatile float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki +static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame +static float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki /** * Mainloop of attitude_estimator_so3_comp. @@ -135,7 +135,6 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float float recipNorm; float halfvx, halfvy, halfvz; float halfex, halfey, halfez; - float qa, qb, qc; // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { @@ -181,13 +180,10 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); + q0 += (-q1 * gx - q2 * gy - q3 * gz); + q1 += (q0 * gx + q2 * gz - q3 * gy); + q2 += (q0 * gy - q1 * gz + q3 * gx); + q3 += (q0 * gz + q1 * gy - q2 * gx); // Normalise quaternion recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); @@ -203,7 +199,6 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az float hx, hy, bx, bz; float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; float halfex, halfey, halfez; - float qa, qb, qc; // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { @@ -282,13 +277,10 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); + q0 += (-q1 * gx - q2 * gy - q3 * gz); + q1 += (q0 * gx + q2 * gz - q3 * gy); + q2 += (q0 * gy - q1 * gz + q3 * gx); + q3 += (q0 * gz + q1 * gy - q2 * gx); // Normalise quaternion recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); @@ -532,19 +524,19 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds float c = q2; float d = q3; - Rot_matrix[0] = aSq + bSq - cSq - dSq; - Rot_matrix[1] = 2.0 * (b * c - a * d); - Rot_matrix[2] = 2.0 * (a * c + b * d); - Rot_matrix[3] = 2.0 * (b * c + a * d); - Rot_matrix[4] = aSq - bSq + cSq - dSq; - Rot_matrix[5] = 2.0 * (c * d - a * b); - Rot_matrix[6] = 2.0 * (b * d - a * c); - Rot_matrix[7] = 2.0 * (a * b + c * d); - Rot_matrix[8] = aSq - bSq - cSq + dSq; + Rot_matrix[0] = aSq + bSq - cSq - dSq; // 11 + Rot_matrix[1] = 2.0 * (b * c - a * d); // 12 + Rot_matrix[2] = 2.0 * (a * c + b * d); // 13 + Rot_matrix[3] = 2.0 * (b * c + a * d); // 21 + Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22 + Rot_matrix[5] = 2.0 * (c * d - a * b); // 23 + Rot_matrix[6] = 2.0 * (b * d - a * c); // 31 + Rot_matrix[7] = 2.0 * (a * b + c * d); // 32 + Rot_matrix[8] = aSq - bSq - cSq + dSq; // 33 - /* Compute Euler angle */ - float theta = asinf(-Rot_matrix[6]); - euler[1] = theta; + /* FIXME : Work around this later... + float theta = asinf(-Rot_matrix[6]); // -r_{31} + euler[1] = theta; // pitch angle if(fabsf(theta - M_PI_2_F) < 1.0e-3f){ euler[0] = 0.0f; @@ -556,6 +548,16 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); euler[2] = atan2f(Rot_matrix[3], Rot_matrix[0]); } + */ + + float q1q1 = q1*q1; + float q2q2 = q2*q2; + float q3q3 = q3*q3; + + euler[0] = atan2f(2*(q0*q1 + q2*q3),1-2*(q1q1+q2q2)); // roll + euler[1] = asinf(2*(q0*q2 - q3*q1)); // pitch + euler[2] = atan2f(2*(q0*q3 + q1*q2),1-2*(q2q2 + q3q3)); // yaw + /* swap values for next iteration, check for fatal inputs */ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { @@ -577,10 +579,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds att.pitch = euler[1] - so3_comp_params.pitch_off; att.yaw = euler[2] - so3_comp_params.yaw_off; - /* FIXME : This can be a problem for rate controller. Rate in body or inertial? - att.rollspeed = x_aposteriori[0]; - att.pitchspeed = x_aposteriori[1]; - att.yawspeed = x_aposteriori[2]; + /* FIXME : This can be a problem for rate controller. Rate in body or inertial? */ + att.rollspeed = q1; + att.pitchspeed = q2; + att.yawspeed = q3; + + /* att.rollacc = x_aposteriori[3]; att.pitchacc = x_aposteriori[4]; att.yawacc = x_aposteriori[5]; -- cgit v1.2.3 From f547044203f81061a9302f1e5c4fcdf2ef73cac2 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 22 May 2013 00:09:25 +1000 Subject: Roll pitch yaw should be verified again --- .../attitude_estimator_so3_comp_main.cpp | 186 ++++++++++----------- .../attitude_estimator_so3_comp_params.c | 2 +- 2 files changed, 94 insertions(+), 94 deletions(-) (limited to 'src') diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index a8561a078..ff63640ef 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -139,52 +139,52 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Estimated direction of gravity and vector perpendicular to magnetic flux - halfvx = q1 * q3 - q0 * q2; - halfvy = q0 * q1 + q2 * q3; - halfvz = q0 * q0 - 0.5f + q3 * q3; + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Estimated direction of gravity and vector perpendicular to magnetic flux + halfvx = q1 * q3 - q0 * q2; + halfvy = q0 * q1 + q2 * q3; + halfvz = q0 * q0 - 0.5f + q3 * q3; - // Error is sum of cross product between estimated and measured direction of gravity - halfex = (ay * halfvz - az * halfvy); - halfey = (az * halfvx - ax * halfvz); - halfez = (ax * halfvy - ay * halfvx); - - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * dt; // integral error scaled by Ki - integralFBy += twoKi * halfey * dt; - integralFBz += twoKi * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } + // Error is sum of cross product between estimated and measured direction of gravity + halfex = (ay * halfvz - az * halfvy); + halfey = (az * halfvx - ax * halfvz); + halfez = (ax * halfvy - ay * halfvx); + + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + integralFBx += twoKi * halfex * dt; // integral error scaled by Ki + integralFBy += twoKi * halfey * dt; + integralFBz += twoKi * halfez * dt; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } + else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; } // Integrate rate of change of quaternion gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - q0 += (-q1 * gx - q2 * gy - q3 * gz); + q0 +=(-q1 * gx - q2 * gy - q3 * gz); q1 += (q0 * gx + q2 * gz - q3 * gy); q2 += (q0 * gy - q1 * gz + q3 * gx); q3 += (q0 * gz + q1 * gy - q2 * gx); - + // Normalise quaternion recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); q0 *= recipNorm; @@ -209,17 +209,17 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; - // Normalise magnetometer measurement - recipNorm = invSqrt(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; + // Normalise magnetometer measurement + recipNorm = invSqrt(mx * mx + my * my + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; // Auxiliary variables to avoid repeated arithmetic q0q0 = q0 * q0; @@ -239,45 +239,45 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az bx = sqrt(hx * hx + hy * hy); bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); - // Estimated direction of gravity and magnetic field - halfvx = q1q3 - q0q2; - halfvy = q0q1 + q2q3; - halfvz = q0q0 - 0.5f + q3q3; + // Estimated direction of gravity and magnetic field + halfvx = q1q3 - q0q2; + halfvy = q0q1 + q2q3; + halfvz = q0q0 - 0.5f + q3q3; halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); - // Error is sum of cross product between estimated direction and measured direction of field vectors - halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); - halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); - halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); - - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * dt; // integral error scaled by Ki - integralFBy += twoKi * halfey * dt; - integralFBz += twoKi * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } + // Error is sum of cross product between estimated direction and measured direction of field vectors + halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); + halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); + halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); + + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + integralFBx += twoKi * halfex * dt; // integral error scaled by Ki + integralFBy += twoKi * halfey * dt; + integralFBz += twoKi * halfez * dt; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } + else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; } // Integrate rate of change of quaternion gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - q0 += (-q1 * gx - q2 * gy - q3 * gz); + q0 +=(-q1 * gx - q2 * gy - q3 * gz); q1 += (q0 * gx + q2 * gz - q3 * gy); q2 += (q0 * gy - q1 * gz + q3 * gx); q3 += (q0 * gz + q1 * gy - q2 * gx); @@ -515,24 +515,28 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],acc[0],acc[1],acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); - float aSq = q0*q0; - float bSq = q1*q1; - float cSq = q2*q2; - float dSq = q3*q3; + float aSq = q0*q0; // 1 + float bSq = q1*q1; // 2 + float cSq = q2*q2; // 3 + float dSq = q3*q3; // 4 float a = q0; float b = q1; float c = q2; float d = q3; - Rot_matrix[0] = aSq + bSq - cSq - dSq; // 11 - Rot_matrix[1] = 2.0 * (b * c - a * d); // 12 - Rot_matrix[2] = 2.0 * (a * c + b * d); // 13 - Rot_matrix[3] = 2.0 * (b * c + a * d); // 21 - Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22 - Rot_matrix[5] = 2.0 * (c * d - a * b); // 23 - Rot_matrix[6] = 2.0 * (b * d - a * c); // 31 - Rot_matrix[7] = 2.0 * (a * b + c * d); // 32 - Rot_matrix[8] = aSq - bSq - cSq + dSq; // 33 + Rot_matrix[0] = 2*aSq - 1 + 2*bSq; // 11 + //Rot_matrix[1] = 2.0 * (b * c - a * d); // 12 + //Rot_matrix[2] = 2.0 * (a * c + b * d); // 13 + Rot_matrix[3] = 2.0 * (b * c - a * d); // 21 + //Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22 + //Rot_matrix[5] = 2.0 * (c * d - a * b); // 23 + Rot_matrix[6] = 2.0 * (b * d + a * c); // 31 + Rot_matrix[7] = 2.0 * (c * d - a * b); // 32 + Rot_matrix[8] = 2*aSq - 1 + 2*dSq; // 33 + + //euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); + //euler[1] = asinf(-Rot_matrix[6]); + //euler[2] = atan2f(Rot_matrix[3],Rot_matrix[0]); /* FIXME : Work around this later... float theta = asinf(-Rot_matrix[6]); // -r_{31} @@ -550,13 +554,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds } */ - float q1q1 = q1*q1; - float q2q2 = q2*q2; - float q3q3 = q3*q3; - - euler[0] = atan2f(2*(q0*q1 + q2*q3),1-2*(q1q1+q2q2)); // roll - euler[1] = asinf(2*(q0*q2 - q3*q1)); // pitch - euler[2] = atan2f(2*(q0*q3 + q1*q2),1-2*(q2q2 + q3q3)); // yaw + euler[0] = atan2f(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2)); + euler[1] = asinf(2*(q0*q2-q3*q1)); + euler[2] = atan2f(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); /* swap values for next iteration, check for fatal inputs */ diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c index 158eb1972..068e4340a 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -7,7 +7,7 @@ #include "attitude_estimator_so3_comp_params.h" /* This is filter gain for nonlinear SO3 complementary filter */ -PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f); +PARAM_DEFINE_FLOAT(SO3_COMP_KP, 0.5f); PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.0f); /* offsets in roll, pitch and yaw of sensor plane and body */ -- cgit v1.2.3 From 364d1a06e308334915c5e7e54e1c6f15b11e5b2e Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 22 May 2013 13:03:14 +1000 Subject: To use freeIMU processing visualization tool, I have implemented float number transmission over uart (default /dev/ttyS2, 115200) But this not tested yet. I should. --- .../attitude_estimator_so3_comp_main.cpp | 273 +++++++++++++++------ 1 file changed, 196 insertions(+), 77 deletions(-) (limited to 'src') diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index ff63640ef..ac898eefc 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -47,6 +47,10 @@ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thr static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame static float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki +//! Serial packet related +static int uart; +static int baudrate; + /** * Mainloop of attitude_estimator_so3_comp. */ @@ -63,7 +67,9 @@ usage(const char *reason) if (reason) fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: attitude_estimator_so3_comp {start|stop|status} [-p ]\n\n"); + fprintf(stderr, "usage: attitude_estimator_so3_comp {start|stop|status} [-d ] [-b ]\n" + "-d and -b options are for separate visualization with raw data (quaternion packet) transfer\n" + "ex) attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200\n"); exit(1); } @@ -80,6 +86,8 @@ int attitude_estimator_so3_comp_main(int argc, char *argv[]) if (argc < 1) usage("missing command"); + + if (!strcmp(argv[1], "start")) { if (thread_running) { @@ -94,12 +102,18 @@ int attitude_estimator_so3_comp_main(int argc, char *argv[]) SCHED_PRIORITY_MAX - 5, 12400, attitude_estimator_so3_comp_thread_main, - (argv) ? (const char **)&argv[2] : (const char **)NULL); + (const char **)argv); exit(0); } if (!strcmp(argv[1], "stop")) { thread_should_exit = true; + + while(thread_running){ + usleep(200000); + printf("."); + } + printf("terminated."); exit(0); } @@ -121,76 +135,18 @@ int attitude_estimator_so3_comp_main(int argc, char *argv[]) //--------------------------------------------------------------------------------------------------- // Fast inverse square-root // See: http://en.wikipedia.org/wiki/Fast_inverse_square_root -float invSqrt(float x) { - float halfx = 0.5f * x; - float y = x; - long i = *(long*)&y; - i = 0x5f3759df - (i>>1); - y = *(float*)&i; - y = y * (1.5f - (halfx * y * y)); - return y; -} - -void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az, float twoKp, float twoKi, float dt) { - float recipNorm; - float halfvx, halfvy, halfvz; - float halfex, halfey, halfez; - - // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) - if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Estimated direction of gravity and vector perpendicular to magnetic flux - halfvx = q1 * q3 - q0 * q2; - halfvy = q0 * q1 + q2 * q3; - halfvz = q0 * q0 - 0.5f + q3 * q3; - - // Error is sum of cross product between estimated and measured direction of gravity - halfex = (ay * halfvz - az * halfvy); - halfey = (az * halfvx - ax * halfvz); - halfez = (ax * halfvy - ay * halfvx); - - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * dt; // integral error scaled by Ki - integralFBy += twoKi * halfey * dt; - integralFBz += twoKi * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; - } - - // Integrate rate of change of quaternion - gx *= (0.5f * dt); // pre-multiply common factors - gy *= (0.5f * dt); - gz *= (0.5f * dt); - q0 +=(-q1 * gx - q2 * gy - q3 * gz); - q1 += (q0 * gx + q2 * gz - q3 * gy); - q2 += (q0 * gy - q1 * gz + q3 * gx); - q3 += (q0 * gz + q1 * gy - q2 * gx); - - // Normalise quaternion - recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; +float invSqrt(float number) { + volatile long i; + volatile float x, y; + volatile const float f = 1.5F; + + x = number * 0.5F; + y = number; + i = * (( long * ) &y); + i = 0x5f375a86 - ( i >> 1 ); + y = * (( float * ) &i); + y = y * ( f - ( x * y * y ) ); + return y; } void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { @@ -202,7 +158,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az, twoKp, twoKi, dt); + //MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az, twoKp, twoKi, dt); return; } @@ -290,6 +246,117 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az q3 *= recipNorm; } +void send_uart_byte(char c) +{ + write(uart,&c,1); +} + +void send_uart_bytes(uint8_t *data, int length) +{ + write(uart,data,(size_t)(sizeof(uint8_t)*length)); +} + +void send_uart_float(float f) { + uint8_t * b = (uint8_t *) &f; + + //! Assume float is 4-bytes + for(int i=0; i<4; i++) { + + uint8_t b1 = (b[i] >> 4) & 0x0f; + uint8_t b2 = (b[i] & 0x0f); + + uint8_t c1 = (b1 < 10) ? ('0' + b1) : 'A' + b1 - 10; + uint8_t c2 = (b2 < 10) ? ('0' + b2) : 'A' + b2 - 10; + + send_uart_bytes(&c1,1); + send_uart_bytes(&c2,1); + } +} + +void send_uart_float_arr(float *arr, int length) +{ + for(int i=0;i, default : /dev/ttyS2 + //! -b , default : 115200 + while ((ch = getopt(argc,argv,"d:b:")) != EOF){ + switch(ch){ + case 'b': + baudrate = strtoul(optarg, NULL, 10); + if(baudrate == 0) + printf("invalid baud rate '%s'",optarg); + break; + case 'd': + device_name = optarg; + debug_mode = true; + break; + default: + usage("invalid argument"); + } + } + + if(debug_mode){ + uart = open_uart(baudrate, device_name, &uart_config_original, &usb_uart); + if (uart < 0) + printf("could not open %s", device_name); + } + // print text printf("Nonlinear SO3 Attitude Estimator initialized..\n\n"); fflush(stdout); @@ -554,9 +658,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds } */ - euler[0] = atan2f(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2)); - euler[1] = asinf(2*(q0*q2-q3*q1)); - euler[2] = atan2f(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3)); + euler[2] = atan2f(2*(q1*q2-q0*q3),2*(q0*q0+q1*q1)-1); + euler[1]= -asinf(2*(q1*q3+q0*q2)); + euler[0] = atan2f(2*(q2*q3-q0*q1),2*(q0*q0+q3*q3)-1); /* swap values for next iteration, check for fatal inputs */ @@ -607,7 +711,18 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds } perf_end(so3_comp_loop_perf); - } + + if(debug_mode) + { + float quat[4]; + quat[0] = q0; + quat[1] = q1; + quat[2] = q2; + quat[3] = q3; + send_uart_float_arr(quat,4); + send_uart_byte('\n'); + } + }// else } } @@ -616,5 +731,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds thread_running = false; + /* Reset the UART flags to original state */ + if (!usb_uart) + tcsetattr(uart, TCSANOW, &uart_config_original); + return 0; } -- cgit v1.2.3 From 4bf05054218efab3b3dc182939f32a96f5ed1673 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Thu, 23 May 2013 16:12:29 +1000 Subject: Test flight has been performed with nonlinear SO(3) attitude estimator. Here are few observations: - When the system initialized, roll angle is initially reversed. As filter converged, it becomes normal. - I put a negative sign on roll, yaw. It should naturally has right sign, but I do not know why for now. Let me investigate again. - Gain : I do not know what gain is good for quadrotor flight. Let me take a look Ardupilot gain in the later. Anyway, you can fly with this attitude estimator. --- nuttx/configs/px4fmu/nsh/defconfig | 6 +- .../attitude_estimator_so3_comp_main.cpp | 224 +++++++++++---------- 2 files changed, 116 insertions(+), 114 deletions(-) (limited to 'src') diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 02e224302..94d99112e 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -248,7 +248,7 @@ CONFIG_SERIAL_TERMIOS=y CONFIG_SERIAL_CONSOLE_REINIT=y CONFIG_STANDARD_SERIAL=y -CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART1_SERIAL_CONSOLE=n CONFIG_USART2_SERIAL_CONSOLE=n CONFIG_USART3_SERIAL_CONSOLE=n CONFIG_UART4_SERIAL_CONSOLE=n @@ -561,7 +561,7 @@ CONFIG_START_MONTH=1 CONFIG_START_DAY=1 CONFIG_GREGORIAN_TIME=n CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y +CONFIG_DEV_CONSOLE=n CONFIG_DEV_LOWCONSOLE=n CONFIG_MUTEX_TYPES=n CONFIG_PRIORITY_INHERITANCE=y @@ -925,7 +925,7 @@ CONFIG_USBDEV_TRACE_NRECORDS=512 # Size of the serial receive/transmit buffers. Default 256. # CONFIG_CDCACM=y -CONFIG_CDCACM_CONSOLE=n +CONFIG_CDCACM_CONSOLE=y #CONFIG_CDCACM_EP0MAXPACKET CONFIG_CDCACM_EPINTIN=1 #CONFIG_CDCACM_EPINTIN_FSSIZE diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index ac898eefc..28fcf0369 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -44,8 +44,9 @@ extern "C" __EXPORT int attitude_estimator_so3_comp_main(int argc, char *argv[]) static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ -static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame -static float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki +static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */ +static float gyro_bias[3] = {0.0f, 0.0f, 0.0f}; /** bias estimation */ +static float gravity_vector[3] = {0.0f,0.0f,0.0f}; /** estimated gravity vector */ //! Serial packet related static int uart; @@ -151,82 +152,91 @@ float invSqrt(float number) { void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { float recipNorm; - float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; - float hx, hy, bx, bz; - float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; - float halfex, halfey, halfez; - - // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) + float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; + float halfex = 0.0f, halfey = 0.0f, halfez = 0.0f; + + // Auxiliary variables to avoid repeated arithmetic + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; + + //! If magnetometer measurement is available, use it. if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - //MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az, twoKp, twoKi, dt); - return; + float hx, hy, bx, bz; + float halfwx, halfwy, halfwz; + + // Normalise magnetometer measurement + recipNorm = invSqrt(mx * mx + my * my + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; + + // Reference direction of Earth's magnetic field + hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); + hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); + bx = sqrt(hx * hx + hy * hy); + bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); + + // Estimated direction of magnetic field + halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); + halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); + halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); + + // Error is sum of cross product between estimated direction and measured direction of field vectors + halfex += (my * halfwz - mz * halfwy); + halfey += (mz * halfwx - mx * halfwz); + halfez += (mx * halfwy - my * halfwx); } // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Normalise magnetometer measurement - recipNorm = invSqrt(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; - - // Auxiliary variables to avoid repeated arithmetic - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; - - // Reference direction of Earth's magnetic field - hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); - hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); - bx = sqrt(hx * hx + hy * hy); - bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); - - // Estimated direction of gravity and magnetic field - halfvx = q1q3 - q0q2; - halfvy = q0q1 + q2q3; - halfvz = q0q0 - 0.5f + q3q3; - halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); - halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); - halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); + float halfvx, halfvy, halfvz; - // Error is sum of cross product between estimated direction and measured direction of field vectors - halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); - halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); - halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); - - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * dt; // integral error scaled by Ki - integralFBy += twoKi * halfey * dt; - integralFBz += twoKi * halfez * dt; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Estimated direction of gravity and magnetic field + halfvx = q1q3 - q0q2; + halfvy = q0q1 + q2q3; + halfvz = q0q0 - 0.5f + q3q3; + + // Error is sum of cross product between estimated direction and measured direction of field vectors + halfex += ay * halfvz - az * halfvy; + halfey += az * halfvx - ax * halfvz; + halfez += ax * halfvy - ay * halfvx; } - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; + // Apply feedback only when valid data has been gathered from the accelerometer or magnetometer + if(halfex != 0.0f && halfey != 0.0f && halfez != 0.0f) { + // Compute and apply integral feedback if enabled + if(twoKi > 0.0f) { + gyro_bias[0] += twoKi * halfex * dt; // integral error scaled by Ki + gyro_bias[1] += twoKi * halfey * dt; + gyro_bias[2] += twoKi * halfez * dt; + gx += gyro_bias[0]; // apply integral feedback + gy += gyro_bias[1]; + gz += gyro_bias[2]; + } + else { + gyro_bias[0] = 0.0f; // prevent integral windup + gyro_bias[1] = 0.0f; + gyro_bias[2] = 0.0f; + } + + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; } // Integrate rate of change of quaternion @@ -309,11 +319,11 @@ int open_uart(int baud, const char *uart_name, struct termios *uart_config_origi case 460800: speed = B460800; break; case 921600: speed = B921600; break; default: - fprintf(stderr, "ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud); + printf("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud); return -EINVAL; } - printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud); + printf("[so3_comp_filt] UART is %s, baudrate is %d\n", uart_name, baud); uart = open(uart_name, O_RDWR | O_NOCTTY); /* Try to set baud rate */ @@ -321,11 +331,11 @@ int open_uart(int baud, const char *uart_name, struct termios *uart_config_origi int termios_state; *is_usb = false; - /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */ + /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */ if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/console") != OK) { /* Back up the original uart configuration to restore it after exit */ if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { - fprintf(stderr, "ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state); + printf("ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state); close(uart); return -1; } @@ -338,14 +348,14 @@ int open_uart(int baud, const char *uart_name, struct termios *uart_config_origi /* Set baud rate */ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { - fprintf(stderr, "ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state); + printf("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state); close(uart); return -1; } if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { - fprintf(stderr, "ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name); + printf("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name); close(uart); return -1; } @@ -420,9 +430,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds } if(debug_mode){ + printf("Opening debugging port for 3D visualization\n"); uart = open_uart(baudrate, device_name, &uart_config_original, &usb_uart); if (uart < 0) printf("could not open %s", device_name); + else + printf("Open port success\n"); } // print text @@ -638,30 +651,22 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds Rot_matrix[7] = 2.0 * (c * d - a * b); // 32 Rot_matrix[8] = 2*aSq - 1 + 2*dSq; // 33 + gravity_vector[0] = 2*(q1*q3-q0*q2); + gravity_vector[1] = 2*(q0*q1+q2*q3); + gravity_vector[2] = aSq - bSq - cSq + dSq; + //euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); - //euler[1] = asinf(-Rot_matrix[6]); + //euler[1] = -asinf(Rot_matrix[6]); //euler[2] = atan2f(Rot_matrix[3],Rot_matrix[0]); - /* FIXME : Work around this later... - float theta = asinf(-Rot_matrix[6]); // -r_{31} - euler[1] = theta; // pitch angle - - if(fabsf(theta - M_PI_2_F) < 1.0e-3f){ - euler[0] = 0.0f; - euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]); - } else if (fabsf(theta + M_PI_2_F) < 1.0e-3f) { - euler[0] = 0.0f; - euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]); - } else { - euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); - euler[2] = atan2f(Rot_matrix[3], Rot_matrix[0]); - } - */ - - euler[2] = atan2f(2*(q1*q2-q0*q3),2*(q0*q0+q1*q1)-1); - euler[1]= -asinf(2*(q1*q3+q0*q2)); - euler[0] = atan2f(2*(q2*q3-q0*q1),2*(q0*q0+q3*q3)-1); - + // Euler angle directly from quaternion. + euler[0] = -atan2f(gravity_vector[1], sqrtf(gravity_vector[0]*gravity_vector[0] + gravity_vector[2]*gravity_vector[2])); // roll + euler[1] = atan2f(gravity_vector[0], sqrtf(gravity_vector[1]*gravity_vector[1] + gravity_vector[2]*gravity_vector[2])); // pitch + euler[2] = -atan2f(2*(q1*q2-q0*q3),2*(q0*q0+q1*q1)-1); // yaw + + //euler[2] = atan2(2 * q1*q2 - 2 * q0*q3, 2 * q0*q0 + 2 * q1*q1 - 1); // psi + //euler[1] = -asin(2 * q1*q3 + 2 * q0*q2); // theta + //euler[0] = atan2(2 * q2*q3 - 2 * q0*q1, 2 * q0*q0 + 2 * q3*q3 - 1); // phi /* swap values for next iteration, check for fatal inputs */ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { @@ -684,19 +689,15 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds att.yaw = euler[2] - so3_comp_params.yaw_off; /* FIXME : This can be a problem for rate controller. Rate in body or inertial? */ - att.rollspeed = q1; - att.pitchspeed = q2; - att.yawspeed = q3; + att.rollspeed = gyro[0]; + att.pitchspeed = gyro[1]; + att.yawspeed = gyro[2]; + att.rollacc = 0; + att.pitchacc = 0; + att.yawacc = 0; - /* - att.rollacc = x_aposteriori[3]; - att.pitchacc = x_aposteriori[4]; - att.yawacc = x_aposteriori[5]; - */ - - //att.yawspeed =z_k[2] ; - /* copy offsets */ - //memcpy(&att.rate_offsets, &(x_aposteriori[3]), sizeof(att.rate_offsets)); + /* TODO: Bias estimation required */ + memcpy(&att.rate_offsets, &(gyro_bias), sizeof(att.rate_offsets)); /* copy rotation matrix */ memcpy(&att.R, Rot_matrix, sizeof(Rot_matrix)); @@ -712,6 +713,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds perf_end(so3_comp_loop_perf); + //! This will print out debug packet to visualization software if(debug_mode) { float quat[4]; @@ -722,12 +724,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds send_uart_float_arr(quat,4); send_uart_byte('\n'); } - }// else + } } } loopcounter++; - } + }// while thread_running = false; -- cgit v1.2.3 From e2113526043f82700c2cff5d16d9e3a4dee089c7 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 25 May 2013 22:15:56 +0400 Subject: sdlog2 logger app added. New flexible log format, compatible with APM. --- makefiles/config_px4fmu_default.mk | 1 + src/modules/sdlog2/module.mk | 43 ++ src/modules/sdlog2/sdlog2.c | 890 +++++++++++++++++++++++++++++++++ src/modules/sdlog2/sdlog2_format.h | 98 ++++ src/modules/sdlog2/sdlog2_messages.h | 82 +++ src/modules/sdlog2/sdlog2_ringbuffer.c | 141 ++++++ src/modules/sdlog2/sdlog2_ringbuffer.h | 68 +++ 7 files changed, 1323 insertions(+) create mode 100644 src/modules/sdlog2/module.mk create mode 100644 src/modules/sdlog2/sdlog2.c create mode 100644 src/modules/sdlog2/sdlog2_format.h create mode 100644 src/modules/sdlog2/sdlog2_messages.h create mode 100644 src/modules/sdlog2/sdlog2_ringbuffer.c create mode 100644 src/modules/sdlog2/sdlog2_ringbuffer.h (limited to 'src') diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index 1e4d59266..b6fa4014a 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -78,6 +78,7 @@ MODULES += modules/multirotor_pos_control # Logging # MODULES += modules/sdlog +MODULES += modules/sdlog2 # # Library modules diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk new file mode 100644 index 000000000..5a9936635 --- /dev/null +++ b/src/modules/sdlog2/module.mk @@ -0,0 +1,43 @@ +############################################################################ +# +# Copyright (c) 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# sdlog2 Application +# + +MODULE_COMMAND = sdlog2 +# The main thread only buffers to RAM, needs a high priority +MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30" + +SRCS = sdlog2.c \ + sdlog2_ringbuffer.c diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c new file mode 100644 index 000000000..38b57082f --- /dev/null +++ b/src/modules/sdlog2/sdlog2.c @@ -0,0 +1,890 @@ +/**************************************************************************** + * + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier + * Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2.c + * + * Simple SD logger for flight data. Buffers new sensor values and + * does the heavy SD I/O in a low-priority worker thread. + * + * @author Lorenz Meier + * @author Anton Babushkin + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include "sdlog2_ringbuffer.h" +#include "sdlog2_messages.h" + +static bool thread_should_exit = false; /**< Deamon exit flag */ +static bool thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ +static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */ +static const int LOG_BUFFER_SIZE = 2048; +static const int MAX_WRITE_CHUNK = 1024; + +static const char *mountpoint = "/fs/microsd"; +int log_file = -1; +int mavlink_fd = -1; +struct sdlog2_logbuffer lb; + +/* mutex / condition to synchronize threads */ +pthread_mutex_t logbuffer_mutex; +pthread_cond_t logbuffer_cond; + +/** + * System state vector log buffer writing + */ +static void *sdlog2_logbuffer_write_thread(void *arg); + +/** + * Create the thread to write the system vector + */ +pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf); + +/** + * Write a header to log file: list of message formats + */ +void sdlog2_write_formats(int fd); + +/** + * SD log management function. + */ +__EXPORT int sdlog2_main(int argc, char *argv[]); + +/** + * Mainloop of sd log deamon. + */ +int sdlog2_thread_main(int argc, char *argv[]); + +/** + * Print the correct usage. + */ +static void usage(const char *reason); + +static int file_exist(const char *filename); + +static int file_copy(const char *file_old, const char *file_new); + +static void handle_command(struct vehicle_command_s *cmd); + +/** + * Print the current status. + */ +static void print_sdlog2_status(void); + +/** + * Create folder for current logging session. + */ +static int create_logfolder(char *folder_path); + +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + + errx(1, "usage: sdlog2 {start|stop|status} [-s ]\n\n"); +} + +unsigned long log_bytes_written = 0; +uint64_t starttime = 0; + +/* logging on or off, default to true */ +bool logging_enabled = true; + +/** + * The sd log deamon app only briefly exists to start + * the background job. The stack size assigned in the + * Makefile does only apply to this management task. + * + * The actual stack size should be set in the call + * to task_spawn(). + */ +int sdlog2_main(int argc, char *argv[]) +{ + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + printf("sdlog2 already running\n"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + deamon_task = task_spawn("sdlog2", + SCHED_DEFAULT, + SCHED_PRIORITY_DEFAULT - 30, + 4096, + sdlog2_thread_main, + (const char **)argv); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + if (!thread_running) { + printf("\tsdlog2 is not started\n"); + } + + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + print_sdlog2_status(); + + } else { + printf("\tsdlog2 not started\n"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +int create_logfolder(char *folder_path) +{ + /* make folder on sdcard */ + uint16_t foldernumber = 1; // start with folder 0001 + int mkdir_ret; + + /* look for the next folder that does not exist */ + while (foldernumber < MAX_NO_LOGFOLDER) { + /* set up file path: e.g. /mnt/sdcard/sensorfile0001.txt */ + sprintf(folder_path, "%s/session%04u", mountpoint, foldernumber); + mkdir_ret = mkdir(folder_path, S_IRWXU | S_IRWXG | S_IRWXO); + /* the result is -1 if the folder exists */ + + if (mkdir_ret == 0) { + /* folder does not exist, success */ + + /* copy parser script file */ + // TODO + /* + char mfile_out[100]; + sprintf(mfile_out, "%s/session%04u/run_to_plot_data.m", mountpoint, foldernumber); + int ret = file_copy(mfile_in, mfile_out); + + if (!ret) { + warnx("copied m file to %s", mfile_out); + + } else { + warnx("failed copying m file from %s to\n %s", mfile_in, mfile_out); + } + */ + + break; + + } else if (mkdir_ret == -1) { + /* folder exists already */ + foldernumber++; + continue; + + } else { + warn("failed creating new folder"); + return -1; + } + } + + if (foldernumber >= MAX_NO_LOGFOLDER) { + /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */ + warn("all %d possible folders exist already", MAX_NO_LOGFOLDER); + return -1; + } + + return 0; +} + +static void * +sdlog2_logbuffer_write_thread(void *arg) +{ + /* set name */ + prctl(PR_SET_NAME, "sdlog2 microSD I/O", 0); + + struct sdlog2_logbuffer *logbuf = (struct sdlog2_logbuffer *)arg; + + int poll_count = 0; + + void *read_ptr; + int n = 0; + + while (!thread_should_exit) { + + /* make sure threads are synchronized */ + pthread_mutex_lock(&logbuffer_mutex); + + /* update read pointer if needed */ + if (n > 0) { + sdlog2_logbuffer_mark_read(&lb, n); + } + + /* only wait if no data is available to process */ + if (sdlog2_logbuffer_is_empty(logbuf)) { + /* blocking wait for new data at this line */ + pthread_cond_wait(&logbuffer_cond, &logbuffer_mutex); + } + + /* only get pointer to thread-safe data, do heavy I/O a few lines down */ + n = sdlog2_logbuffer_get_ptr(logbuf, &read_ptr); + + /* continue */ + pthread_mutex_unlock(&logbuffer_mutex); + + if (n > 0) { + /* do heavy IO here */ + if (n > MAX_WRITE_CHUNK) + n = MAX_WRITE_CHUNK; + + n = write(log_file, read_ptr, n); + + if (n > 0) { + log_bytes_written += n; + } + } + + if (poll_count % 100 == 0) { + fsync(log_file); + } + + poll_count++; + } + + fsync(log_file); + + return OK; +} + +pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf) +{ + pthread_attr_t receiveloop_attr; + pthread_attr_init(&receiveloop_attr); + + struct sched_param param; + /* low priority, as this is expensive disk I/O */ + param.sched_priority = SCHED_PRIORITY_DEFAULT - 40; + (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); + + pthread_attr_setstacksize(&receiveloop_attr, 2048); + + pthread_t thread; + pthread_create(&thread, &receiveloop_attr, sdlog2_logbuffer_write_thread, logbuf); + return thread; + + // XXX we have to destroy the attr at some point +} + +void sdlog2_write_formats(int fd) +{ + /* construct message format packet */ + struct { + LOG_PACKET_HEADER; + struct log_format_s body; + } log_format_packet = { + LOG_PACKET_HEADER_INIT(LOG_FORMAT_MSG), + }; + + /* fill message format packet for each format and write to log */ + int i; + + for (i = 0; i < log_formats_num; i++) { + log_format_packet.body = log_formats[i]; + write(fd, &log_format_packet, sizeof(log_format_packet)); + } + + fsync(fd); +} + +int sdlog2_thread_main(int argc, char *argv[]) +{ + mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); + + if (mavlink_fd < 0) { + warnx("ERROR: Failed to open MAVLink log stream, start mavlink app first.\n"); + } + + /* log every n'th value (skip three per default) */ + int skip_value = 3; + + /* work around some stupidity in task_create's argv handling */ + argc -= 2; + argv += 2; + int ch; + + while ((ch = getopt(argc, argv, "s:r")) != EOF) { + switch (ch) { + case 's': { + /* log only every n'th (gyro clocked) value */ + unsigned s = strtoul(optarg, NULL, 10); + + if (s < 1 || s > 250) { + errx(1, "Wrong skip value of %d, out of range (1..250)\n", s); + + } else { + skip_value = s; + } + } + break; + + case 'r': + /* log only on request, disable logging per default */ + logging_enabled = false; + break; + + case '?': + if (optopt == 'c') { + warnx("Option -%c requires an argument.\n", optopt); + + } else if (isprint(optopt)) { + warnx("Unknown option `-%c'.\n", optopt); + + } else { + warnx("Unknown option character `\\x%x'.\n", optopt); + } + + default: + usage("unrecognized flag"); + errx(1, "exiting."); + } + } + + if (file_exist(mountpoint) != OK) { + errx(1, "logging mount point %s not present, exiting.", mountpoint); + } + + char folder_path[64]; + + if (create_logfolder(folder_path)) + errx(1, "unable to create logging folder, exiting."); + + /* string to hold the path to the sensorfile */ + char path_buf[64] = ""; + + /* only print logging path, important to find log file later */ + warnx("logging to directory %s\n", folder_path); + + /* set up file path: e.g. /mnt/sdcard/session0001/actuator_controls0.bin */ + sprintf(path_buf, "%s/%s.bin", folder_path, "log"); + + if (0 == (log_file = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC))) { + errx(1, "opening %s failed.\n", path_buf); + } + + /* write log messages formats */ + sdlog2_write_formats(log_file); + + /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ + /* number of messages */ + const ssize_t fdsc = 25; + /* Sanity check variable and index */ + ssize_t fdsc_count = 0; + /* file descriptors to wait for */ + struct pollfd fds[fdsc]; + + /* warning! using union here to save memory, elements should be used separately! */ + union { + struct sensor_combined_s raw; + struct vehicle_attitude_s att; + struct vehicle_attitude_setpoint_s att_sp; + struct actuator_outputs_s act_outputs; + struct actuator_controls_s act_controls; + struct actuator_controls_effective_s act_controls_effective; + struct vehicle_command_s cmd; + struct vehicle_local_position_s local_pos; + struct vehicle_global_position_s global_pos; + struct vehicle_gps_position_s gps_pos; + struct vehicle_vicon_position_s vicon_pos; + struct optical_flow_s flow; + struct battery_status_s batt; + struct differential_pressure_s diff_pres; + struct airspeed_s airspeed; + } buf; + memset(&buf, 0, sizeof(buf)); + + struct { + int cmd_sub; + int sensor_sub; + int att_sub; + int att_sp_sub; + int act_0_sub; + int controls_0_sub; + int controls_effective_0_sub; + int local_pos_sub; + int global_pos_sub; + int gps_pos_sub; + int vicon_pos_sub; + int flow_sub; + int batt_sub; + int diff_pres_sub; + int airspeed_sub; + } subs; + + /* log message buffer: header + body */ + struct { + LOG_PACKET_HEADER; + union { + struct log_TS_s log_TS; + struct log_ATT_s log_ATT; + struct log_RAW_s log_RAW; + } body; + } log_msg = { + LOG_PACKET_HEADER_INIT(0) + }; + memset(&log_msg.body, 0, sizeof(log_msg.body)); + + /* --- MANAGEMENT - LOGGING COMMAND --- */ + /* subscribe to ORB for vehicle command */ + subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); + fds[fdsc_count].fd = subs.cmd_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- GPS POSITION --- */ + /* subscribe to ORB for global position */ + subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); + fds[fdsc_count].fd = subs.gps_pos_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- SENSORS RAW VALUE --- */ + /* subscribe to ORB for sensors raw */ + subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); + fds[fdsc_count].fd = subs.sensor_sub; + /* do not rate limit, instead use skip counter (aliasing on rate limit) */ + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- ATTITUDE VALUE --- */ + /* subscribe to ORB for attitude */ + subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); + fds[fdsc_count].fd = subs.att_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- ATTITUDE SETPOINT VALUE --- */ + /* subscribe to ORB for attitude setpoint */ + /* struct already allocated */ + subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); + fds[fdsc_count].fd = subs.att_sp_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /** --- ACTUATOR OUTPUTS --- */ + subs.act_0_sub = orb_subscribe(ORB_ID(actuator_outputs_0)); + fds[fdsc_count].fd = subs.act_0_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- ACTUATOR CONTROL VALUE --- */ + /* subscribe to ORB for actuator control */ + subs.controls_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); + fds[fdsc_count].fd = subs.controls_0_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ + /* subscribe to ORB for actuator control */ + subs.controls_effective_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE); + fds[fdsc_count].fd = subs.controls_effective_0_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- LOCAL POSITION --- */ + /* subscribe to ORB for local position */ + subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); + fds[fdsc_count].fd = subs.local_pos_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- GLOBAL POSITION --- */ + /* subscribe to ORB for global position */ + subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); + fds[fdsc_count].fd = subs.global_pos_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- VICON POSITION --- */ + /* subscribe to ORB for vicon position */ + subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position)); + fds[fdsc_count].fd = subs.vicon_pos_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- FLOW measurements --- */ + /* subscribe to ORB for flow measurements */ + subs.flow_sub = orb_subscribe(ORB_ID(optical_flow)); + fds[fdsc_count].fd = subs.flow_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- BATTERY STATUS --- */ + /* subscribe to ORB for flow measurements */ + subs.batt_sub = orb_subscribe(ORB_ID(battery_status)); + fds[fdsc_count].fd = subs.batt_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- DIFFERENTIAL PRESSURE --- */ + /* subscribe to ORB for flow measurements */ + subs.diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); + fds[fdsc_count].fd = subs.diff_pres_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- AIRSPEED --- */ + /* subscribe to ORB for airspeed */ + subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed)); + fds[fdsc_count].fd = subs.airspeed_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* WARNING: If you get the error message below, + * then the number of registered messages (fdsc) + * differs from the number of messages in the above list. + */ + if (fdsc_count > fdsc) { + warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.\n", __FILE__, __LINE__); + fdsc_count = fdsc; + } + + /* + * set up poll to block for new data, + * wait for a maximum of 1000 ms (1 second) + */ + // const int timeout = 1000; + + thread_running = true; + + /* initialize log buffer with specified size */ + sdlog2_logbuffer_init(&lb, LOG_BUFFER_SIZE); + + /* initialize thread synchronization */ + pthread_mutex_init(&logbuffer_mutex, NULL); + pthread_cond_init(&logbuffer_cond, NULL); + + /* start logbuffer emptying thread */ + pthread_t logwriter_pthread = sdlog2_logwriter_start(&lb); + + starttime = hrt_absolute_time(); + + /* track skipping */ + int skip_count = 0; + + while (!thread_should_exit) { + + /* poll all topics */ + int poll_ret = poll(fds, 4, 1000); + + /* handle the poll result */ + if (poll_ret == 0) { + /* XXX this means none of our providers is giving us data - might be an error? */ + } else if (poll_ret < 0) { + /* XXX this is seriously bad - should be an emergency */ + } else { + + int ifds = 0; + + if (!logging_enabled) { + usleep(100000); + continue; + } + + pthread_mutex_lock(&logbuffer_mutex); + + /* write time stamp message */ + log_msg.msg_type = LOG_TS_MSG; + log_msg.body.log_TS.t = hrt_absolute_time(); + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(TS)); + + /* --- VEHICLE COMMAND VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + /* copy command into local buffer */ + orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd); + handle_command(&buf.cmd); + } + + /* --- GPS POSITION --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + } + + /* --- SENSORS RAW VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.raw); + log_msg.msg_type = LOG_RAW_MSG; + log_msg.body.log_RAW.accX = buf.raw.accelerometer_m_s2[0]; + log_msg.body.log_RAW.accY = buf.raw.accelerometer_m_s2[1]; + log_msg.body.log_RAW.accZ = buf.raw.accelerometer_m_s2[2]; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(RAW)); + } + + /* --- ATTITUDE VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att); + log_msg.msg_type = LOG_ATT_MSG; + log_msg.body.log_ATT.roll = buf.att.roll; + log_msg.body.log_ATT.pitch = buf.att.pitch; + log_msg.body.log_ATT.yaw = buf.att.yaw; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATT)); + } + + /* --- ATTITUDE SETPOINT VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_attitude_setpoint), subs.att_sp_sub, &buf.att_sp); + // TODO not implemented yet + } + + /* --- ACTUATOR OUTPUTS --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- ACTUATOR CONTROL VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- LOCAL POSITION --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- GLOBAL POSITION --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- VICON POSITION --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- FLOW measurements --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- BATTERY STATUS --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- DIFFERENTIAL PRESSURE --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* --- AIRSPEED --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet + } + + /* signal the other thread new data, but not yet unlock */ + if (sdlog2_logbuffer_count(&lb) > (lb.size / 2)) { + /* only request write if several packets can be written at once */ + pthread_cond_signal(&logbuffer_cond); + } + + /* unlock, now the writer thread may run */ + pthread_mutex_unlock(&logbuffer_mutex); + } + } + + print_sdlog2_status(); + + /* wake up write thread one last time */ + pthread_mutex_lock(&logbuffer_mutex); + pthread_cond_signal(&logbuffer_cond); + /* unlock, now the writer thread may return */ + pthread_mutex_unlock(&logbuffer_mutex); + + /* wait for write thread to return */ + (void)pthread_join(logwriter_pthread, NULL); + + pthread_mutex_destroy(&logbuffer_mutex); + pthread_cond_destroy(&logbuffer_cond); + + warnx("exiting.\n\n"); + + thread_running = false; + + return 0; +} + +void print_sdlog2_status() +{ + float mebibytes = log_bytes_written / 1024.0f / 1024.0f; + float seconds = ((float)(hrt_absolute_time() - starttime)) / 1000000.0f; + + warnx("wrote %4.2f MiB (average %5.3f MiB/s).\n", (double)mebibytes, (double)(mebibytes / seconds)); +} + +/** + * @return 0 if file exists + */ +int file_exist(const char *filename) +{ + struct stat buffer; + return stat(filename, &buffer); +} + +int file_copy(const char *file_old, const char *file_new) +{ + FILE *source, *target; + source = fopen(file_old, "r"); + int ret = 0; + + if (source == NULL) { + warnx("failed opening input file to copy"); + return 1; + } + + target = fopen(file_new, "w"); + + if (target == NULL) { + fclose(source); + warnx("failed to open output file to copy"); + return 1; + } + + char buf[128]; + int nread; + + while ((nread = fread(buf, 1, sizeof(buf), source)) > 0) { + ret = fwrite(buf, 1, nread, target); + + if (ret <= 0) { + warnx("error writing file"); + ret = 1; + break; + } + } + + fsync(fileno(target)); + + fclose(source); + fclose(target); + + return ret; +} + +void handle_command(struct vehicle_command_s *cmd) +{ + /* result of the command */ + uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED; + + /* request to set different system mode */ + switch (cmd->command) { + + case VEHICLE_CMD_PREFLIGHT_STORAGE: + + if (((int)(cmd->param3)) == 1) { + + /* enable logging */ + mavlink_log_info(mavlink_fd, "[log] file:"); + mavlink_log_info(mavlink_fd, "logdir"); + logging_enabled = true; + } + + if (((int)(cmd->param3)) == 0) { + + /* disable logging */ + mavlink_log_info(mavlink_fd, "[log] stopped."); + logging_enabled = false; + } + + break; + + default: + /* silently ignore */ + break; + } + +} diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h new file mode 100644 index 000000000..f5347a7bd --- /dev/null +++ b/src/modules/sdlog2/sdlog2_format.h @@ -0,0 +1,98 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2_format.h + * + * General log format structures and macro. + * + * @author Anton Babushkin + */ + +/* +Format characters in the format string for binary log messages + b : int8_t + B : uint8_t + h : int16_t + H : uint16_t + i : int32_t + I : uint32_t + f : float + n : char[4] + N : char[16] + Z : char[64] + c : int16_t * 100 + C : uint16_t * 100 + e : int32_t * 100 + E : uint32_t * 100 + L : int32_t latitude/longitude + M : uint8_t flight mode + + q : int64_t + Q : uint64_t + */ + +#ifndef SDLOG2_FORMAT_H_ +#define SDLOG2_FORMAT_H_ + +#define LOG_PACKET_HEADER_LEN 3 +#define LOG_PACKET_HEADER uint8_t head1, head2, msg_type; +#define LOG_PACKET_HEADER_INIT(id) .head1 = HEAD_BYTE1, .head2 = HEAD_BYTE2, .msg_type = id + +// once the logging code is all converted we will remove these from +// this header +#define HEAD_BYTE1 0xA3 // Decimal 163 +#define HEAD_BYTE2 0x95 // Decimal 149 + +struct log_format_s { + uint8_t type; + uint8_t length; + char name[4]; + char format[16]; + char labels[64]; +}; + +#define LOG_FORMAT(_name, _format, _labels) { \ + .type = LOG_##_name##_MSG, \ + .length = sizeof(struct log_##_name##_s) + 8, \ + .name = #_name, \ + .format = _format, \ + .labels = _labels \ + } + +#define LOG_FORMAT_MSG 128 + +#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(log_msg.body.log_##_name) + +#endif /* SDLOG2_FORMAT_H_ */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h new file mode 100644 index 000000000..ae98ea038 --- /dev/null +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -0,0 +1,82 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2_messages.h + * + * Log messages and structures definition. + * + * @author Anton Babushkin + */ + +#ifndef SDLOG2_MESSAGES_H_ +#define SDLOG2_MESSAGES_H_ + +#include "sdlog2_format.h" + +/* define message formats */ + +/* === 1: TS - TIME STAMP === */ +#define LOG_TS_MSG 1 +struct log_TS_s { + uint64_t t; +}; + +/* === 2: ATT - ATTITUDE === */ +#define LOG_ATT_MSG 2 +struct log_ATT_s { + float roll; + float pitch; + float yaw; +}; + +/* === 3: RAW - SENSORS === */ +#define LOG_RAW_MSG 3 +struct log_RAW_s { + float accX; + float accY; + float accZ; +}; + +/* construct list of all message formats */ + +static const struct log_format_s log_formats[] = { + LOG_FORMAT(TS, "Q", "t"), + LOG_FORMAT(ATT, "fff", "roll,pitch,yaw"), + LOG_FORMAT(RAW, "fff", "accX,accY,accZ"), +}; + +static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); + +#endif /* SDLOG2_MESSAGES_H_ */ diff --git a/src/modules/sdlog2/sdlog2_ringbuffer.c b/src/modules/sdlog2/sdlog2_ringbuffer.c new file mode 100644 index 000000000..022a183ba --- /dev/null +++ b/src/modules/sdlog2/sdlog2_ringbuffer.c @@ -0,0 +1,141 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2_ringbuffer.c + * + * Ring FIFO buffer for binary data. + * + * @author Anton Babushkin + */ + +#include +#include + +#include "sdlog2_ringbuffer.h" + +void sdlog2_logbuffer_init(struct sdlog2_logbuffer *lb, int size) +{ + lb->size = size; + lb->write_ptr = 0; + lb->read_ptr = 0; + lb->data = malloc(lb->size); +} + +int sdlog2_logbuffer_free(struct sdlog2_logbuffer *lb) +{ + int n = lb->read_ptr - lb->write_ptr - 1; + + if (n < 0) { + n += lb->size; + } + + return n; +} + +int sdlog2_logbuffer_count(struct sdlog2_logbuffer *lb) +{ + int n = lb->write_ptr - lb->read_ptr; + + if (n < 0) { + n += lb->size; + } + + return n; +} + +int sdlog2_logbuffer_is_empty(struct sdlog2_logbuffer *lb) +{ + return lb->read_ptr == lb->write_ptr; +} + +void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size) +{ + // bytes available to write + int available = lb->read_ptr - lb->write_ptr - 1; + + if (available < 0) + available += lb->size; + + if (size > available) { + // buffer overflow + return; + } + + char *c = (char *) ptr; + int n = lb->size - lb->write_ptr; // bytes to end of the buffer + + if (n < size) { + // message goes over end of the buffer + memcpy(&(lb->data[lb->write_ptr]), c, n); + lb->write_ptr = 0; + + } else { + n = 0; + } + + // now: n = bytes already written + int p = size - n; // number of bytes to write + memcpy(&(lb->data[lb->write_ptr]), &(c[n]), p); + lb->write_ptr = (lb->write_ptr + p) % lb->size; +} + +int sdlog2_logbuffer_get_ptr(struct sdlog2_logbuffer *lb, void **ptr) +{ + // bytes available to read + int available = lb->write_ptr - lb->read_ptr; + + if (available == 0) { + return 0; // buffer is empty + } + + int n = 0; + + if (available > 0) { + // read pointer is before write pointer, write all available bytes + n = available; + + } else { + // read pointer is after write pointer, write bytes from read_ptr to end + n = lb->size - lb->read_ptr; + } + + *ptr = &(lb->data[lb->read_ptr]); + return n; +} + +void sdlog2_logbuffer_mark_read(struct sdlog2_logbuffer *lb, int n) +{ + lb->read_ptr = (lb->read_ptr + n) % lb->size; +} diff --git a/src/modules/sdlog2/sdlog2_ringbuffer.h b/src/modules/sdlog2/sdlog2_ringbuffer.h new file mode 100644 index 000000000..287f56c34 --- /dev/null +++ b/src/modules/sdlog2/sdlog2_ringbuffer.h @@ -0,0 +1,68 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sdlog2_ringbuffer.h + * + * Ring FIFO buffer for binary data. + * + * @author Anton Babushkin + */ + +#ifndef SDLOG2_RINGBUFFER_H_ +#define SDLOG2_RINGBUFFER_H_ + +struct sdlog2_logbuffer { + // all pointers are in bytes + int write_ptr; + int read_ptr; + int size; + char *data; +}; + +void sdlog2_logbuffer_init(struct sdlog2_logbuffer *lb, int size); + +int sdlog2_logbuffer_free(struct sdlog2_logbuffer *lb); + +int sdlog2_logbuffer_count(struct sdlog2_logbuffer *lb); + +int sdlog2_logbuffer_is_empty(struct sdlog2_logbuffer *lb); + +void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size); + +int sdlog2_logbuffer_get_ptr(struct sdlog2_logbuffer *lb, void **ptr); + +void sdlog2_logbuffer_mark_read(struct sdlog2_logbuffer *lb, int n); + +#endif -- cgit v1.2.3 From 691dc8eefd835c437251e544f74f126bb883869c Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 26 May 2013 00:14:10 +0400 Subject: sdlog2 strick packing fixed, length bug fixed, "sdlog2_dump.py" debug tool added --- Tools/sdlog2_dump.py | 90 ++++++++++++++++++++++++++++++++++++++ src/modules/sdlog2/sdlog2.c | 2 + src/modules/sdlog2/sdlog2_format.h | 12 ++--- 3 files changed, 98 insertions(+), 6 deletions(-) create mode 100644 Tools/sdlog2_dump.py (limited to 'src') diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py new file mode 100644 index 000000000..bdcbfdda7 --- /dev/null +++ b/Tools/sdlog2_dump.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python + +"""Parse and dump binary log generated by sdlog2 + + Usage: python sdlog2_dump.py """ + +__author__ = "Anton Babushkin" +__version__ = "0.1" + +import struct, sys + +class BufferUnderflow(Exception): + pass + +class SDLog2Parser: + BLOCK_SIZE = 8192 + MSG_HEADER_LEN = 3 + MSG_HEAD1 = 0xA3 + MSG_HEAD2 = 0x95 + MSG_FORMAT_PACKET_LEN = 89 + MSG_TYPE_FORMAT = 0x80 + + def __init__(self): + return + + def reset(self): + self.msg_formats = {} + self.buffer = "" + self.ptr = 0 + + def process(self, fn): + self.reset() + f = open(fn, "r") + while True: + chunk = f.read(self.BLOCK_SIZE) + if len(chunk) == 0: + break + self.buffer = self.buffer[self.ptr:] + chunk + self.ptr = 0 + while self._bytes_left() >= self.MSG_HEADER_LEN: + head1 = ord(self.buffer[self.ptr]) + head2 = ord(self.buffer[self.ptr+1]) + if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): + raise Exception("Invalid header: %02X %02X, must be %02X %02X" % (head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) + msg_type = ord(self.buffer[self.ptr+2]) + if msg_type == self.MSG_TYPE_FORMAT: + self._parse_msg_format() + else: + msg_format = self.msg_formats[msg_type] + if msg_format == None: + raise Exception("Unknown msg type: %i" % msg_type) + msg_length = msg_format[0] + if self._bytes_left() < msg_length: + break + self._parse_msg(msg_format) + f.close() + + def _bytes_left(self): + return len(self.buffer) - self.ptr + + def _parse_msg_format(self): + if self._bytes_left() < self.MSG_FORMAT_PACKET_LEN: + raise BufferUnderflow("Data is too short: %i bytes, need %i" % (self._bytes_left(), self.MSG_FORMAT_PACKET_LEN)) + msg_type = ord(self.buffer[self.ptr+3]) + msg_length = ord(self.buffer[self.ptr+4]) + msg_name = self.buffer[self.ptr+5:self.ptr+9].strip('\0') + msg_struct = self.buffer[self.ptr+9:self.ptr+25].strip('\0') + msg_labels = self.buffer[self.ptr+25:self.ptr+89].strip('\0').split(",") + print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s" % (msg_type, msg_length, msg_name, msg_struct, str(msg_labels)) + self.msg_formats[msg_type] = (msg_length, msg_name, msg_struct, msg_labels) + self.ptr += self.MSG_FORMAT_PACKET_LEN + + def _parse_msg(self, msg_format): + msg_length = msg_format[0] + msg_name = msg_format[1] + msg_struct = "<" + msg_format[2] + data = struct.unpack(msg_struct, self.buffer[self.ptr+self.MSG_HEADER_LEN:self.ptr+msg_length]) + print "MSG %s: %s" % (msg_name, str(data)) + self.ptr += msg_format[0] + +def _main(): + if len(sys.argv) < 2: + print "Usage:\npython sdlog2_dump.py " + return + fn = sys.argv[1] + parser = SDLog2Parser() + parser.process(fn) + +if __name__ == "__main__": + _main() diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 38b57082f..8d4d2f8ce 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -492,6 +492,7 @@ int sdlog2_thread_main(int argc, char *argv[]) } subs; /* log message buffer: header + body */ + #pragma pack(push, 1) struct { LOG_PACKET_HEADER; union { @@ -502,6 +503,7 @@ int sdlog2_thread_main(int argc, char *argv[]) } log_msg = { LOG_PACKET_HEADER_INIT(0) }; + #pragma pack(pop) memset(&log_msg.body, 0, sizeof(log_msg.body)); /* --- MANAGEMENT - LOGGING COMMAND --- */ diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h index f5347a7bd..bbf8b6f12 100644 --- a/src/modules/sdlog2/sdlog2_format.h +++ b/src/modules/sdlog2/sdlog2_format.h @@ -77,7 +77,7 @@ Format characters in the format string for binary log messages struct log_format_s { uint8_t type; - uint8_t length; + uint8_t length; // full packet length including header char name[4]; char format[16]; char labels[64]; @@ -85,13 +85,13 @@ struct log_format_s { #define LOG_FORMAT(_name, _format, _labels) { \ .type = LOG_##_name##_MSG, \ - .length = sizeof(struct log_##_name##_s) + 8, \ - .name = #_name, \ - .format = _format, \ - .labels = _labels \ + .length = sizeof(struct log_##_name##_s) + LOG_PACKET_HEADER_LEN, \ + .name = #_name, \ + .format = _format, \ + .labels = _labels \ } -#define LOG_FORMAT_MSG 128 +#define LOG_FORMAT_MSG 0x80 #define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(log_msg.body.log_##_name) -- cgit v1.2.3 From cc6c590af062d80681430fa5139837c87fbd72f0 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 29 May 2013 00:29:31 +1000 Subject: I finished to implement nonlinear complementary filter on the SO(3). The previous problem was roll,pitch and yaw angle from quaternion. Now it is fixed. 1-2-3 Euler representation is used. Also accelerometer sign change has been applied. --- .../attitude_estimator_so3_comp_main.cpp | 176 ++++++++++++++------- 1 file changed, 120 insertions(+), 56 deletions(-) (limited to 'src') diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 28fcf0369..9bb749caf 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -1,7 +1,19 @@ /* + * Author: Hyon Lim + * * @file attitude_estimator_so3_comp_main.c * - * Nonlinear SO3 filter for Attitude Estimation. + * Implementation of nonlinear complementary filters on the SO(3). + * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer. + * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix. + * + * Theory of nonlinear complementary filters on the SO(3) is based on [1]. + * Quaternion realization of [1] is based on [2]. + * Optmized quaternion update code is based on Sebastian Madgwick's implementation. + * + * References + * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008 + * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008 */ #include @@ -46,7 +58,13 @@ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */ static float gyro_bias[3] = {0.0f, 0.0f, 0.0f}; /** bias estimation */ -static float gravity_vector[3] = {0.0f,0.0f,0.0f}; /** estimated gravity vector */ +static bool bFilterInit = false; + +//! Auxiliary variables to reduce number of repeated operations +static float q0q0, q0q1, q0q2, q0q3; +static float q1q1, q1q2, q1q3; +static float q2q2, q2q3; +static float q3q3; //! Serial packet related static int uart; @@ -150,29 +168,77 @@ float invSqrt(float number) { return y; } +//! Using accelerometer, sense the gravity vector. +//! Using magnetometer, sense yaw. +void MahonyAHRSinit(float ax, float ay, float az, float mx, float my, float mz) +{ + float initialRoll, initialPitch; + float cosRoll, sinRoll, cosPitch, sinPitch; + float magX, magY; + float initialHdg, cosHeading, sinHeading; + + initialRoll = atan2(-ay, -az); + initialPitch = atan2(ax, -az); + + cosRoll = cosf(initialRoll); + sinRoll = sinf(initialRoll); + cosPitch = cosf(initialPitch); + sinPitch = sinf(initialPitch); + + magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch; + + magY = my * cosRoll - mz * sinRoll; + + initialHdg = atan2f(-magY, magX); + + cosRoll = cosf(initialRoll * 0.5f); + sinRoll = sinf(initialRoll * 0.5f); + + cosPitch = cosf(initialPitch * 0.5f); + sinPitch = sinf(initialPitch * 0.5f); + + cosHeading = cosf(initialHdg * 0.5f); + sinHeading = sinf(initialHdg * 0.5f); + + q0 = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading; + q1 = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading; + q2 = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading; + q3 = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading; + + // auxillary variables to reduce number of repeated operations, for 1st pass + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; +} + void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { float recipNorm; - float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; float halfex = 0.0f, halfey = 0.0f, halfez = 0.0f; - - // Auxiliary variables to avoid repeated arithmetic - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; + //! Make filter converge to initial solution faster + //! This function assumes you are in static position. + //! WARNING : in case air reboot, this can cause problem. But this is very + //! unlikely happen. + if(bFilterInit == false) + { + MahonyAHRSinit(ax,ay,az,mx,my,mz); + bFilterInit = true; + } + //! If magnetometer measurement is available, use it. if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - float hx, hy, bx, bz; + float hx, hy, hz, bx, bz; float halfwx, halfwy, halfwz; // Normalise magnetometer measurement + // Will sqrt work better? PX4 system is powerful enough? recipNorm = invSqrt(mx * mx + my * my + mz * mz); mx *= recipNorm; my *= recipNorm; @@ -181,8 +247,9 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az // Reference direction of Earth's magnetic field hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); + hz = 2 * mx * (q1q3 - q0q2) + 2 * my * (q2q3 + q0q1) + 2 * mz * (0.5 - q1q1 - q2q2); bx = sqrt(hx * hx + hy * hy); - bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); + bz = hz; // Estimated direction of magnetic field halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); @@ -203,7 +270,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az recipNorm = invSqrt(ax * ax + ay * ay + az * az); ax *= recipNorm; ay *= recipNorm; - az *= recipNorm; + az *= recipNorm; // Estimated direction of gravity and magnetic field halfvx = q1q3 - q0q2; @@ -254,6 +321,18 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az q1 *= recipNorm; q2 *= recipNorm; q3 *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; } void send_uart_byte(char c) @@ -630,44 +709,29 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds uint64_t timing_start = hrt_absolute_time(); - MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],acc[0],acc[1],acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); - - float aSq = q0*q0; // 1 - float bSq = q1*q1; // 2 - float cSq = q2*q2; // 3 - float dSq = q3*q3; // 4 - float a = q0; - float b = q1; - float c = q2; - float d = q3; - - Rot_matrix[0] = 2*aSq - 1 + 2*bSq; // 11 - //Rot_matrix[1] = 2.0 * (b * c - a * d); // 12 - //Rot_matrix[2] = 2.0 * (a * c + b * d); // 13 - Rot_matrix[3] = 2.0 * (b * c - a * d); // 21 - //Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22 - //Rot_matrix[5] = 2.0 * (c * d - a * b); // 23 - Rot_matrix[6] = 2.0 * (b * d + a * c); // 31 - Rot_matrix[7] = 2.0 * (c * d - a * b); // 32 - Rot_matrix[8] = 2*aSq - 1 + 2*dSq; // 33 - - gravity_vector[0] = 2*(q1*q3-q0*q2); - gravity_vector[1] = 2*(q0*q1+q2*q3); - gravity_vector[2] = aSq - bSq - cSq + dSq; - - //euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]); - //euler[1] = -asinf(Rot_matrix[6]); - //euler[2] = atan2f(Rot_matrix[3],Rot_matrix[0]); - - // Euler angle directly from quaternion. - euler[0] = -atan2f(gravity_vector[1], sqrtf(gravity_vector[0]*gravity_vector[0] + gravity_vector[2]*gravity_vector[2])); // roll - euler[1] = atan2f(gravity_vector[0], sqrtf(gravity_vector[1]*gravity_vector[1] + gravity_vector[2]*gravity_vector[2])); // pitch - euler[2] = -atan2f(2*(q1*q2-q0*q3),2*(q0*q0+q1*q1)-1); // yaw - - //euler[2] = atan2(2 * q1*q2 - 2 * q0*q3, 2 * q0*q0 + 2 * q1*q1 - 1); // psi - //euler[1] = -asin(2 * q1*q3 + 2 * q0*q2); // theta - //euler[0] = atan2(2 * q2*q3 - 2 * q0*q1, 2 * q0*q0 + 2 * q3*q3 - 1); // phi - + // NOTE : Accelerometer is reversed. + // Because proper mount of PX4 will give you a reversed accelerometer readings. + MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],-acc[0],-acc[1],-acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); + + // Convert q->R. + Rot_matrix[0] = q0q0 + q1q1 - q2q2 - q3q3;// 11 + Rot_matrix[1] = 2.0 * (q1*q2 + q0*q3); // 12 + Rot_matrix[2] = 2.0 * (q1*q3 - q0*q2); // 13 + Rot_matrix[3] = 2.0 * (q1*q2 - q0*q3); // 21 + Rot_matrix[4] = q0q0 - q1q1 + q2q2 - q3q3;// 22 + Rot_matrix[5] = 2.0 * (q2*q3 + q0*q1); // 23 + Rot_matrix[6] = 2.0 * (q1*q3 + q0*q2); // 31 + Rot_matrix[7] = 2.0 * (q2*q3 - q0*q1); // 32 + Rot_matrix[8] = q0q0 - q1q1 - q2q2 + q3q3;// 33 + + //1-2-3 Representation. + //Equation (290) + //Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors, James Diebel. + // Existing PX4 EKF code was generated by MATLAB which uses coloum major order matrix. + euler[0] = atan2f(Rot_matrix[5], Rot_matrix[8]); //! Roll + euler[1] = -asinf(Rot_matrix[2]); //! Pitch + euler[2] = atan2f(Rot_matrix[1],Rot_matrix[0]); //! Yaw + /* swap values for next iteration, check for fatal inputs */ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) { /* Do something */ -- cgit v1.2.3 From 7a2adb22eb3ebec5fd90d1d4fbce3f5dbd61bb3c Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 29 May 2013 00:45:02 +1000 Subject: Visualization code has been added. --- src/modules/attitude_estimator_so3_comp/README | 5 + .../attitude_estimator_so3_comp_params.c | 14 +- .../attitude_estimator_so3_comp_params.h | 14 +- .../FreeIMU_cube/FreeIMU_cube.pde | 265 ++++++++ .../visualization_code/FreeIMU_cube/LICENSE.txt | 674 +++++++++++++++++++++ .../FreeIMU_cube/data/CourierNew36.vlw | Bin 0 -> 114920 bytes .../FreeIMU_yaw_pitch_roll.pde | 229 +++++++ .../FreeIMU_yaw_pitch_roll/LICENSE.txt | 674 +++++++++++++++++++++ .../FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw | Bin 0 -> 114920 bytes .../visualization_code/README | 9 + 10 files changed, 1882 insertions(+), 2 deletions(-) create mode 100644 src/modules/attitude_estimator_so3_comp/README create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw create mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/README (limited to 'src') diff --git a/src/modules/attitude_estimator_so3_comp/README b/src/modules/attitude_estimator_so3_comp/README new file mode 100644 index 000000000..26b270d37 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/README @@ -0,0 +1,5 @@ +Synopsis + + nsh> attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200 + +Option -d is for debugging packet. See visualization_code folder. diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c index 068e4340a..1d5e0670a 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -1,7 +1,19 @@ /* + * Author: Hyon Lim + * * @file attitude_estimator_so3_comp_params.c * - * Parameters for SO3 complementary filter + * Implementation of nonlinear complementary filters on the SO(3). + * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer. + * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix. + * + * Theory of nonlinear complementary filters on the SO(3) is based on [1]. + * Quaternion realization of [1] is based on [2]. + * Optmized quaternion update code is based on Sebastian Madgwick's implementation. + * + * References + * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008 + * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008 */ #include "attitude_estimator_so3_comp_params.h" diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h index 2fccec61c..f00695630 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h @@ -1,7 +1,19 @@ /* + * Author: Hyon Lim + * * @file attitude_estimator_so3_comp_params.h * - * Parameters for EKF filter + * Implementation of nonlinear complementary filters on the SO(3). + * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer. + * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix. + * + * Theory of nonlinear complementary filters on the SO(3) is based on [1]. + * Quaternion realization of [1] is based on [2]. + * Optmized quaternion update code is based on Sebastian Madgwick's implementation. + * + * References + * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008 + * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008 */ #include diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde new file mode 100644 index 000000000..3706437d3 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde @@ -0,0 +1,265 @@ +/** +Visualize a cube which will assumes the orientation described +in a quaternion coming from the serial port. + +INSTRUCTIONS: +This program has to be run when you have the FreeIMU_serial +program running on your Arduino and the Arduino connected to your PC. +Remember to set the serialPort variable below to point to the name the +Arduino serial port has in your system. You can get the port using the +Arduino IDE from Tools->Serial Port: the selected entry is what you have +to use as serialPort variable. + + +Copyright (C) 2011-2012 Fabio Varesano - http://www.varesano.net/ + +This program is free software: you can redistribute it and/or modify +it under the terms of the version 3 GNU General Public License as +published by the Free Software Foundation. + +This program 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 this program. If not, see . + +*/ + +import processing.serial.*; +import processing.opengl.*; + +Serial myPort; // Create object from Serial class + +final String serialPort = "/dev/ttyUSB9"; // replace this with your serial port. On windows you will need something like "COM1". + +float [] q = new float [4]; +float [] hq = null; +float [] Euler = new float [3]; // psi, theta, phi + +int lf = 10; // 10 is '\n' in ASCII +byte[] inBuffer = new byte[22]; // this is the number of chars on each line from the Arduino (including /r/n) + +PFont font; +final int VIEW_SIZE_X = 800, VIEW_SIZE_Y = 600; + +final int burst = 32; +int count = 0; + +void myDelay(int time) { + try { + Thread.sleep(time); + } catch (InterruptedException e) { } +} + +void setup() +{ + size(VIEW_SIZE_X, VIEW_SIZE_Y, OPENGL); + myPort = new Serial(this, serialPort, 115200); + + // The font must be located in the sketch's "data" directory to load successfully + font = loadFont("CourierNew36.vlw"); + + println("Waiting IMU.."); + + myPort.clear(); + + while (myPort.available() == 0) { + myPort.write("v"); + myDelay(1000); + } + println(myPort.readStringUntil('\n')); + myPort.write("q" + char(burst)); + myPort.bufferUntil('\n'); +} + + +float decodeFloat(String inString) { + byte [] inData = new byte[4]; + + if(inString.length() == 8) { + inData[0] = (byte) unhex(inString.substring(0, 2)); + inData[1] = (byte) unhex(inString.substring(2, 4)); + inData[2] = (byte) unhex(inString.substring(4, 6)); + inData[3] = (byte) unhex(inString.substring(6, 8)); + } + + int intbits = (inData[3] << 24) | ((inData[2] & 0xff) << 16) | ((inData[1] & 0xff) << 8) | (inData[0] & 0xff); + return Float.intBitsToFloat(intbits); +} + +void serialEvent(Serial p) { + if(p.available() >= 18) { + String inputString = p.readStringUntil('\n'); + //print(inputString); + if (inputString != null && inputString.length() > 0) { + String [] inputStringArr = split(inputString, ","); + if(inputStringArr.length >= 5) { // q1,q2,q3,q4,\r\n so we have 5 elements + q[0] = decodeFloat(inputStringArr[0]); + q[1] = decodeFloat(inputStringArr[1]); + q[2] = decodeFloat(inputStringArr[2]); + q[3] = decodeFloat(inputStringArr[3]); + } + } + count = count + 1; + if(burst == count) { // ask more data when burst completed + p.write("q" + char(burst)); + count = 0; + } + } +} + + + +void buildBoxShape() { + //box(60, 10, 40); + noStroke(); + beginShape(QUADS); + + //Z+ (to the drawing area) + fill(#00ff00); + vertex(-30, -5, 20); + vertex(30, -5, 20); + vertex(30, 5, 20); + vertex(-30, 5, 20); + + //Z- + fill(#0000ff); + vertex(-30, -5, -20); + vertex(30, -5, -20); + vertex(30, 5, -20); + vertex(-30, 5, -20); + + //X- + fill(#ff0000); + vertex(-30, -5, -20); + vertex(-30, -5, 20); + vertex(-30, 5, 20); + vertex(-30, 5, -20); + + //X+ + fill(#ffff00); + vertex(30, -5, -20); + vertex(30, -5, 20); + vertex(30, 5, 20); + vertex(30, 5, -20); + + //Y- + fill(#ff00ff); + vertex(-30, -5, -20); + vertex(30, -5, -20); + vertex(30, -5, 20); + vertex(-30, -5, 20); + + //Y+ + fill(#00ffff); + vertex(-30, 5, -20); + vertex(30, 5, -20); + vertex(30, 5, 20); + vertex(-30, 5, 20); + + endShape(); +} + + +void drawCube() { + pushMatrix(); + translate(VIEW_SIZE_X/2, VIEW_SIZE_Y/2 + 50, 0); + scale(5,5,5); + + // a demonstration of the following is at + // http://www.varesano.net/blog/fabio/ahrs-sensor-fusion-orientation-filter-3d-graphical-rotating-cube + rotateZ(-Euler[2]); + rotateX(-Euler[1]); + rotateY(-Euler[0]); + + buildBoxShape(); + + popMatrix(); +} + + +void draw() { + background(#000000); + fill(#ffffff); + + if(hq != null) { // use home quaternion + quaternionToEuler(quatProd(hq, q), Euler); + text("Disable home position by pressing \"n\"", 20, VIEW_SIZE_Y - 30); + } + else { + quaternionToEuler(q, Euler); + text("Point FreeIMU's X axis to your monitor then press \"h\"", 20, VIEW_SIZE_Y - 30); + } + + textFont(font, 20); + textAlign(LEFT, TOP); + text("Q:\n" + q[0] + "\n" + q[1] + "\n" + q[2] + "\n" + q[3], 20, 20); + text("Euler Angles:\nYaw (psi) : " + degrees(Euler[0]) + "\nPitch (theta): " + degrees(Euler[1]) + "\nRoll (phi) : " + degrees(Euler[2]), 200, 20); + + drawCube(); + //myPort.write("q" + 1); +} + + +void keyPressed() { + if(key == 'h') { + println("pressed h"); + + // set hq the home quaternion as the quatnion conjugate coming from the sensor fusion + hq = quatConjugate(q); + + } + else if(key == 'n') { + println("pressed n"); + hq = null; + } +} + +// See Sebastian O.H. Madwick report +// "An efficient orientation filter for inertial and intertial/magnetic sensor arrays" Chapter 2 Quaternion representation + +void quaternionToEuler(float [] q, float [] euler) { + euler[0] = atan2(2 * q[1] * q[2] - 2 * q[0] * q[3], 2 * q[0]*q[0] + 2 * q[1] * q[1] - 1); // psi + euler[1] = -asin(2 * q[1] * q[3] + 2 * q[0] * q[2]); // theta + euler[2] = atan2(2 * q[2] * q[3] - 2 * q[0] * q[1], 2 * q[0] * q[0] + 2 * q[3] * q[3] - 1); // phi +} + +float [] quatProd(float [] a, float [] b) { + float [] q = new float[4]; + + q[0] = a[0] * b[0] - a[1] * b[1] - a[2] * b[2] - a[3] * b[3]; + q[1] = a[0] * b[1] + a[1] * b[0] + a[2] * b[3] - a[3] * b[2]; + q[2] = a[0] * b[2] - a[1] * b[3] + a[2] * b[0] + a[3] * b[1]; + q[3] = a[0] * b[3] + a[1] * b[2] - a[2] * b[1] + a[3] * b[0]; + + return q; +} + +// returns a quaternion from an axis angle representation +float [] quatAxisAngle(float [] axis, float angle) { + float [] q = new float[4]; + + float halfAngle = angle / 2.0; + float sinHalfAngle = sin(halfAngle); + q[0] = cos(halfAngle); + q[1] = -axis[0] * sinHalfAngle; + q[2] = -axis[1] * sinHalfAngle; + q[3] = -axis[2] * sinHalfAngle; + + return q; +} + +// return the quaternion conjugate of quat +float [] quatConjugate(float [] quat) { + float [] conj = new float[4]; + + conj[0] = quat[0]; + conj[1] = -quat[1]; + conj[2] = -quat[2]; + conj[3] = -quat[3]; + + return conj; +} + diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt new file mode 100644 index 000000000..94a9ed024 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program 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. + + This program 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 this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw new file mode 100644 index 000000000..904771486 Binary files /dev/null and b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw differ diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde new file mode 100644 index 000000000..02afed971 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde @@ -0,0 +1,229 @@ +/** +Visualize orientation information from a FreeIMU device + +INSTRUCTIONS: +This program has to be run when you have the FreeIMU_serial +program running on your Arduino and the Arduino connected to your PC. +Remember to set the serialPort variable below to point to the name the +Arduino serial port has in your system. You can get the port using the +Arduino IDE from Tools->Serial Port: the selected entry is what you have +to use as serialPort variable. + +Copyright (C) 2011-2012 Fabio Varesano - http://www.varesano.net/ + +This program is free software: you can redistribute it and/or modify +it under the terms of the version 3 GNU General Public License as +published by the Free Software Foundation. + +This program 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 this program. If not, see . + +*/ + +import processing.serial.*; + +Serial myPort; // Create object from Serial class + + +float [] q = new float [4]; +float [] Euler = new float [3]; // psi, theta, phi + +int lf = 10; // 10 is '\n' in ASCII +byte[] inBuffer = new byte[22]; // this is the number of chars on each line from the Arduino (including /r/n) + +PFont font; +final int VIEW_SIZE_X = 800, VIEW_SIZE_Y = 600; + +int burst = 32, count = 0; + +void myDelay(int time) { + try { + Thread.sleep(time); + } catch (InterruptedException e) { } +} + +void setup() +{ + size(VIEW_SIZE_X, VIEW_SIZE_Y, P3D); + myPort = new Serial(this, "/dev/ttyUSB9", 115200); + + // The font must be located in the sketch's "data" directory to load successfully + font = loadFont("CourierNew36.vlw"); + + println("Waiting IMU.."); + + myPort.clear(); + + while (myPort.available() == 0) { + myPort.write("v"); + myDelay(1000); + } + println(myPort.readStringUntil('\n')); + myPort.write("q" + char(burst)); + myPort.bufferUntil('\n'); +} + + +float decodeFloat(String inString) { + byte [] inData = new byte[4]; + + if(inString.length() == 8) { + inData[0] = (byte) unhex(inString.substring(0, 2)); + inData[1] = (byte) unhex(inString.substring(2, 4)); + inData[2] = (byte) unhex(inString.substring(4, 6)); + inData[3] = (byte) unhex(inString.substring(6, 8)); + } + + int intbits = (inData[3] << 24) | ((inData[2] & 0xff) << 16) | ((inData[1] & 0xff) << 8) | (inData[0] & 0xff); + return Float.intBitsToFloat(intbits); +} + + +void serialEvent(Serial p) { + if(p.available() >= 18) { + String inputString = p.readStringUntil('\n'); + //print(inputString); + if (inputString != null && inputString.length() > 0) { + String [] inputStringArr = split(inputString, ","); + if(inputStringArr.length >= 5) { // q1,q2,q3,q4,\r\n so we have 5 elements + q[0] = decodeFloat(inputStringArr[0]); + q[1] = decodeFloat(inputStringArr[1]); + q[2] = decodeFloat(inputStringArr[2]); + q[3] = decodeFloat(inputStringArr[3]); + } + } + count = count + 1; + if(burst == count) { // ask more data when burst completed + p.write("q" + char(burst)); + count = 0; + } + } +} + + + +void buildBoxShape() { + //box(60, 10, 40); + noStroke(); + beginShape(QUADS); + + //Z+ (to the drawing area) + fill(#00ff00); + vertex(-30, -5, 20); + vertex(30, -5, 20); + vertex(30, 5, 20); + vertex(-30, 5, 20); + + //Z- + fill(#0000ff); + vertex(-30, -5, -20); + vertex(30, -5, -20); + vertex(30, 5, -20); + vertex(-30, 5, -20); + + //X- + fill(#ff0000); + vertex(-30, -5, -20); + vertex(-30, -5, 20); + vertex(-30, 5, 20); + vertex(-30, 5, -20); + + //X+ + fill(#ffff00); + vertex(30, -5, -20); + vertex(30, -5, 20); + vertex(30, 5, 20); + vertex(30, 5, -20); + + //Y- + fill(#ff00ff); + vertex(-30, -5, -20); + vertex(30, -5, -20); + vertex(30, -5, 20); + vertex(-30, -5, 20); + + //Y+ + fill(#00ffff); + vertex(-30, 5, -20); + vertex(30, 5, -20); + vertex(30, 5, 20); + vertex(-30, 5, 20); + + endShape(); +} + + +void drawcompass(float heading, int circlex, int circley, int circlediameter) { + noStroke(); + ellipse(circlex, circley, circlediameter, circlediameter); + fill(#ff0000); + ellipse(circlex, circley, circlediameter/20, circlediameter/20); + stroke(#ff0000); + strokeWeight(4); + line(circlex, circley, circlex - circlediameter/2 * sin(-heading), circley - circlediameter/2 * cos(-heading)); + noStroke(); + fill(#ffffff); + textAlign(CENTER, BOTTOM); + text("N", circlex, circley - circlediameter/2 - 10); + textAlign(CENTER, TOP); + text("S", circlex, circley + circlediameter/2 + 10); + textAlign(RIGHT, CENTER); + text("W", circlex - circlediameter/2 - 10, circley); + textAlign(LEFT, CENTER); + text("E", circlex + circlediameter/2 + 10, circley); +} + + +void drawAngle(float angle, int circlex, int circley, int circlediameter, String title) { + angle = angle + PI/2; + + noStroke(); + ellipse(circlex, circley, circlediameter, circlediameter); + fill(#ff0000); + strokeWeight(4); + stroke(#ff0000); + line(circlex - circlediameter/2 * sin(angle), circley - circlediameter/2 * cos(angle), circlex + circlediameter/2 * sin(angle), circley + circlediameter/2 * cos(angle)); + noStroke(); + fill(#ffffff); + textAlign(CENTER, BOTTOM); + text(title, circlex, circley - circlediameter/2 - 30); +} + +void draw() { + + quaternionToYawPitchRoll(q, Euler); + + background(#000000); + fill(#ffffff); + + textFont(font, 20); + //float temp_decoded = 35.0 + ((float) (temp + 13200)) / 280; + //text("temp:\n" + temp_decoded + " C", 350, 250); + textAlign(LEFT, TOP); + text("Q:\n" + q[0] + "\n" + q[1] + "\n" + q[2] + "\n" + q[3], 20, 10); + text("Euler Angles:\nYaw (psi) : " + degrees(Euler[0]) + "\nPitch (theta): " + degrees(Euler[1]) + "\nRoll (phi) : " + degrees(Euler[2]), 200, 10); + + drawcompass(Euler[0], VIEW_SIZE_X/2 - 250, VIEW_SIZE_Y/2, 200); + drawAngle(Euler[1], VIEW_SIZE_X/2, VIEW_SIZE_Y/2, 200, "Pitch:"); + drawAngle(Euler[2], VIEW_SIZE_X/2 + 250, VIEW_SIZE_Y/2, 200, "Roll:"); +} + + +void quaternionToYawPitchRoll(float [] q, float [] ypr) { + float gx, gy, gz; // estimated gravity direction + + gx = 2 * (q[1]*q[3] - q[0]*q[2]); + gy = 2 * (q[0]*q[1] + q[2]*q[3]); + gz = q[0]*q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]; + + ypr[0] = atan2(2 * q[1] * q[2] - 2 * q[0] * q[3], 2 * q[0]*q[0] + 2 * q[1] * q[1] - 1); + ypr[1] = atan2(gx, sqrt(gy*gy + gz*gz)); + ypr[2] = atan2(gy, sqrt(gx*gx + gz*gz)); +} + + diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt new file mode 100644 index 000000000..94a9ed024 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program 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. + + This program 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 this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw new file mode 100644 index 000000000..904771486 Binary files /dev/null and b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw differ diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/README b/src/modules/attitude_estimator_so3_comp/visualization_code/README new file mode 100644 index 000000000..c02863343 --- /dev/null +++ b/src/modules/attitude_estimator_so3_comp/visualization_code/README @@ -0,0 +1,9 @@ +If you run the attitude estimator by following command, the software will write packets +over /dev/ttyS1 which is used for 3D visualization. + + nsh> attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200 + +This visualization code can be executed by Processing. + Download : http://www.processing.org/download/ + +The visualization code works with Processing version 1.5.1. -- cgit v1.2.3 From 90fdf35ae549b4a5ef3b0a8f47a9c23d76e9e485 Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Wed, 29 May 2013 00:59:20 +1000 Subject: GPL Licensed code has been removed --- src/modules/attitude_estimator_so3_comp/README | 2 +- .../FreeIMU_cube/FreeIMU_cube.pde | 265 -------- .../visualization_code/FreeIMU_cube/LICENSE.txt | 674 --------------------- .../FreeIMU_cube/data/CourierNew36.vlw | Bin 114920 -> 0 bytes .../FreeIMU_yaw_pitch_roll.pde | 229 ------- .../FreeIMU_yaw_pitch_roll/LICENSE.txt | 674 --------------------- .../FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw | Bin 114920 -> 0 bytes .../visualization_code/README | 9 - 8 files changed, 1 insertion(+), 1852 deletions(-) delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw delete mode 100644 src/modules/attitude_estimator_so3_comp/visualization_code/README (limited to 'src') diff --git a/src/modules/attitude_estimator_so3_comp/README b/src/modules/attitude_estimator_so3_comp/README index 26b270d37..79c50a531 100644 --- a/src/modules/attitude_estimator_so3_comp/README +++ b/src/modules/attitude_estimator_so3_comp/README @@ -2,4 +2,4 @@ Synopsis nsh> attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200 -Option -d is for debugging packet. See visualization_code folder. +Option -d is for debugging packet. See code for detailed packet structure. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde deleted file mode 100644 index 3706437d3..000000000 --- a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/FreeIMU_cube.pde +++ /dev/null @@ -1,265 +0,0 @@ -/** -Visualize a cube which will assumes the orientation described -in a quaternion coming from the serial port. - -INSTRUCTIONS: -This program has to be run when you have the FreeIMU_serial -program running on your Arduino and the Arduino connected to your PC. -Remember to set the serialPort variable below to point to the name the -Arduino serial port has in your system. You can get the port using the -Arduino IDE from Tools->Serial Port: the selected entry is what you have -to use as serialPort variable. - - -Copyright (C) 2011-2012 Fabio Varesano - http://www.varesano.net/ - -This program is free software: you can redistribute it and/or modify -it under the terms of the version 3 GNU General Public License as -published by the Free Software Foundation. - -This program 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 this program. If not, see . - -*/ - -import processing.serial.*; -import processing.opengl.*; - -Serial myPort; // Create object from Serial class - -final String serialPort = "/dev/ttyUSB9"; // replace this with your serial port. On windows you will need something like "COM1". - -float [] q = new float [4]; -float [] hq = null; -float [] Euler = new float [3]; // psi, theta, phi - -int lf = 10; // 10 is '\n' in ASCII -byte[] inBuffer = new byte[22]; // this is the number of chars on each line from the Arduino (including /r/n) - -PFont font; -final int VIEW_SIZE_X = 800, VIEW_SIZE_Y = 600; - -final int burst = 32; -int count = 0; - -void myDelay(int time) { - try { - Thread.sleep(time); - } catch (InterruptedException e) { } -} - -void setup() -{ - size(VIEW_SIZE_X, VIEW_SIZE_Y, OPENGL); - myPort = new Serial(this, serialPort, 115200); - - // The font must be located in the sketch's "data" directory to load successfully - font = loadFont("CourierNew36.vlw"); - - println("Waiting IMU.."); - - myPort.clear(); - - while (myPort.available() == 0) { - myPort.write("v"); - myDelay(1000); - } - println(myPort.readStringUntil('\n')); - myPort.write("q" + char(burst)); - myPort.bufferUntil('\n'); -} - - -float decodeFloat(String inString) { - byte [] inData = new byte[4]; - - if(inString.length() == 8) { - inData[0] = (byte) unhex(inString.substring(0, 2)); - inData[1] = (byte) unhex(inString.substring(2, 4)); - inData[2] = (byte) unhex(inString.substring(4, 6)); - inData[3] = (byte) unhex(inString.substring(6, 8)); - } - - int intbits = (inData[3] << 24) | ((inData[2] & 0xff) << 16) | ((inData[1] & 0xff) << 8) | (inData[0] & 0xff); - return Float.intBitsToFloat(intbits); -} - -void serialEvent(Serial p) { - if(p.available() >= 18) { - String inputString = p.readStringUntil('\n'); - //print(inputString); - if (inputString != null && inputString.length() > 0) { - String [] inputStringArr = split(inputString, ","); - if(inputStringArr.length >= 5) { // q1,q2,q3,q4,\r\n so we have 5 elements - q[0] = decodeFloat(inputStringArr[0]); - q[1] = decodeFloat(inputStringArr[1]); - q[2] = decodeFloat(inputStringArr[2]); - q[3] = decodeFloat(inputStringArr[3]); - } - } - count = count + 1; - if(burst == count) { // ask more data when burst completed - p.write("q" + char(burst)); - count = 0; - } - } -} - - - -void buildBoxShape() { - //box(60, 10, 40); - noStroke(); - beginShape(QUADS); - - //Z+ (to the drawing area) - fill(#00ff00); - vertex(-30, -5, 20); - vertex(30, -5, 20); - vertex(30, 5, 20); - vertex(-30, 5, 20); - - //Z- - fill(#0000ff); - vertex(-30, -5, -20); - vertex(30, -5, -20); - vertex(30, 5, -20); - vertex(-30, 5, -20); - - //X- - fill(#ff0000); - vertex(-30, -5, -20); - vertex(-30, -5, 20); - vertex(-30, 5, 20); - vertex(-30, 5, -20); - - //X+ - fill(#ffff00); - vertex(30, -5, -20); - vertex(30, -5, 20); - vertex(30, 5, 20); - vertex(30, 5, -20); - - //Y- - fill(#ff00ff); - vertex(-30, -5, -20); - vertex(30, -5, -20); - vertex(30, -5, 20); - vertex(-30, -5, 20); - - //Y+ - fill(#00ffff); - vertex(-30, 5, -20); - vertex(30, 5, -20); - vertex(30, 5, 20); - vertex(-30, 5, 20); - - endShape(); -} - - -void drawCube() { - pushMatrix(); - translate(VIEW_SIZE_X/2, VIEW_SIZE_Y/2 + 50, 0); - scale(5,5,5); - - // a demonstration of the following is at - // http://www.varesano.net/blog/fabio/ahrs-sensor-fusion-orientation-filter-3d-graphical-rotating-cube - rotateZ(-Euler[2]); - rotateX(-Euler[1]); - rotateY(-Euler[0]); - - buildBoxShape(); - - popMatrix(); -} - - -void draw() { - background(#000000); - fill(#ffffff); - - if(hq != null) { // use home quaternion - quaternionToEuler(quatProd(hq, q), Euler); - text("Disable home position by pressing \"n\"", 20, VIEW_SIZE_Y - 30); - } - else { - quaternionToEuler(q, Euler); - text("Point FreeIMU's X axis to your monitor then press \"h\"", 20, VIEW_SIZE_Y - 30); - } - - textFont(font, 20); - textAlign(LEFT, TOP); - text("Q:\n" + q[0] + "\n" + q[1] + "\n" + q[2] + "\n" + q[3], 20, 20); - text("Euler Angles:\nYaw (psi) : " + degrees(Euler[0]) + "\nPitch (theta): " + degrees(Euler[1]) + "\nRoll (phi) : " + degrees(Euler[2]), 200, 20); - - drawCube(); - //myPort.write("q" + 1); -} - - -void keyPressed() { - if(key == 'h') { - println("pressed h"); - - // set hq the home quaternion as the quatnion conjugate coming from the sensor fusion - hq = quatConjugate(q); - - } - else if(key == 'n') { - println("pressed n"); - hq = null; - } -} - -// See Sebastian O.H. Madwick report -// "An efficient orientation filter for inertial and intertial/magnetic sensor arrays" Chapter 2 Quaternion representation - -void quaternionToEuler(float [] q, float [] euler) { - euler[0] = atan2(2 * q[1] * q[2] - 2 * q[0] * q[3], 2 * q[0]*q[0] + 2 * q[1] * q[1] - 1); // psi - euler[1] = -asin(2 * q[1] * q[3] + 2 * q[0] * q[2]); // theta - euler[2] = atan2(2 * q[2] * q[3] - 2 * q[0] * q[1], 2 * q[0] * q[0] + 2 * q[3] * q[3] - 1); // phi -} - -float [] quatProd(float [] a, float [] b) { - float [] q = new float[4]; - - q[0] = a[0] * b[0] - a[1] * b[1] - a[2] * b[2] - a[3] * b[3]; - q[1] = a[0] * b[1] + a[1] * b[0] + a[2] * b[3] - a[3] * b[2]; - q[2] = a[0] * b[2] - a[1] * b[3] + a[2] * b[0] + a[3] * b[1]; - q[3] = a[0] * b[3] + a[1] * b[2] - a[2] * b[1] + a[3] * b[0]; - - return q; -} - -// returns a quaternion from an axis angle representation -float [] quatAxisAngle(float [] axis, float angle) { - float [] q = new float[4]; - - float halfAngle = angle / 2.0; - float sinHalfAngle = sin(halfAngle); - q[0] = cos(halfAngle); - q[1] = -axis[0] * sinHalfAngle; - q[2] = -axis[1] * sinHalfAngle; - q[3] = -axis[2] * sinHalfAngle; - - return q; -} - -// return the quaternion conjugate of quat -float [] quatConjugate(float [] quat) { - float [] conj = new float[4]; - - conj[0] = quat[0]; - conj[1] = -quat[1]; - conj[2] = -quat[2]; - conj[3] = -quat[3]; - - return conj; -} - diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt deleted file mode 100644 index 94a9ed024..000000000 --- a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/LICENSE.txt +++ /dev/null @@ -1,674 +0,0 @@ - GNU GENERAL PUBLIC LICENSE - Version 3, 29 June 2007 - - Copyright (C) 2007 Free Software Foundation, Inc. - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. - - Preamble - - The GNU General Public License is a free, copyleft license for -software and other kinds of works. - - The licenses for most software and other practical works are designed -to take away your freedom to share and change the works. By contrast, -the GNU General Public License is intended to guarantee your freedom to -share and change all versions of a program--to make sure it remains free -software for all its users. We, the Free Software Foundation, use the -GNU General Public License for most of our software; it applies also to -any other work released this way by its authors. You can apply it to -your programs, too. - - When we speak of free software, we are referring to freedom, not -price. Our General Public Licenses are designed to make sure that you -have the freedom to distribute copies of free software (and charge for -them if you wish), that you receive source code or can get it if you -want it, that you can change the software or use pieces of it in new -free programs, and that you know you can do these things. - - To protect your rights, we need to prevent others from denying you -these rights or asking you to surrender the rights. Therefore, you have -certain responsibilities if you distribute copies of the software, or if -you modify it: responsibilities to respect the freedom of others. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must pass on to the recipients the same -freedoms that you received. You must make sure that they, too, receive -or can get the source code. And you must show them these terms so they -know their rights. - - Developers that use the GNU GPL protect your rights with two steps: -(1) assert copyright on the software, and (2) offer you this License -giving you legal permission to copy, distribute and/or modify it. - - For the developers' and authors' protection, the GPL clearly explains -that there is no warranty for this free software. For both users' and -authors' sake, the GPL requires that modified versions be marked as -changed, so that their problems will not be attributed erroneously to -authors of previous versions. - - Some devices are designed to deny users access to install or run -modified versions of the software inside them, although the manufacturer -can do so. This is fundamentally incompatible with the aim of -protecting users' freedom to change the software. The systematic -pattern of such abuse occurs in the area of products for individuals to -use, which is precisely where it is most unacceptable. Therefore, we -have designed this version of the GPL to prohibit the practice for those -products. If such problems arise substantially in other domains, we -stand ready to extend this provision to those domains in future versions -of the GPL, as needed to protect the freedom of users. - - Finally, every program is threatened constantly by software patents. -States should not allow patents to restrict development and use of -software on general-purpose computers, but in those that do, we wish to -avoid the special danger that patents applied to a free program could -make it effectively proprietary. To prevent this, the GPL assures that -patents cannot be used to render the program non-free. - - The precise terms and conditions for copying, distribution and -modification follow. - - TERMS AND CONDITIONS - - 0. Definitions. - - "This License" refers to version 3 of the GNU General Public License. - - "Copyright" also means copyright-like laws that apply to other kinds of -works, such as semiconductor masks. - - "The Program" refers to any copyrightable work licensed under this -License. Each licensee is addressed as "you". "Licensees" and -"recipients" may be individuals or organizations. - - To "modify" a work means to copy from or adapt all or part of the work -in a fashion requiring copyright permission, other than the making of an -exact copy. The resulting work is called a "modified version" of the -earlier work or a work "based on" the earlier work. - - A "covered work" means either the unmodified Program or a work based -on the Program. - - To "propagate" a work means to do anything with it that, without -permission, would make you directly or secondarily liable for -infringement under applicable copyright law, except executing it on a -computer or modifying a private copy. Propagation includes copying, -distribution (with or without modification), making available to the -public, and in some countries other activities as well. - - To "convey" a work means any kind of propagation that enables other -parties to make or receive copies. Mere interaction with a user through -a computer network, with no transfer of a copy, is not conveying. - - An interactive user interface displays "Appropriate Legal Notices" -to the extent that it includes a convenient and prominently visible -feature that (1) displays an appropriate copyright notice, and (2) -tells the user that there is no warranty for the work (except to the -extent that warranties are provided), that licensees may convey the -work under this License, and how to view a copy of this License. If -the interface presents a list of user commands or options, such as a -menu, a prominent item in the list meets this criterion. - - 1. Source Code. - - The "source code" for a work means the preferred form of the work -for making modifications to it. "Object code" means any non-source -form of a work. - - A "Standard Interface" means an interface that either is an official -standard defined by a recognized standards body, or, in the case of -interfaces specified for a particular programming language, one that -is widely used among developers working in that language. - - The "System Libraries" of an executable work include anything, other -than the work as a whole, that (a) is included in the normal form of -packaging a Major Component, but which is not part of that Major -Component, and (b) serves only to enable use of the work with that -Major Component, or to implement a Standard Interface for which an -implementation is available to the public in source code form. A -"Major Component", in this context, means a major essential component -(kernel, window system, and so on) of the specific operating system -(if any) on which the executable work runs, or a compiler used to -produce the work, or an object code interpreter used to run it. - - The "Corresponding Source" for a work in object code form means all -the source code needed to generate, install, and (for an executable -work) run the object code and to modify the work, including scripts to -control those activities. However, it does not include the work's -System Libraries, or general-purpose tools or generally available free -programs which are used unmodified in performing those activities but -which are not part of the work. For example, Corresponding Source -includes interface definition files associated with source files for -the work, and the source code for shared libraries and dynamically -linked subprograms that the work is specifically designed to require, -such as by intimate data communication or control flow between those -subprograms and other parts of the work. - - The Corresponding Source need not include anything that users -can regenerate automatically from other parts of the Corresponding -Source. - - The Corresponding Source for a work in source code form is that -same work. - - 2. Basic Permissions. - - All rights granted under this License are granted for the term of -copyright on the Program, and are irrevocable provided the stated -conditions are met. This License explicitly affirms your unlimited -permission to run the unmodified Program. The output from running a -covered work is covered by this License only if the output, given its -content, constitutes a covered work. This License acknowledges your -rights of fair use or other equivalent, as provided by copyright law. - - You may make, run and propagate covered works that you do not -convey, without conditions so long as your license otherwise remains -in force. You may convey covered works to others for the sole purpose -of having them make modifications exclusively for you, or provide you -with facilities for running those works, provided that you comply with -the terms of this License in conveying all material for which you do -not control copyright. Those thus making or running the covered works -for you must do so exclusively on your behalf, under your direction -and control, on terms that prohibit them from making any copies of -your copyrighted material outside their relationship with you. - - Conveying under any other circumstances is permitted solely under -the conditions stated below. Sublicensing is not allowed; section 10 -makes it unnecessary. - - 3. Protecting Users' Legal Rights From Anti-Circumvention Law. - - No covered work shall be deemed part of an effective technological -measure under any applicable law fulfilling obligations under article -11 of the WIPO copyright treaty adopted on 20 December 1996, or -similar laws prohibiting or restricting circumvention of such -measures. - - When you convey a covered work, you waive any legal power to forbid -circumvention of technological measures to the extent such circumvention -is effected by exercising rights under this License with respect to -the covered work, and you disclaim any intention to limit operation or -modification of the work as a means of enforcing, against the work's -users, your or third parties' legal rights to forbid circumvention of -technological measures. - - 4. Conveying Verbatim Copies. - - You may convey verbatim copies of the Program's source code as you -receive it, in any medium, provided that you conspicuously and -appropriately publish on each copy an appropriate copyright notice; -keep intact all notices stating that this License and any -non-permissive terms added in accord with section 7 apply to the code; -keep intact all notices of the absence of any warranty; and give all -recipients a copy of this License along with the Program. - - You may charge any price or no price for each copy that you convey, -and you may offer support or warranty protection for a fee. - - 5. Conveying Modified Source Versions. - - You may convey a work based on the Program, or the modifications to -produce it from the Program, in the form of source code under the -terms of section 4, provided that you also meet all of these conditions: - - a) The work must carry prominent notices stating that you modified - it, and giving a relevant date. - - b) The work must carry prominent notices stating that it is - released under this License and any conditions added under section - 7. This requirement modifies the requirement in section 4 to - "keep intact all notices". - - c) You must license the entire work, as a whole, under this - License to anyone who comes into possession of a copy. This - License will therefore apply, along with any applicable section 7 - additional terms, to the whole of the work, and all its parts, - regardless of how they are packaged. This License gives no - permission to license the work in any other way, but it does not - invalidate such permission if you have separately received it. - - d) If the work has interactive user interfaces, each must display - Appropriate Legal Notices; however, if the Program has interactive - interfaces that do not display Appropriate Legal Notices, your - work need not make them do so. - - A compilation of a covered work with other separate and independent -works, which are not by their nature extensions of the covered work, -and which are not combined with it such as to form a larger program, -in or on a volume of a storage or distribution medium, is called an -"aggregate" if the compilation and its resulting copyright are not -used to limit the access or legal rights of the compilation's users -beyond what the individual works permit. Inclusion of a covered work -in an aggregate does not cause this License to apply to the other -parts of the aggregate. - - 6. Conveying Non-Source Forms. - - You may convey a covered work in object code form under the terms -of sections 4 and 5, provided that you also convey the -machine-readable Corresponding Source under the terms of this License, -in one of these ways: - - a) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by the - Corresponding Source fixed on a durable physical medium - customarily used for software interchange. - - b) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by a - written offer, valid for at least three years and valid for as - long as you offer spare parts or customer support for that product - model, to give anyone who possesses the object code either (1) a - copy of the Corresponding Source for all the software in the - product that is covered by this License, on a durable physical - medium customarily used for software interchange, for a price no - more than your reasonable cost of physically performing this - conveying of source, or (2) access to copy the - Corresponding Source from a network server at no charge. - - c) Convey individual copies of the object code with a copy of the - written offer to provide the Corresponding Source. This - alternative is allowed only occasionally and noncommercially, and - only if you received the object code with such an offer, in accord - with subsection 6b. - - d) Convey the object code by offering access from a designated - place (gratis or for a charge), and offer equivalent access to the - Corresponding Source in the same way through the same place at no - further charge. You need not require recipients to copy the - Corresponding Source along with the object code. If the place to - copy the object code is a network server, the Corresponding Source - may be on a different server (operated by you or a third party) - that supports equivalent copying facilities, provided you maintain - clear directions next to the object code saying where to find the - Corresponding Source. Regardless of what server hosts the - Corresponding Source, you remain obligated to ensure that it is - available for as long as needed to satisfy these requirements. - - e) Convey the object code using peer-to-peer transmission, provided - you inform other peers where the object code and Corresponding - Source of the work are being offered to the general public at no - charge under subsection 6d. - - A separable portion of the object code, whose source code is excluded -from the Corresponding Source as a System Library, need not be -included in conveying the object code work. - - A "User Product" is either (1) a "consumer product", which means any -tangible personal property which is normally used for personal, family, -or household purposes, or (2) anything designed or sold for incorporation -into a dwelling. In determining whether a product is a consumer product, -doubtful cases shall be resolved in favor of coverage. For a particular -product received by a particular user, "normally used" refers to a -typical or common use of that class of product, regardless of the status -of the particular user or of the way in which the particular user -actually uses, or expects or is expected to use, the product. A product -is a consumer product regardless of whether the product has substantial -commercial, industrial or non-consumer uses, unless such uses represent -the only significant mode of use of the product. - - "Installation Information" for a User Product means any methods, -procedures, authorization keys, or other information required to install -and execute modified versions of a covered work in that User Product from -a modified version of its Corresponding Source. The information must -suffice to ensure that the continued functioning of the modified object -code is in no case prevented or interfered with solely because -modification has been made. - - If you convey an object code work under this section in, or with, or -specifically for use in, a User Product, and the conveying occurs as -part of a transaction in which the right of possession and use of the -User Product is transferred to the recipient in perpetuity or for a -fixed term (regardless of how the transaction is characterized), the -Corresponding Source conveyed under this section must be accompanied -by the Installation Information. But this requirement does not apply -if neither you nor any third party retains the ability to install -modified object code on the User Product (for example, the work has -been installed in ROM). - - The requirement to provide Installation Information does not include a -requirement to continue to provide support service, warranty, or updates -for a work that has been modified or installed by the recipient, or for -the User Product in which it has been modified or installed. Access to a -network may be denied when the modification itself materially and -adversely affects the operation of the network or violates the rules and -protocols for communication across the network. - - Corresponding Source conveyed, and Installation Information provided, -in accord with this section must be in a format that is publicly -documented (and with an implementation available to the public in -source code form), and must require no special password or key for -unpacking, reading or copying. - - 7. Additional Terms. - - "Additional permissions" are terms that supplement the terms of this -License by making exceptions from one or more of its conditions. -Additional permissions that are applicable to the entire Program shall -be treated as though they were included in this License, to the extent -that they are valid under applicable law. If additional permissions -apply only to part of the Program, that part may be used separately -under those permissions, but the entire Program remains governed by -this License without regard to the additional permissions. - - When you convey a copy of a covered work, you may at your option -remove any additional permissions from that copy, or from any part of -it. (Additional permissions may be written to require their own -removal in certain cases when you modify the work.) You may place -additional permissions on material, added by you to a covered work, -for which you have or can give appropriate copyright permission. - - Notwithstanding any other provision of this License, for material you -add to a covered work, you may (if authorized by the copyright holders of -that material) supplement the terms of this License with terms: - - a) Disclaiming warranty or limiting liability differently from the - terms of sections 15 and 16 of this License; or - - b) Requiring preservation of specified reasonable legal notices or - author attributions in that material or in the Appropriate Legal - Notices displayed by works containing it; or - - c) Prohibiting misrepresentation of the origin of that material, or - requiring that modified versions of such material be marked in - reasonable ways as different from the original version; or - - d) Limiting the use for publicity purposes of names of licensors or - authors of the material; or - - e) Declining to grant rights under trademark law for use of some - trade names, trademarks, or service marks; or - - f) Requiring indemnification of licensors and authors of that - material by anyone who conveys the material (or modified versions of - it) with contractual assumptions of liability to the recipient, for - any liability that these contractual assumptions directly impose on - those licensors and authors. - - All other non-permissive additional terms are considered "further -restrictions" within the meaning of section 10. If the Program as you -received it, or any part of it, contains a notice stating that it is -governed by this License along with a term that is a further -restriction, you may remove that term. If a license document contains -a further restriction but permits relicensing or conveying under this -License, you may add to a covered work material governed by the terms -of that license document, provided that the further restriction does -not survive such relicensing or conveying. - - If you add terms to a covered work in accord with this section, you -must place, in the relevant source files, a statement of the -additional terms that apply to those files, or a notice indicating -where to find the applicable terms. - - Additional terms, permissive or non-permissive, may be stated in the -form of a separately written license, or stated as exceptions; -the above requirements apply either way. - - 8. Termination. - - You may not propagate or modify a covered work except as expressly -provided under this License. Any attempt otherwise to propagate or -modify it is void, and will automatically terminate your rights under -this License (including any patent licenses granted under the third -paragraph of section 11). - - However, if you cease all violation of this License, then your -license from a particular copyright holder is reinstated (a) -provisionally, unless and until the copyright holder explicitly and -finally terminates your license, and (b) permanently, if the copyright -holder fails to notify you of the violation by some reasonable means -prior to 60 days after the cessation. - - Moreover, your license from a particular copyright holder is -reinstated permanently if the copyright holder notifies you of the -violation by some reasonable means, this is the first time you have -received notice of violation of this License (for any work) from that -copyright holder, and you cure the violation prior to 30 days after -your receipt of the notice. - - Termination of your rights under this section does not terminate the -licenses of parties who have received copies or rights from you under -this License. If your rights have been terminated and not permanently -reinstated, you do not qualify to receive new licenses for the same -material under section 10. - - 9. Acceptance Not Required for Having Copies. - - You are not required to accept this License in order to receive or -run a copy of the Program. Ancillary propagation of a covered work -occurring solely as a consequence of using peer-to-peer transmission -to receive a copy likewise does not require acceptance. However, -nothing other than this License grants you permission to propagate or -modify any covered work. These actions infringe copyright if you do -not accept this License. Therefore, by modifying or propagating a -covered work, you indicate your acceptance of this License to do so. - - 10. Automatic Licensing of Downstream Recipients. - - Each time you convey a covered work, the recipient automatically -receives a license from the original licensors, to run, modify and -propagate that work, subject to this License. You are not responsible -for enforcing compliance by third parties with this License. - - An "entity transaction" is a transaction transferring control of an -organization, or substantially all assets of one, or subdividing an -organization, or merging organizations. If propagation of a covered -work results from an entity transaction, each party to that -transaction who receives a copy of the work also receives whatever -licenses to the work the party's predecessor in interest had or could -give under the previous paragraph, plus a right to possession of the -Corresponding Source of the work from the predecessor in interest, if -the predecessor has it or can get it with reasonable efforts. - - You may not impose any further restrictions on the exercise of the -rights granted or affirmed under this License. For example, you may -not impose a license fee, royalty, or other charge for exercise of -rights granted under this License, and you may not initiate litigation -(including a cross-claim or counterclaim in a lawsuit) alleging that -any patent claim is infringed by making, using, selling, offering for -sale, or importing the Program or any portion of it. - - 11. Patents. - - A "contributor" is a copyright holder who authorizes use under this -License of the Program or a work on which the Program is based. The -work thus licensed is called the contributor's "contributor version". - - A contributor's "essential patent claims" are all patent claims -owned or controlled by the contributor, whether already acquired or -hereafter acquired, that would be infringed by some manner, permitted -by this License, of making, using, or selling its contributor version, -but do not include claims that would be infringed only as a -consequence of further modification of the contributor version. For -purposes of this definition, "control" includes the right to grant -patent sublicenses in a manner consistent with the requirements of -this License. - - Each contributor grants you a non-exclusive, worldwide, royalty-free -patent license under the contributor's essential patent claims, to -make, use, sell, offer for sale, import and otherwise run, modify and -propagate the contents of its contributor version. - - In the following three paragraphs, a "patent license" is any express -agreement or commitment, however denominated, not to enforce a patent -(such as an express permission to practice a patent or covenant not to -sue for patent infringement). To "grant" such a patent license to a -party means to make such an agreement or commitment not to enforce a -patent against the party. - - If you convey a covered work, knowingly relying on a patent license, -and the Corresponding Source of the work is not available for anyone -to copy, free of charge and under the terms of this License, through a -publicly available network server or other readily accessible means, -then you must either (1) cause the Corresponding Source to be so -available, or (2) arrange to deprive yourself of the benefit of the -patent license for this particular work, or (3) arrange, in a manner -consistent with the requirements of this License, to extend the patent -license to downstream recipients. "Knowingly relying" means you have -actual knowledge that, but for the patent license, your conveying the -covered work in a country, or your recipient's use of the covered work -in a country, would infringe one or more identifiable patents in that -country that you have reason to believe are valid. - - If, pursuant to or in connection with a single transaction or -arrangement, you convey, or propagate by procuring conveyance of, a -covered work, and grant a patent license to some of the parties -receiving the covered work authorizing them to use, propagate, modify -or convey a specific copy of the covered work, then the patent license -you grant is automatically extended to all recipients of the covered -work and works based on it. - - A patent license is "discriminatory" if it does not include within -the scope of its coverage, prohibits the exercise of, or is -conditioned on the non-exercise of one or more of the rights that are -specifically granted under this License. You may not convey a covered -work if you are a party to an arrangement with a third party that is -in the business of distributing software, under which you make payment -to the third party based on the extent of your activity of conveying -the work, and under which the third party grants, to any of the -parties who would receive the covered work from you, a discriminatory -patent license (a) in connection with copies of the covered work -conveyed by you (or copies made from those copies), or (b) primarily -for and in connection with specific products or compilations that -contain the covered work, unless you entered into that arrangement, -or that patent license was granted, prior to 28 March 2007. - - Nothing in this License shall be construed as excluding or limiting -any implied license or other defenses to infringement that may -otherwise be available to you under applicable patent law. - - 12. No Surrender of Others' Freedom. - - If conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot convey a -covered work so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you may -not convey it at all. For example, if you agree to terms that obligate you -to collect a royalty for further conveying from those to whom you convey -the Program, the only way you could satisfy both those terms and this -License would be to refrain entirely from conveying the Program. - - 13. Use with the GNU Affero General Public License. - - Notwithstanding any other provision of this License, you have -permission to link or combine any covered work with a work licensed -under version 3 of the GNU Affero General Public License into a single -combined work, and to convey the resulting work. The terms of this -License will continue to apply to the part which is the covered work, -but the special requirements of the GNU Affero General Public License, -section 13, concerning interaction through a network will apply to the -combination as such. - - 14. Revised Versions of this License. - - The Free Software Foundation may publish revised and/or new versions of -the GNU General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to -address new problems or concerns. - - Each version is given a distinguishing version number. If the -Program specifies that a certain numbered version of the GNU General -Public License "or any later version" applies to it, you have the -option of following the terms and conditions either of that numbered -version or of any later version published by the Free Software -Foundation. If the Program does not specify a version number of the -GNU General Public License, you may choose any version ever published -by the Free Software Foundation. - - If the Program specifies that a proxy can decide which future -versions of the GNU General Public License can be used, that proxy's -public statement of acceptance of a version permanently authorizes you -to choose that version for the Program. - - Later license versions may give you additional or different -permissions. However, no additional obligations are imposed on any -author or copyright holder as a result of your choosing to follow a -later version. - - 15. Disclaimer of Warranty. - - THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY -APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT -HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY -OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, -THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR -PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM -IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF -ALL NECESSARY SERVICING, REPAIR OR CORRECTION. - - 16. Limitation of Liability. - - IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING -WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS -THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY -GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE -USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF -DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD -PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), -EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF -SUCH DAMAGES. - - 17. Interpretation of Sections 15 and 16. - - If the disclaimer of warranty and limitation of liability provided -above cannot be given local legal effect according to their terms, -reviewing courts shall apply local law that most closely approximates -an absolute waiver of all civil liability in connection with the -Program, unless a warranty or assumption of liability accompanies a -copy of the Program in return for a fee. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Programs - - If you develop a new program, and you want it to be of the greatest -possible use to the public, the best way to achieve this is to make it -free software which everyone can redistribute and change under these terms. - - To do so, attach the following notices to the program. It is safest -to attach them to the start of each source file to most effectively -state the exclusion of warranty; and each file should have at least -the "copyright" line and a pointer to where the full notice is found. - - - Copyright (C) - - This program 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. - - This program 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 this program. If not, see . - -Also add information on how to contact you by electronic and paper mail. - - If the program does terminal interaction, make it output a short -notice like this when it starts in an interactive mode: - - Copyright (C) - This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, your program's commands -might be different; for a GUI interface, you would use an "about box". - - You should also get your employer (if you work as a programmer) or school, -if any, to sign a "copyright disclaimer" for the program, if necessary. -For more information on this, and how to apply and follow the GNU GPL, see -. - - The GNU General Public License does not permit incorporating your program -into proprietary programs. If your program is a subroutine library, you -may consider it more useful to permit linking proprietary applications with -the library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. But first, please read -. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw deleted file mode 100644 index 904771486..000000000 Binary files a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_cube/data/CourierNew36.vlw and /dev/null differ diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde deleted file mode 100644 index 02afed971..000000000 --- a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/FreeIMU_yaw_pitch_roll.pde +++ /dev/null @@ -1,229 +0,0 @@ -/** -Visualize orientation information from a FreeIMU device - -INSTRUCTIONS: -This program has to be run when you have the FreeIMU_serial -program running on your Arduino and the Arduino connected to your PC. -Remember to set the serialPort variable below to point to the name the -Arduino serial port has in your system. You can get the port using the -Arduino IDE from Tools->Serial Port: the selected entry is what you have -to use as serialPort variable. - -Copyright (C) 2011-2012 Fabio Varesano - http://www.varesano.net/ - -This program is free software: you can redistribute it and/or modify -it under the terms of the version 3 GNU General Public License as -published by the Free Software Foundation. - -This program 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 this program. If not, see . - -*/ - -import processing.serial.*; - -Serial myPort; // Create object from Serial class - - -float [] q = new float [4]; -float [] Euler = new float [3]; // psi, theta, phi - -int lf = 10; // 10 is '\n' in ASCII -byte[] inBuffer = new byte[22]; // this is the number of chars on each line from the Arduino (including /r/n) - -PFont font; -final int VIEW_SIZE_X = 800, VIEW_SIZE_Y = 600; - -int burst = 32, count = 0; - -void myDelay(int time) { - try { - Thread.sleep(time); - } catch (InterruptedException e) { } -} - -void setup() -{ - size(VIEW_SIZE_X, VIEW_SIZE_Y, P3D); - myPort = new Serial(this, "/dev/ttyUSB9", 115200); - - // The font must be located in the sketch's "data" directory to load successfully - font = loadFont("CourierNew36.vlw"); - - println("Waiting IMU.."); - - myPort.clear(); - - while (myPort.available() == 0) { - myPort.write("v"); - myDelay(1000); - } - println(myPort.readStringUntil('\n')); - myPort.write("q" + char(burst)); - myPort.bufferUntil('\n'); -} - - -float decodeFloat(String inString) { - byte [] inData = new byte[4]; - - if(inString.length() == 8) { - inData[0] = (byte) unhex(inString.substring(0, 2)); - inData[1] = (byte) unhex(inString.substring(2, 4)); - inData[2] = (byte) unhex(inString.substring(4, 6)); - inData[3] = (byte) unhex(inString.substring(6, 8)); - } - - int intbits = (inData[3] << 24) | ((inData[2] & 0xff) << 16) | ((inData[1] & 0xff) << 8) | (inData[0] & 0xff); - return Float.intBitsToFloat(intbits); -} - - -void serialEvent(Serial p) { - if(p.available() >= 18) { - String inputString = p.readStringUntil('\n'); - //print(inputString); - if (inputString != null && inputString.length() > 0) { - String [] inputStringArr = split(inputString, ","); - if(inputStringArr.length >= 5) { // q1,q2,q3,q4,\r\n so we have 5 elements - q[0] = decodeFloat(inputStringArr[0]); - q[1] = decodeFloat(inputStringArr[1]); - q[2] = decodeFloat(inputStringArr[2]); - q[3] = decodeFloat(inputStringArr[3]); - } - } - count = count + 1; - if(burst == count) { // ask more data when burst completed - p.write("q" + char(burst)); - count = 0; - } - } -} - - - -void buildBoxShape() { - //box(60, 10, 40); - noStroke(); - beginShape(QUADS); - - //Z+ (to the drawing area) - fill(#00ff00); - vertex(-30, -5, 20); - vertex(30, -5, 20); - vertex(30, 5, 20); - vertex(-30, 5, 20); - - //Z- - fill(#0000ff); - vertex(-30, -5, -20); - vertex(30, -5, -20); - vertex(30, 5, -20); - vertex(-30, 5, -20); - - //X- - fill(#ff0000); - vertex(-30, -5, -20); - vertex(-30, -5, 20); - vertex(-30, 5, 20); - vertex(-30, 5, -20); - - //X+ - fill(#ffff00); - vertex(30, -5, -20); - vertex(30, -5, 20); - vertex(30, 5, 20); - vertex(30, 5, -20); - - //Y- - fill(#ff00ff); - vertex(-30, -5, -20); - vertex(30, -5, -20); - vertex(30, -5, 20); - vertex(-30, -5, 20); - - //Y+ - fill(#00ffff); - vertex(-30, 5, -20); - vertex(30, 5, -20); - vertex(30, 5, 20); - vertex(-30, 5, 20); - - endShape(); -} - - -void drawcompass(float heading, int circlex, int circley, int circlediameter) { - noStroke(); - ellipse(circlex, circley, circlediameter, circlediameter); - fill(#ff0000); - ellipse(circlex, circley, circlediameter/20, circlediameter/20); - stroke(#ff0000); - strokeWeight(4); - line(circlex, circley, circlex - circlediameter/2 * sin(-heading), circley - circlediameter/2 * cos(-heading)); - noStroke(); - fill(#ffffff); - textAlign(CENTER, BOTTOM); - text("N", circlex, circley - circlediameter/2 - 10); - textAlign(CENTER, TOP); - text("S", circlex, circley + circlediameter/2 + 10); - textAlign(RIGHT, CENTER); - text("W", circlex - circlediameter/2 - 10, circley); - textAlign(LEFT, CENTER); - text("E", circlex + circlediameter/2 + 10, circley); -} - - -void drawAngle(float angle, int circlex, int circley, int circlediameter, String title) { - angle = angle + PI/2; - - noStroke(); - ellipse(circlex, circley, circlediameter, circlediameter); - fill(#ff0000); - strokeWeight(4); - stroke(#ff0000); - line(circlex - circlediameter/2 * sin(angle), circley - circlediameter/2 * cos(angle), circlex + circlediameter/2 * sin(angle), circley + circlediameter/2 * cos(angle)); - noStroke(); - fill(#ffffff); - textAlign(CENTER, BOTTOM); - text(title, circlex, circley - circlediameter/2 - 30); -} - -void draw() { - - quaternionToYawPitchRoll(q, Euler); - - background(#000000); - fill(#ffffff); - - textFont(font, 20); - //float temp_decoded = 35.0 + ((float) (temp + 13200)) / 280; - //text("temp:\n" + temp_decoded + " C", 350, 250); - textAlign(LEFT, TOP); - text("Q:\n" + q[0] + "\n" + q[1] + "\n" + q[2] + "\n" + q[3], 20, 10); - text("Euler Angles:\nYaw (psi) : " + degrees(Euler[0]) + "\nPitch (theta): " + degrees(Euler[1]) + "\nRoll (phi) : " + degrees(Euler[2]), 200, 10); - - drawcompass(Euler[0], VIEW_SIZE_X/2 - 250, VIEW_SIZE_Y/2, 200); - drawAngle(Euler[1], VIEW_SIZE_X/2, VIEW_SIZE_Y/2, 200, "Pitch:"); - drawAngle(Euler[2], VIEW_SIZE_X/2 + 250, VIEW_SIZE_Y/2, 200, "Roll:"); -} - - -void quaternionToYawPitchRoll(float [] q, float [] ypr) { - float gx, gy, gz; // estimated gravity direction - - gx = 2 * (q[1]*q[3] - q[0]*q[2]); - gy = 2 * (q[0]*q[1] + q[2]*q[3]); - gz = q[0]*q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]; - - ypr[0] = atan2(2 * q[1] * q[2] - 2 * q[0] * q[3], 2 * q[0]*q[0] + 2 * q[1] * q[1] - 1); - ypr[1] = atan2(gx, sqrt(gy*gy + gz*gz)); - ypr[2] = atan2(gy, sqrt(gx*gx + gz*gz)); -} - - diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt deleted file mode 100644 index 94a9ed024..000000000 --- a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/LICENSE.txt +++ /dev/null @@ -1,674 +0,0 @@ - GNU GENERAL PUBLIC LICENSE - Version 3, 29 June 2007 - - Copyright (C) 2007 Free Software Foundation, Inc. - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. - - Preamble - - The GNU General Public License is a free, copyleft license for -software and other kinds of works. - - The licenses for most software and other practical works are designed -to take away your freedom to share and change the works. By contrast, -the GNU General Public License is intended to guarantee your freedom to -share and change all versions of a program--to make sure it remains free -software for all its users. We, the Free Software Foundation, use the -GNU General Public License for most of our software; it applies also to -any other work released this way by its authors. You can apply it to -your programs, too. - - When we speak of free software, we are referring to freedom, not -price. Our General Public Licenses are designed to make sure that you -have the freedom to distribute copies of free software (and charge for -them if you wish), that you receive source code or can get it if you -want it, that you can change the software or use pieces of it in new -free programs, and that you know you can do these things. - - To protect your rights, we need to prevent others from denying you -these rights or asking you to surrender the rights. Therefore, you have -certain responsibilities if you distribute copies of the software, or if -you modify it: responsibilities to respect the freedom of others. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must pass on to the recipients the same -freedoms that you received. You must make sure that they, too, receive -or can get the source code. And you must show them these terms so they -know their rights. - - Developers that use the GNU GPL protect your rights with two steps: -(1) assert copyright on the software, and (2) offer you this License -giving you legal permission to copy, distribute and/or modify it. - - For the developers' and authors' protection, the GPL clearly explains -that there is no warranty for this free software. For both users' and -authors' sake, the GPL requires that modified versions be marked as -changed, so that their problems will not be attributed erroneously to -authors of previous versions. - - Some devices are designed to deny users access to install or run -modified versions of the software inside them, although the manufacturer -can do so. This is fundamentally incompatible with the aim of -protecting users' freedom to change the software. The systematic -pattern of such abuse occurs in the area of products for individuals to -use, which is precisely where it is most unacceptable. Therefore, we -have designed this version of the GPL to prohibit the practice for those -products. If such problems arise substantially in other domains, we -stand ready to extend this provision to those domains in future versions -of the GPL, as needed to protect the freedom of users. - - Finally, every program is threatened constantly by software patents. -States should not allow patents to restrict development and use of -software on general-purpose computers, but in those that do, we wish to -avoid the special danger that patents applied to a free program could -make it effectively proprietary. To prevent this, the GPL assures that -patents cannot be used to render the program non-free. - - The precise terms and conditions for copying, distribution and -modification follow. - - TERMS AND CONDITIONS - - 0. Definitions. - - "This License" refers to version 3 of the GNU General Public License. - - "Copyright" also means copyright-like laws that apply to other kinds of -works, such as semiconductor masks. - - "The Program" refers to any copyrightable work licensed under this -License. Each licensee is addressed as "you". "Licensees" and -"recipients" may be individuals or organizations. - - To "modify" a work means to copy from or adapt all or part of the work -in a fashion requiring copyright permission, other than the making of an -exact copy. The resulting work is called a "modified version" of the -earlier work or a work "based on" the earlier work. - - A "covered work" means either the unmodified Program or a work based -on the Program. - - To "propagate" a work means to do anything with it that, without -permission, would make you directly or secondarily liable for -infringement under applicable copyright law, except executing it on a -computer or modifying a private copy. Propagation includes copying, -distribution (with or without modification), making available to the -public, and in some countries other activities as well. - - To "convey" a work means any kind of propagation that enables other -parties to make or receive copies. Mere interaction with a user through -a computer network, with no transfer of a copy, is not conveying. - - An interactive user interface displays "Appropriate Legal Notices" -to the extent that it includes a convenient and prominently visible -feature that (1) displays an appropriate copyright notice, and (2) -tells the user that there is no warranty for the work (except to the -extent that warranties are provided), that licensees may convey the -work under this License, and how to view a copy of this License. If -the interface presents a list of user commands or options, such as a -menu, a prominent item in the list meets this criterion. - - 1. Source Code. - - The "source code" for a work means the preferred form of the work -for making modifications to it. "Object code" means any non-source -form of a work. - - A "Standard Interface" means an interface that either is an official -standard defined by a recognized standards body, or, in the case of -interfaces specified for a particular programming language, one that -is widely used among developers working in that language. - - The "System Libraries" of an executable work include anything, other -than the work as a whole, that (a) is included in the normal form of -packaging a Major Component, but which is not part of that Major -Component, and (b) serves only to enable use of the work with that -Major Component, or to implement a Standard Interface for which an -implementation is available to the public in source code form. A -"Major Component", in this context, means a major essential component -(kernel, window system, and so on) of the specific operating system -(if any) on which the executable work runs, or a compiler used to -produce the work, or an object code interpreter used to run it. - - The "Corresponding Source" for a work in object code form means all -the source code needed to generate, install, and (for an executable -work) run the object code and to modify the work, including scripts to -control those activities. However, it does not include the work's -System Libraries, or general-purpose tools or generally available free -programs which are used unmodified in performing those activities but -which are not part of the work. For example, Corresponding Source -includes interface definition files associated with source files for -the work, and the source code for shared libraries and dynamically -linked subprograms that the work is specifically designed to require, -such as by intimate data communication or control flow between those -subprograms and other parts of the work. - - The Corresponding Source need not include anything that users -can regenerate automatically from other parts of the Corresponding -Source. - - The Corresponding Source for a work in source code form is that -same work. - - 2. Basic Permissions. - - All rights granted under this License are granted for the term of -copyright on the Program, and are irrevocable provided the stated -conditions are met. This License explicitly affirms your unlimited -permission to run the unmodified Program. The output from running a -covered work is covered by this License only if the output, given its -content, constitutes a covered work. This License acknowledges your -rights of fair use or other equivalent, as provided by copyright law. - - You may make, run and propagate covered works that you do not -convey, without conditions so long as your license otherwise remains -in force. You may convey covered works to others for the sole purpose -of having them make modifications exclusively for you, or provide you -with facilities for running those works, provided that you comply with -the terms of this License in conveying all material for which you do -not control copyright. Those thus making or running the covered works -for you must do so exclusively on your behalf, under your direction -and control, on terms that prohibit them from making any copies of -your copyrighted material outside their relationship with you. - - Conveying under any other circumstances is permitted solely under -the conditions stated below. Sublicensing is not allowed; section 10 -makes it unnecessary. - - 3. Protecting Users' Legal Rights From Anti-Circumvention Law. - - No covered work shall be deemed part of an effective technological -measure under any applicable law fulfilling obligations under article -11 of the WIPO copyright treaty adopted on 20 December 1996, or -similar laws prohibiting or restricting circumvention of such -measures. - - When you convey a covered work, you waive any legal power to forbid -circumvention of technological measures to the extent such circumvention -is effected by exercising rights under this License with respect to -the covered work, and you disclaim any intention to limit operation or -modification of the work as a means of enforcing, against the work's -users, your or third parties' legal rights to forbid circumvention of -technological measures. - - 4. Conveying Verbatim Copies. - - You may convey verbatim copies of the Program's source code as you -receive it, in any medium, provided that you conspicuously and -appropriately publish on each copy an appropriate copyright notice; -keep intact all notices stating that this License and any -non-permissive terms added in accord with section 7 apply to the code; -keep intact all notices of the absence of any warranty; and give all -recipients a copy of this License along with the Program. - - You may charge any price or no price for each copy that you convey, -and you may offer support or warranty protection for a fee. - - 5. Conveying Modified Source Versions. - - You may convey a work based on the Program, or the modifications to -produce it from the Program, in the form of source code under the -terms of section 4, provided that you also meet all of these conditions: - - a) The work must carry prominent notices stating that you modified - it, and giving a relevant date. - - b) The work must carry prominent notices stating that it is - released under this License and any conditions added under section - 7. This requirement modifies the requirement in section 4 to - "keep intact all notices". - - c) You must license the entire work, as a whole, under this - License to anyone who comes into possession of a copy. This - License will therefore apply, along with any applicable section 7 - additional terms, to the whole of the work, and all its parts, - regardless of how they are packaged. This License gives no - permission to license the work in any other way, but it does not - invalidate such permission if you have separately received it. - - d) If the work has interactive user interfaces, each must display - Appropriate Legal Notices; however, if the Program has interactive - interfaces that do not display Appropriate Legal Notices, your - work need not make them do so. - - A compilation of a covered work with other separate and independent -works, which are not by their nature extensions of the covered work, -and which are not combined with it such as to form a larger program, -in or on a volume of a storage or distribution medium, is called an -"aggregate" if the compilation and its resulting copyright are not -used to limit the access or legal rights of the compilation's users -beyond what the individual works permit. Inclusion of a covered work -in an aggregate does not cause this License to apply to the other -parts of the aggregate. - - 6. Conveying Non-Source Forms. - - You may convey a covered work in object code form under the terms -of sections 4 and 5, provided that you also convey the -machine-readable Corresponding Source under the terms of this License, -in one of these ways: - - a) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by the - Corresponding Source fixed on a durable physical medium - customarily used for software interchange. - - b) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by a - written offer, valid for at least three years and valid for as - long as you offer spare parts or customer support for that product - model, to give anyone who possesses the object code either (1) a - copy of the Corresponding Source for all the software in the - product that is covered by this License, on a durable physical - medium customarily used for software interchange, for a price no - more than your reasonable cost of physically performing this - conveying of source, or (2) access to copy the - Corresponding Source from a network server at no charge. - - c) Convey individual copies of the object code with a copy of the - written offer to provide the Corresponding Source. This - alternative is allowed only occasionally and noncommercially, and - only if you received the object code with such an offer, in accord - with subsection 6b. - - d) Convey the object code by offering access from a designated - place (gratis or for a charge), and offer equivalent access to the - Corresponding Source in the same way through the same place at no - further charge. You need not require recipients to copy the - Corresponding Source along with the object code. If the place to - copy the object code is a network server, the Corresponding Source - may be on a different server (operated by you or a third party) - that supports equivalent copying facilities, provided you maintain - clear directions next to the object code saying where to find the - Corresponding Source. Regardless of what server hosts the - Corresponding Source, you remain obligated to ensure that it is - available for as long as needed to satisfy these requirements. - - e) Convey the object code using peer-to-peer transmission, provided - you inform other peers where the object code and Corresponding - Source of the work are being offered to the general public at no - charge under subsection 6d. - - A separable portion of the object code, whose source code is excluded -from the Corresponding Source as a System Library, need not be -included in conveying the object code work. - - A "User Product" is either (1) a "consumer product", which means any -tangible personal property which is normally used for personal, family, -or household purposes, or (2) anything designed or sold for incorporation -into a dwelling. In determining whether a product is a consumer product, -doubtful cases shall be resolved in favor of coverage. For a particular -product received by a particular user, "normally used" refers to a -typical or common use of that class of product, regardless of the status -of the particular user or of the way in which the particular user -actually uses, or expects or is expected to use, the product. A product -is a consumer product regardless of whether the product has substantial -commercial, industrial or non-consumer uses, unless such uses represent -the only significant mode of use of the product. - - "Installation Information" for a User Product means any methods, -procedures, authorization keys, or other information required to install -and execute modified versions of a covered work in that User Product from -a modified version of its Corresponding Source. The information must -suffice to ensure that the continued functioning of the modified object -code is in no case prevented or interfered with solely because -modification has been made. - - If you convey an object code work under this section in, or with, or -specifically for use in, a User Product, and the conveying occurs as -part of a transaction in which the right of possession and use of the -User Product is transferred to the recipient in perpetuity or for a -fixed term (regardless of how the transaction is characterized), the -Corresponding Source conveyed under this section must be accompanied -by the Installation Information. But this requirement does not apply -if neither you nor any third party retains the ability to install -modified object code on the User Product (for example, the work has -been installed in ROM). - - The requirement to provide Installation Information does not include a -requirement to continue to provide support service, warranty, or updates -for a work that has been modified or installed by the recipient, or for -the User Product in which it has been modified or installed. Access to a -network may be denied when the modification itself materially and -adversely affects the operation of the network or violates the rules and -protocols for communication across the network. - - Corresponding Source conveyed, and Installation Information provided, -in accord with this section must be in a format that is publicly -documented (and with an implementation available to the public in -source code form), and must require no special password or key for -unpacking, reading or copying. - - 7. Additional Terms. - - "Additional permissions" are terms that supplement the terms of this -License by making exceptions from one or more of its conditions. -Additional permissions that are applicable to the entire Program shall -be treated as though they were included in this License, to the extent -that they are valid under applicable law. If additional permissions -apply only to part of the Program, that part may be used separately -under those permissions, but the entire Program remains governed by -this License without regard to the additional permissions. - - When you convey a copy of a covered work, you may at your option -remove any additional permissions from that copy, or from any part of -it. (Additional permissions may be written to require their own -removal in certain cases when you modify the work.) You may place -additional permissions on material, added by you to a covered work, -for which you have or can give appropriate copyright permission. - - Notwithstanding any other provision of this License, for material you -add to a covered work, you may (if authorized by the copyright holders of -that material) supplement the terms of this License with terms: - - a) Disclaiming warranty or limiting liability differently from the - terms of sections 15 and 16 of this License; or - - b) Requiring preservation of specified reasonable legal notices or - author attributions in that material or in the Appropriate Legal - Notices displayed by works containing it; or - - c) Prohibiting misrepresentation of the origin of that material, or - requiring that modified versions of such material be marked in - reasonable ways as different from the original version; or - - d) Limiting the use for publicity purposes of names of licensors or - authors of the material; or - - e) Declining to grant rights under trademark law for use of some - trade names, trademarks, or service marks; or - - f) Requiring indemnification of licensors and authors of that - material by anyone who conveys the material (or modified versions of - it) with contractual assumptions of liability to the recipient, for - any liability that these contractual assumptions directly impose on - those licensors and authors. - - All other non-permissive additional terms are considered "further -restrictions" within the meaning of section 10. If the Program as you -received it, or any part of it, contains a notice stating that it is -governed by this License along with a term that is a further -restriction, you may remove that term. If a license document contains -a further restriction but permits relicensing or conveying under this -License, you may add to a covered work material governed by the terms -of that license document, provided that the further restriction does -not survive such relicensing or conveying. - - If you add terms to a covered work in accord with this section, you -must place, in the relevant source files, a statement of the -additional terms that apply to those files, or a notice indicating -where to find the applicable terms. - - Additional terms, permissive or non-permissive, may be stated in the -form of a separately written license, or stated as exceptions; -the above requirements apply either way. - - 8. Termination. - - You may not propagate or modify a covered work except as expressly -provided under this License. Any attempt otherwise to propagate or -modify it is void, and will automatically terminate your rights under -this License (including any patent licenses granted under the third -paragraph of section 11). - - However, if you cease all violation of this License, then your -license from a particular copyright holder is reinstated (a) -provisionally, unless and until the copyright holder explicitly and -finally terminates your license, and (b) permanently, if the copyright -holder fails to notify you of the violation by some reasonable means -prior to 60 days after the cessation. - - Moreover, your license from a particular copyright holder is -reinstated permanently if the copyright holder notifies you of the -violation by some reasonable means, this is the first time you have -received notice of violation of this License (for any work) from that -copyright holder, and you cure the violation prior to 30 days after -your receipt of the notice. - - Termination of your rights under this section does not terminate the -licenses of parties who have received copies or rights from you under -this License. If your rights have been terminated and not permanently -reinstated, you do not qualify to receive new licenses for the same -material under section 10. - - 9. Acceptance Not Required for Having Copies. - - You are not required to accept this License in order to receive or -run a copy of the Program. Ancillary propagation of a covered work -occurring solely as a consequence of using peer-to-peer transmission -to receive a copy likewise does not require acceptance. However, -nothing other than this License grants you permission to propagate or -modify any covered work. These actions infringe copyright if you do -not accept this License. Therefore, by modifying or propagating a -covered work, you indicate your acceptance of this License to do so. - - 10. Automatic Licensing of Downstream Recipients. - - Each time you convey a covered work, the recipient automatically -receives a license from the original licensors, to run, modify and -propagate that work, subject to this License. You are not responsible -for enforcing compliance by third parties with this License. - - An "entity transaction" is a transaction transferring control of an -organization, or substantially all assets of one, or subdividing an -organization, or merging organizations. If propagation of a covered -work results from an entity transaction, each party to that -transaction who receives a copy of the work also receives whatever -licenses to the work the party's predecessor in interest had or could -give under the previous paragraph, plus a right to possession of the -Corresponding Source of the work from the predecessor in interest, if -the predecessor has it or can get it with reasonable efforts. - - You may not impose any further restrictions on the exercise of the -rights granted or affirmed under this License. For example, you may -not impose a license fee, royalty, or other charge for exercise of -rights granted under this License, and you may not initiate litigation -(including a cross-claim or counterclaim in a lawsuit) alleging that -any patent claim is infringed by making, using, selling, offering for -sale, or importing the Program or any portion of it. - - 11. Patents. - - A "contributor" is a copyright holder who authorizes use under this -License of the Program or a work on which the Program is based. The -work thus licensed is called the contributor's "contributor version". - - A contributor's "essential patent claims" are all patent claims -owned or controlled by the contributor, whether already acquired or -hereafter acquired, that would be infringed by some manner, permitted -by this License, of making, using, or selling its contributor version, -but do not include claims that would be infringed only as a -consequence of further modification of the contributor version. For -purposes of this definition, "control" includes the right to grant -patent sublicenses in a manner consistent with the requirements of -this License. - - Each contributor grants you a non-exclusive, worldwide, royalty-free -patent license under the contributor's essential patent claims, to -make, use, sell, offer for sale, import and otherwise run, modify and -propagate the contents of its contributor version. - - In the following three paragraphs, a "patent license" is any express -agreement or commitment, however denominated, not to enforce a patent -(such as an express permission to practice a patent or covenant not to -sue for patent infringement). To "grant" such a patent license to a -party means to make such an agreement or commitment not to enforce a -patent against the party. - - If you convey a covered work, knowingly relying on a patent license, -and the Corresponding Source of the work is not available for anyone -to copy, free of charge and under the terms of this License, through a -publicly available network server or other readily accessible means, -then you must either (1) cause the Corresponding Source to be so -available, or (2) arrange to deprive yourself of the benefit of the -patent license for this particular work, or (3) arrange, in a manner -consistent with the requirements of this License, to extend the patent -license to downstream recipients. "Knowingly relying" means you have -actual knowledge that, but for the patent license, your conveying the -covered work in a country, or your recipient's use of the covered work -in a country, would infringe one or more identifiable patents in that -country that you have reason to believe are valid. - - If, pursuant to or in connection with a single transaction or -arrangement, you convey, or propagate by procuring conveyance of, a -covered work, and grant a patent license to some of the parties -receiving the covered work authorizing them to use, propagate, modify -or convey a specific copy of the covered work, then the patent license -you grant is automatically extended to all recipients of the covered -work and works based on it. - - A patent license is "discriminatory" if it does not include within -the scope of its coverage, prohibits the exercise of, or is -conditioned on the non-exercise of one or more of the rights that are -specifically granted under this License. You may not convey a covered -work if you are a party to an arrangement with a third party that is -in the business of distributing software, under which you make payment -to the third party based on the extent of your activity of conveying -the work, and under which the third party grants, to any of the -parties who would receive the covered work from you, a discriminatory -patent license (a) in connection with copies of the covered work -conveyed by you (or copies made from those copies), or (b) primarily -for and in connection with specific products or compilations that -contain the covered work, unless you entered into that arrangement, -or that patent license was granted, prior to 28 March 2007. - - Nothing in this License shall be construed as excluding or limiting -any implied license or other defenses to infringement that may -otherwise be available to you under applicable patent law. - - 12. No Surrender of Others' Freedom. - - If conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot convey a -covered work so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you may -not convey it at all. For example, if you agree to terms that obligate you -to collect a royalty for further conveying from those to whom you convey -the Program, the only way you could satisfy both those terms and this -License would be to refrain entirely from conveying the Program. - - 13. Use with the GNU Affero General Public License. - - Notwithstanding any other provision of this License, you have -permission to link or combine any covered work with a work licensed -under version 3 of the GNU Affero General Public License into a single -combined work, and to convey the resulting work. The terms of this -License will continue to apply to the part which is the covered work, -but the special requirements of the GNU Affero General Public License, -section 13, concerning interaction through a network will apply to the -combination as such. - - 14. Revised Versions of this License. - - The Free Software Foundation may publish revised and/or new versions of -the GNU General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to -address new problems or concerns. - - Each version is given a distinguishing version number. If the -Program specifies that a certain numbered version of the GNU General -Public License "or any later version" applies to it, you have the -option of following the terms and conditions either of that numbered -version or of any later version published by the Free Software -Foundation. If the Program does not specify a version number of the -GNU General Public License, you may choose any version ever published -by the Free Software Foundation. - - If the Program specifies that a proxy can decide which future -versions of the GNU General Public License can be used, that proxy's -public statement of acceptance of a version permanently authorizes you -to choose that version for the Program. - - Later license versions may give you additional or different -permissions. However, no additional obligations are imposed on any -author or copyright holder as a result of your choosing to follow a -later version. - - 15. Disclaimer of Warranty. - - THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY -APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT -HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY -OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, -THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR -PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM -IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF -ALL NECESSARY SERVICING, REPAIR OR CORRECTION. - - 16. Limitation of Liability. - - IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING -WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS -THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY -GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE -USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF -DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD -PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), -EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF -SUCH DAMAGES. - - 17. Interpretation of Sections 15 and 16. - - If the disclaimer of warranty and limitation of liability provided -above cannot be given local legal effect according to their terms, -reviewing courts shall apply local law that most closely approximates -an absolute waiver of all civil liability in connection with the -Program, unless a warranty or assumption of liability accompanies a -copy of the Program in return for a fee. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Programs - - If you develop a new program, and you want it to be of the greatest -possible use to the public, the best way to achieve this is to make it -free software which everyone can redistribute and change under these terms. - - To do so, attach the following notices to the program. It is safest -to attach them to the start of each source file to most effectively -state the exclusion of warranty; and each file should have at least -the "copyright" line and a pointer to where the full notice is found. - - - Copyright (C) - - This program 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. - - This program 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 this program. If not, see . - -Also add information on how to contact you by electronic and paper mail. - - If the program does terminal interaction, make it output a short -notice like this when it starts in an interactive mode: - - Copyright (C) - This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, your program's commands -might be different; for a GUI interface, you would use an "about box". - - You should also get your employer (if you work as a programmer) or school, -if any, to sign a "copyright disclaimer" for the program, if necessary. -For more information on this, and how to apply and follow the GNU GPL, see -. - - The GNU General Public License does not permit incorporating your program -into proprietary programs. If your program is a subroutine library, you -may consider it more useful to permit linking proprietary applications with -the library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. But first, please read -. diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw b/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw deleted file mode 100644 index 904771486..000000000 Binary files a/src/modules/attitude_estimator_so3_comp/visualization_code/FreeIMU_yaw_pitch_roll/data/CourierNew36.vlw and /dev/null differ diff --git a/src/modules/attitude_estimator_so3_comp/visualization_code/README b/src/modules/attitude_estimator_so3_comp/visualization_code/README deleted file mode 100644 index c02863343..000000000 --- a/src/modules/attitude_estimator_so3_comp/visualization_code/README +++ /dev/null @@ -1,9 +0,0 @@ -If you run the attitude estimator by following command, the software will write packets -over /dev/ttyS1 which is used for 3D visualization. - - nsh> attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200 - -This visualization code can be executed by Processing. - Download : http://www.processing.org/download/ - -The visualization code works with Processing version 1.5.1. -- cgit v1.2.3 From 7e95edbbe848ec49ee81dbd85dc8c91558a83aa8 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 28 May 2013 19:02:16 +0400 Subject: New messages added to sdlog2 --- src/modules/sdlog2/sdlog2.c | 189 ++++++++++++++++++++--------------- src/modules/sdlog2/sdlog2_format.h | 2 +- src/modules/sdlog2/sdlog2_messages.h | 77 +++++++++++--- 3 files changed, 172 insertions(+), 96 deletions(-) (limited to 'src') diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 8d4d2f8ce..48d107945 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -81,6 +81,7 @@ #include #include "sdlog2_ringbuffer.h" +#include "sdlog2_format.h" #include "sdlog2_messages.h" static bool thread_should_exit = false; /**< Deamon exit flag */ @@ -447,7 +448,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 25; + const ssize_t fdsc = 13; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -455,7 +456,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* warning! using union here to save memory, elements should be used separately! */ union { - struct sensor_combined_s raw; + struct sensor_combined_s sensor; struct vehicle_attitude_s att; struct vehicle_attitude_setpoint_s att_sp; struct actuator_outputs_s act_outputs; @@ -478,9 +479,9 @@ int sdlog2_thread_main(int argc, char *argv[]) int sensor_sub; int att_sub; int att_sp_sub; - int act_0_sub; - int controls_0_sub; - int controls_effective_0_sub; + int act_outputs_sub; + int act_controls_sub; + int act_controls_effective_sub; int local_pos_sub; int global_pos_sub; int gps_pos_sub; @@ -496,9 +497,13 @@ int sdlog2_thread_main(int argc, char *argv[]) struct { LOG_PACKET_HEADER; union { - struct log_TS_s log_TS; + struct log_TIME_s log_TIME; struct log_ATT_s log_ATT; - struct log_RAW_s log_RAW; + struct log_ATSP_s log_ATSP; + struct log_IMU_s log_IMU; + struct log_SENS_s log_SENS; + struct log_LPOS_s log_LPOS; + struct log_LPSP_s log_LPSP; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -514,14 +519,12 @@ int sdlog2_thread_main(int argc, char *argv[]) fdsc_count++; /* --- GPS POSITION --- */ - /* subscribe to ORB for global position */ subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); fds[fdsc_count].fd = subs.gps_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- SENSORS RAW VALUE --- */ - /* subscribe to ORB for sensors raw */ subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); fds[fdsc_count].fd = subs.sensor_sub; /* do not rate limit, instead use skip counter (aliasing on rate limit) */ @@ -529,89 +532,65 @@ int sdlog2_thread_main(int argc, char *argv[]) fdsc_count++; /* --- ATTITUDE VALUE --- */ - /* subscribe to ORB for attitude */ subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); fds[fdsc_count].fd = subs.att_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- ATTITUDE SETPOINT VALUE --- */ - /* subscribe to ORB for attitude setpoint */ - /* struct already allocated */ subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); fds[fdsc_count].fd = subs.att_sp_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /** --- ACTUATOR OUTPUTS --- */ - subs.act_0_sub = orb_subscribe(ORB_ID(actuator_outputs_0)); - fds[fdsc_count].fd = subs.act_0_sub; + /* --- ACTUATOR OUTPUTS --- */ + subs.act_outputs_sub = orb_subscribe(ORB_ID(actuator_outputs_0)); + fds[fdsc_count].fd = subs.act_outputs_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- ACTUATOR CONTROL VALUE --- */ - /* subscribe to ORB for actuator control */ - subs.controls_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); - fds[fdsc_count].fd = subs.controls_0_sub; + subs.act_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); + fds[fdsc_count].fd = subs.act_controls_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ - /* subscribe to ORB for actuator control */ - subs.controls_effective_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE); - fds[fdsc_count].fd = subs.controls_effective_0_sub; + subs.act_controls_effective_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE); + fds[fdsc_count].fd = subs.act_controls_effective_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- LOCAL POSITION --- */ - /* subscribe to ORB for local position */ subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); fds[fdsc_count].fd = subs.local_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- GLOBAL POSITION --- */ - /* subscribe to ORB for global position */ subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); fds[fdsc_count].fd = subs.global_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- VICON POSITION --- */ - /* subscribe to ORB for vicon position */ subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position)); fds[fdsc_count].fd = subs.vicon_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- FLOW measurements --- */ - /* subscribe to ORB for flow measurements */ subs.flow_sub = orb_subscribe(ORB_ID(optical_flow)); fds[fdsc_count].fd = subs.flow_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; /* --- BATTERY STATUS --- */ - /* subscribe to ORB for flow measurements */ subs.batt_sub = orb_subscribe(ORB_ID(battery_status)); fds[fdsc_count].fd = subs.batt_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- DIFFERENTIAL PRESSURE --- */ - /* subscribe to ORB for flow measurements */ - subs.diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); - fds[fdsc_count].fd = subs.diff_pres_sub; - fds[fdsc_count].events = POLLIN; - fdsc_count++; - - /* --- AIRSPEED --- */ - /* subscribe to ORB for airspeed */ - subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed)); - fds[fdsc_count].fd = subs.airspeed_sub; - fds[fdsc_count].events = POLLIN; - fdsc_count++; - /* WARNING: If you get the error message below, * then the number of registered messages (fdsc) * differs from the number of messages in the above list. @@ -625,7 +604,7 @@ int sdlog2_thread_main(int argc, char *argv[]) * set up poll to block for new data, * wait for a maximum of 1000 ms (1 second) */ - // const int timeout = 1000; + const int poll_timeout = 1000; thread_running = true; @@ -641,13 +620,17 @@ int sdlog2_thread_main(int argc, char *argv[]) starttime = hrt_absolute_time(); - /* track skipping */ - int skip_count = 0; + /* track changes in sensor_combined topic */ + uint16_t gyro_counter = 0; + uint16_t accelerometer_counter = 0; + uint16_t magnetometer_counter = 0; + uint16_t baro_counter = 0; + uint16_t differential_pressure_counter = 0; while (!thread_should_exit) { /* poll all topics */ - int poll_ret = poll(fds, 4, 1000); + int poll_ret = poll(fds, fdsc, poll_timeout); /* handle the poll result */ if (poll_ret == 0) { @@ -666,11 +649,11 @@ int sdlog2_thread_main(int argc, char *argv[]) pthread_mutex_lock(&logbuffer_mutex); /* write time stamp message */ - log_msg.msg_type = LOG_TS_MSG; - log_msg.body.log_TS.t = hrt_absolute_time(); - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(TS)); + log_msg.msg_type = LOG_TIME_MSG; + log_msg.body.log_TIME.t = hrt_absolute_time(); + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(TIME)); - /* --- VEHICLE COMMAND VALUE --- */ + /* --- VEHICLE COMMAND --- */ if (fds[ifds++].revents & POLLIN) { /* copy command into local buffer */ orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd); @@ -680,19 +663,58 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- GPS POSITION --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + // TODO not implemented yet } - /* --- SENSORS RAW VALUE --- */ + /* --- SENSOR COMBINED --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.raw); - log_msg.msg_type = LOG_RAW_MSG; - log_msg.body.log_RAW.accX = buf.raw.accelerometer_m_s2[0]; - log_msg.body.log_RAW.accY = buf.raw.accelerometer_m_s2[1]; - log_msg.body.log_RAW.accZ = buf.raw.accelerometer_m_s2[2]; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(RAW)); + orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor); + bool write_IMU = false; + bool write_SENS = false; + if (buf.sensor.gyro_counter != gyro_counter) { + gyro_counter = buf.sensor.gyro_counter; + write_IMU = true; + } + if (buf.sensor.accelerometer_counter != accelerometer_counter) { + accelerometer_counter = buf.sensor.accelerometer_counter; + write_IMU = true; + } + if (buf.sensor.magnetometer_counter != magnetometer_counter) { + magnetometer_counter = buf.sensor.magnetometer_counter; + write_IMU = true; + } + if (buf.sensor.baro_counter != baro_counter) { + baro_counter = buf.sensor.baro_counter; + write_SENS = true; + } + if (buf.sensor.differential_pressure_counter != differential_pressure_counter) { + differential_pressure_counter = buf.sensor.differential_pressure_counter; + write_SENS = true; + } + if (write_IMU) { + log_msg.msg_type = LOG_IMU_MSG; + log_msg.body.log_IMU.gyro_x = buf.sensor.gyro_rad_s[0]; + log_msg.body.log_IMU.gyro_y = buf.sensor.gyro_rad_s[1]; + log_msg.body.log_IMU.gyro_z = buf.sensor.gyro_rad_s[2]; + log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer_m_s2[0]; + log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer_m_s2[1]; + log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer_m_s2[2]; + log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer_ga[0]; + log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer_ga[1]; + log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2]; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(IMU)); + } + if (write_SENS) { + log_msg.msg_type = LOG_SENS_MSG; + log_msg.body.log_SENS.baro_pres = buf.sensor.baro_pres_mbar; + log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter; + log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius; + log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure_pa; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(SENS)); + } } - /* --- ATTITUDE VALUE --- */ + /* --- ATTITUDE --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att); log_msg.msg_type = LOG_ATT_MSG; @@ -702,69 +724,72 @@ int sdlog2_thread_main(int argc, char *argv[]) sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATT)); } - /* --- ATTITUDE SETPOINT VALUE --- */ + /* --- ATTITUDE SETPOINT --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_attitude_setpoint), subs.att_sp_sub, &buf.att_sp); - // TODO not implemented yet + log_msg.msg_type = LOG_ATSP_MSG; + log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body; + log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body; + log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATSP)); } /* --- ACTUATOR OUTPUTS --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs); // TODO not implemented yet } - /* --- ACTUATOR CONTROL VALUE --- */ + /* --- ACTUATOR CONTROL --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, subs.act_controls_sub, &buf.act_controls); // TODO not implemented yet } - /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ + /* --- ACTUATOR CONTROL EFFECTIVE --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE, subs.act_controls_effective_sub, &buf.act_controls_effective); // TODO not implemented yet } /* --- LOCAL POSITION --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); - // TODO not implemented yet + orb_copy(ORB_ID(vehicle_local_position), subs.local_pos_sub, &buf.local_pos); + log_msg.msg_type = LOG_LPOS_MSG; + log_msg.body.log_LPOS.x = buf.local_pos.x; + log_msg.body.log_LPOS.y = buf.local_pos.y; + log_msg.body.log_LPOS.z = buf.local_pos.z; + log_msg.body.log_LPOS.vx = buf.local_pos.vx; + log_msg.body.log_LPOS.vy = buf.local_pos.vy; + log_msg.body.log_LPOS.vz = buf.local_pos.vz; + log_msg.body.log_LPOS.hdg = buf.local_pos.hdg; + log_msg.body.log_LPOS.home_lat = buf.local_pos.home_lat; + log_msg.body.log_LPOS.home_lon = buf.local_pos.home_lon; + log_msg.body.log_LPOS.home_alt = buf.local_pos.home_alt; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(LPOS)); } /* --- GLOBAL POSITION --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(vehicle_global_position), subs.global_pos_sub, &buf.global_pos); // TODO not implemented yet } /* --- VICON POSITION --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos); // TODO not implemented yet } - /* --- FLOW measurements --- */ + /* --- FLOW --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(optical_flow), subs.flow_sub, &buf.flow); // TODO not implemented yet } /* --- BATTERY STATUS --- */ if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); - // TODO not implemented yet - } - - /* --- DIFFERENTIAL PRESSURE --- */ - if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); - // TODO not implemented yet - } - - /* --- AIRSPEED --- */ - if (fds[ifds++].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); + orb_copy(ORB_ID(battery_status), subs.batt_sub, &buf.batt); // TODO not implemented yet } diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h index bbf8b6f12..59b91d90d 100644 --- a/src/modules/sdlog2/sdlog2_format.h +++ b/src/modules/sdlog2/sdlog2_format.h @@ -93,6 +93,6 @@ struct log_format_s { #define LOG_FORMAT_MSG 0x80 -#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(log_msg.body.log_##_name) +#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(struct log_##_name##_s) #endif /* SDLOG2_FORMAT_H_ */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index ae98ea038..0bc999e24 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -47,13 +47,13 @@ /* define message formats */ -/* === 1: TS - TIME STAMP === */ -#define LOG_TS_MSG 1 -struct log_TS_s { +/* --- TIME - TIME STAMP --- */ +#define LOG_TIME_MSG 1 +struct log_TIME_s { uint64_t t; }; -/* === 2: ATT - ATTITUDE === */ +/* --- ATT - ATTITUDE --- */ #define LOG_ATT_MSG 2 struct log_ATT_s { float roll; @@ -61,20 +61,71 @@ struct log_ATT_s { float yaw; }; -/* === 3: RAW - SENSORS === */ -#define LOG_RAW_MSG 3 -struct log_RAW_s { - float accX; - float accY; - float accZ; +/* --- ATSP - ATTITUDE SET POINT --- */ +#define LOG_ATSP_MSG 3 +struct log_ATSP_s { + float roll_sp; + float pitch_sp; + float yaw_sp; +}; + +/* --- IMU - IMU SENSORS --- */ +#define LOG_IMU_MSG 4 +struct log_IMU_s { + float acc_x; + float acc_y; + float acc_z; + float gyro_x; + float gyro_y; + float gyro_z; + float mag_x; + float mag_y; + float mag_z; +}; + +/* --- SENS - OTHER SENSORS --- */ +#define LOG_SENS_MSG 5 +struct log_SENS_s { + float baro_pres; + float baro_alt; + float baro_temp; + float diff_pres; +}; + +/* --- LPOS - LOCAL POSITION --- */ +#define LOG_LPOS_MSG 6 +struct log_LPOS_s { + float x; + float y; + float z; + float vx; + float vy; + float vz; + float hdg; + int32_t home_lat; + int32_t home_lon; + float home_alt; +}; + +/* --- LPOS - LOCAL POSITION SETPOINT --- */ +#define LOG_LPSP_MSG 7 +struct log_LPSP_s { + float x; + float y; + float z; + float yaw; }; /* construct list of all message formats */ static const struct log_format_s log_formats[] = { - LOG_FORMAT(TS, "Q", "t"), - LOG_FORMAT(ATT, "fff", "roll,pitch,yaw"), - LOG_FORMAT(RAW, "fff", "accX,accY,accZ"), + LOG_FORMAT(TIME, "Q", "t"), + LOG_FORMAT(ATT, "fff", "Roll,Pitch,Yaw"), + LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"), + LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), + LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), + LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"), + LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); -- cgit v1.2.3 From d6ae0461ab5c89f87ac10a2304d55a893d0f72f9 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 30 May 2013 12:28:05 +0400 Subject: sdlog2: GPS message added --- src/modules/sdlog2/sdlog2.c | 15 ++++++++++++++- src/modules/sdlog2/sdlog2_messages.h | 21 +++++++++++++++++++-- 2 files changed, 33 insertions(+), 3 deletions(-) (limited to 'src') diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 48d107945..8aa4db934 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -504,6 +504,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_SENS_s log_SENS; struct log_LPOS_s log_LPOS; struct log_LPSP_s log_LPSP; + struct log_GPS_s log_GPS; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -663,7 +664,19 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- GPS POSITION --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos); - // TODO not implemented yet + log_msg.msg_type = LOG_GPS_MSG; + log_msg.body.log_GPS.gps_time = buf.gps_pos.time_gps_usec; + log_msg.body.log_GPS.fix_type = buf.gps_pos.fix_type; + log_msg.body.log_GPS.satellites_visible = buf.gps_pos.satellites_visible; + log_msg.body.log_GPS.lat = buf.gps_pos.lat; + log_msg.body.log_GPS.lon = buf.gps_pos.lon; + log_msg.body.log_GPS.alt = buf.gps_pos.alt; + log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s; + log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s; + log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s; + log_msg.body.log_GPS.cog = buf.gps_pos.cog_rad; + log_msg.body.log_GPS.vel_valid = (uint8_t) buf.gps_pos.vel_ned_valid; + sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(GPS)); } /* --- SENSOR COMBINED --- */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 0bc999e24..3ff597815 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -107,7 +107,7 @@ struct log_LPOS_s { float home_alt; }; -/* --- LPOS - LOCAL POSITION SETPOINT --- */ +/* --- LPSP - LOCAL POSITION SETPOINT --- */ #define LOG_LPSP_MSG 7 struct log_LPSP_s { float x; @@ -116,16 +116,33 @@ struct log_LPSP_s { float yaw; }; +/* --- GPS - GPS POSITION --- */ +#define LOG_GPS_MSG 8 +struct log_GPS_s { + uint64_t gps_time; + uint8_t fix_type; + uint8_t satellites_visible; + int32_t lat; + int32_t lon; + float alt; + float vel_n; + float vel_e; + float vel_d; + float cog; + uint8_t vel_valid; +}; + /* construct list of all message formats */ static const struct log_format_s log_formats[] = { - LOG_FORMAT(TIME, "Q", "t"), + LOG_FORMAT(TIME, "Q", "StartTime"), LOG_FORMAT(ATT, "fff", "Roll,Pitch,Yaw"), LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"), LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"), LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), + LOG_FORMAT(GPS, "QBBLLfffffB", "GPSTime,FixType,Sats,Lat,Lon,Alt,VelN,VelE,VelD,Cog,VelValid"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); -- cgit v1.2.3 From 9952fef645a04ca3b0d86dcb7bae203f27c77a03 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 30 May 2013 21:27:55 +0400 Subject: sdlog2 messages packing fixed, sdlog2_dump.py now produces much more compressed output. --- Tools/sdlog2_dump.py | 51 +++++++++++++++++++++++++----------- src/modules/sdlog2/sdlog2_messages.h | 2 ++ 2 files changed, 38 insertions(+), 15 deletions(-) (limited to 'src') diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index fa02a3723..e4a4e2425 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -50,6 +50,7 @@ class SDLog2Parser: __csv_delim = "," __csv_null = "" __msg_filter = [] + __time_msg = None __debug_out = False def __init__(self): @@ -63,6 +64,7 @@ class SDLog2Parser: self.__ptr = 0 # read pointer in buffer self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" self.__csv_data = {} # current values for all columns + self.__csv_updated = False self.__msg_filter_map = {} # filter in form of map, with '*" expanded to full list of fields def setCSVDelimiter(self, csv_delim): @@ -74,6 +76,9 @@ class SDLog2Parser: def setMsgFilter(self, msg_filter): self.__msg_filter = msg_filter + def setTimeMsg(self, time_msg): + self.__time_msg = time_msg + def setDebugOut(self, debug_out): self.__debug_out = debug_out @@ -115,7 +120,8 @@ class SDLog2Parser: self.__initCSV() first_data_msg = False self.__parseMsg(msg_descr) - + if not self.__debug_out and self.__time_msg != None and self.__csv_updated: + self.__printCSVRow() f.close() def __bytesLeft(self): @@ -140,7 +146,18 @@ class SDLog2Parser: self.__csv_columns.append(full_label) self.__csv_data[full_label] = None print self.__csv_delim.join(self.__csv_columns) - + + def __printCSVRow(self): + s = [] + for full_label in self.__csv_columns: + v = self.__csv_data[full_label] + if v == None: + v = self.__csv_null + else: + v = str(v) + s.append(v) + print self.__csv_delim.join(s) + def __parseMsgDescr(self): data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] @@ -171,6 +188,9 @@ class SDLog2Parser: def __parseMsg(self, msg_descr): msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults = msg_descr + if not self.__debug_out and self.__time_msg != None and msg_name == self.__time_msg and self.__csv_updated: + self.__printCSVRow() + self.__csv_updated = False show_fields = self.__filterMsg(msg_name) if (show_fields != None): data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) @@ -193,31 +213,27 @@ class SDLog2Parser: label = msg_labels[i] if label in show_fields: self.__csv_data[msg_name + "." + label] = data[i] - # format and print CSV row - s = [] - for full_label in self.__csv_columns: - v = self.__csv_data[full_label] - if v == None: - v = self.__csv_null - else: - v = str(v) - s.append(v) - print self.__csv_delim.join(s) + if self.__time_msg != None and msg_name != self.__time_msg: + self.__csv_updated = True + if self.__time_msg == None: + self.__printCSVRow() self.__ptr += msg_length def _main(): if len(sys.argv) < 2: - print "Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]]\n" + print "Usage: python sdlog2_dump.py [-v] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n" print "\t-v\tUse plain debug output instead of CSV.\n" print "\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n" print "\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n" print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed." + print "\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n" return fn = sys.argv[1] debug_out = False msg_filter = [] csv_null = "" csv_delim = "," + time_msg = None opt = None for arg in sys.argv[2:]: if opt != None: @@ -225,7 +241,9 @@ def _main(): csv_delim = arg elif opt == "n": csv_null = arg - if opt == "m": + elif opt == "t": + time_msg = arg + elif opt == "m": show_fields = "*" a = arg.split(".") if len(a) > 1: @@ -241,13 +259,16 @@ def _main(): opt = "n" elif arg == "-m": opt = "m" - + elif arg == "-t": + opt = "t" + if csv_delim == "\\t": csv_delim = "\t" parser = SDLog2Parser() parser.setCSVDelimiter(csv_delim) parser.setCSVNull(csv_null) parser.setMsgFilter(msg_filter) + parser.setTimeMsg(time_msg) parser.setDebugOut(debug_out) parser.process(fn) diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 3ff597815..2baccc106 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -47,6 +47,7 @@ /* define message formats */ +#pragma pack(push, 1) /* --- TIME - TIME STAMP --- */ #define LOG_TIME_MSG 1 struct log_TIME_s { @@ -131,6 +132,7 @@ struct log_GPS_s { float cog; uint8_t vel_valid; }; +#pragma pack(pop) /* construct list of all message formats */ -- cgit v1.2.3 From b614d2f1eb3b3ddd26fa22a1a0761a5aef52c1a8 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 30 May 2013 23:41:06 +0400 Subject: adlog2: added options cleanup, updates rate limit added --- src/modules/sdlog2/sdlog2.c | 75 ++++++++++++++++++++++++++++----------------- 1 file changed, 47 insertions(+), 28 deletions(-) (limited to 'src') diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 8aa4db934..2422a15f4 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -152,14 +152,19 @@ usage(const char *reason) if (reason) fprintf(stderr, "%s\n", reason); - errx(1, "usage: sdlog2 {start|stop|status} [-s ]\n\n"); + errx(1, "usage: sdlog2 {start|stop|status} [-r ] -e -a\n" + "\t-r\tLog rate in Hz, 0 means unlimited rate\n" + "\t-e\tEnable logging by default (if not, can be started by command)\n" + "\t-a\tLog only when armed (can be still overriden by command)\n\n"); } unsigned long log_bytes_written = 0; -uint64_t starttime = 0; +uint64_t start_time = 0; /* logging on or off, default to true */ -bool logging_enabled = true; +bool logging_enabled = false; +bool log_when_armed = false; +useconds_t poll_delay = 0; /** * The sd log deamon app only briefly exists to start @@ -384,24 +389,26 @@ int sdlog2_thread_main(int argc, char *argv[]) argv += 2; int ch; - while ((ch = getopt(argc, argv, "s:r")) != EOF) { + while ((ch = getopt(argc, argv, "r:ea")) != EOF) { switch (ch) { - case 's': { - /* log only every n'th (gyro clocked) value */ - unsigned s = strtoul(optarg, NULL, 10); + case 'r': { + unsigned r = strtoul(optarg, NULL, 10); - if (s < 1 || s > 250) { - errx(1, "Wrong skip value of %d, out of range (1..250)\n", s); + if (r == 0) { + poll_delay = 0; } else { - skip_value = s; + poll_delay = 1000000 / r; } } break; - case 'r': - /* log only on request, disable logging per default */ - logging_enabled = false; + case 'e': + logging_enabled = true; + break; + + case 'a': + log_when_armed = true; break; case '?': @@ -493,7 +500,7 @@ int sdlog2_thread_main(int argc, char *argv[]) } subs; /* log message buffer: header + body */ - #pragma pack(push, 1) +#pragma pack(push, 1) struct { LOG_PACKET_HEADER; union { @@ -509,7 +516,7 @@ int sdlog2_thread_main(int argc, char *argv[]) } log_msg = { LOG_PACKET_HEADER_INIT(0) }; - #pragma pack(pop) +#pragma pack(pop) memset(&log_msg.body, 0, sizeof(log_msg.body)); /* --- MANAGEMENT - LOGGING COMMAND --- */ @@ -619,7 +626,9 @@ int sdlog2_thread_main(int argc, char *argv[]) /* start logbuffer emptying thread */ pthread_t logwriter_pthread = sdlog2_logwriter_start(&lb); - starttime = hrt_absolute_time(); + /* initialize statistics counter */ + log_bytes_written = 0; + start_time = hrt_absolute_time(); /* track changes in sensor_combined topic */ uint16_t gyro_counter = 0; @@ -629,23 +638,22 @@ int sdlog2_thread_main(int argc, char *argv[]) uint16_t differential_pressure_counter = 0; while (!thread_should_exit) { + if (!logging_enabled) { + usleep(100000); + continue; + } /* poll all topics */ - int poll_ret = poll(fds, fdsc, poll_timeout); + int poll_ret = poll(fds, fdsc, poll_delay == 0 ? poll_timeout : 0); /* handle the poll result */ - if (poll_ret == 0) { - /* XXX this means none of our providers is giving us data - might be an error? */ - } else if (poll_ret < 0) { - /* XXX this is seriously bad - should be an emergency */ - } else { + if (poll_ret < 0) { + printf("ERROR: Poll error, stop logging\n"); + thread_should_exit = false; - int ifds = 0; + } else if (poll_ret > 0) { - if (!logging_enabled) { - usleep(100000); - continue; - } + int ifds = 0; pthread_mutex_lock(&logbuffer_mutex); @@ -684,26 +692,32 @@ int sdlog2_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor); bool write_IMU = false; bool write_SENS = false; + if (buf.sensor.gyro_counter != gyro_counter) { gyro_counter = buf.sensor.gyro_counter; write_IMU = true; } + if (buf.sensor.accelerometer_counter != accelerometer_counter) { accelerometer_counter = buf.sensor.accelerometer_counter; write_IMU = true; } + if (buf.sensor.magnetometer_counter != magnetometer_counter) { magnetometer_counter = buf.sensor.magnetometer_counter; write_IMU = true; } + if (buf.sensor.baro_counter != baro_counter) { baro_counter = buf.sensor.baro_counter; write_SENS = true; } + if (buf.sensor.differential_pressure_counter != differential_pressure_counter) { differential_pressure_counter = buf.sensor.differential_pressure_counter; write_SENS = true; } + if (write_IMU) { log_msg.msg_type = LOG_IMU_MSG; log_msg.body.log_IMU.gyro_x = buf.sensor.gyro_rad_s[0]; @@ -717,6 +731,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2]; sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(IMU)); } + if (write_SENS) { log_msg.msg_type = LOG_SENS_MSG; log_msg.body.log_SENS.baro_pres = buf.sensor.baro_pres_mbar; @@ -815,6 +830,10 @@ int sdlog2_thread_main(int argc, char *argv[]) /* unlock, now the writer thread may run */ pthread_mutex_unlock(&logbuffer_mutex); } + + if (poll_delay > 0) { + usleep(poll_delay); + } } print_sdlog2_status(); @@ -841,7 +860,7 @@ int sdlog2_thread_main(int argc, char *argv[]) void print_sdlog2_status() { float mebibytes = log_bytes_written / 1024.0f / 1024.0f; - float seconds = ((float)(hrt_absolute_time() - starttime)) / 1000000.0f; + float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; warnx("wrote %4.2f MiB (average %5.3f MiB/s).\n", (double)mebibytes, (double)(mebibytes / seconds)); } -- cgit v1.2.3 From 1bf8f7b47ec8dd8f2f494fe40f193b3d1712e025 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Jun 2013 13:18:03 +0400 Subject: sdlog2 performance increased, fixes and cleanup --- src/modules/sdlog2/logbuffer.c | 144 ++++++++++ src/modules/sdlog2/logbuffer.h | 70 +++++ src/modules/sdlog2/module.mk | 2 +- src/modules/sdlog2/sdlog2.c | 482 ++++++++++++++++++++++----------- src/modules/sdlog2/sdlog2_ringbuffer.c | 141 ---------- src/modules/sdlog2/sdlog2_ringbuffer.h | 68 ----- 6 files changed, 541 insertions(+), 366 deletions(-) create mode 100644 src/modules/sdlog2/logbuffer.c create mode 100644 src/modules/sdlog2/logbuffer.h delete mode 100644 src/modules/sdlog2/sdlog2_ringbuffer.c delete mode 100644 src/modules/sdlog2/sdlog2_ringbuffer.h (limited to 'src') diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c new file mode 100644 index 000000000..52eda649e --- /dev/null +++ b/src/modules/sdlog2/logbuffer.c @@ -0,0 +1,144 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file logbuffer.c + * + * Ring FIFO buffer for binary log data. + * + * @author Anton Babushkin + */ + +#include +#include + +#include "logbuffer.h" + +void logbuffer_init(struct logbuffer_s *lb, int size) +{ + lb->size = size; + lb->write_ptr = 0; + lb->read_ptr = 0; + lb->data = malloc(lb->size); +} + +int logbuffer_free(struct logbuffer_s *lb) +{ + int n = lb->read_ptr - lb->write_ptr - 1; + + if (n < 0) { + n += lb->size; + } + + return n; +} + +int logbuffer_count(struct logbuffer_s *lb) +{ + int n = lb->write_ptr - lb->read_ptr; + + if (n < 0) { + n += lb->size; + } + + return n; +} + +int logbuffer_is_empty(struct logbuffer_s *lb) +{ + return lb->read_ptr == lb->write_ptr; +} + +bool logbuffer_write(struct logbuffer_s *lb, void *ptr, int size) +{ + // bytes available to write + int available = lb->read_ptr - lb->write_ptr - 1; + + if (available < 0) + available += lb->size; + + if (size > available) { + // buffer overflow + return false; + } + + char *c = (char *) ptr; + int n = lb->size - lb->write_ptr; // bytes to end of the buffer + + if (n < size) { + // message goes over end of the buffer + memcpy(&(lb->data[lb->write_ptr]), c, n); + lb->write_ptr = 0; + + } else { + n = 0; + } + + // now: n = bytes already written + int p = size - n; // number of bytes to write + memcpy(&(lb->data[lb->write_ptr]), &(c[n]), p); + lb->write_ptr = (lb->write_ptr + p) % lb->size; + return true; +} + +int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part) +{ + // bytes available to read + int available = lb->write_ptr - lb->read_ptr; + + if (available == 0) { + return 0; // buffer is empty + } + + int n = 0; + + if (available > 0) { + // read pointer is before write pointer, write all available bytes + n = available; + *is_part = false; + + } else { + // read pointer is after write pointer, write bytes from read_ptr to end + n = lb->size - lb->read_ptr; + *is_part = true; + } + + *ptr = &(lb->data[lb->read_ptr]); + return n; +} + +void logbuffer_mark_read(struct logbuffer_s *lb, int n) +{ + lb->read_ptr = (lb->read_ptr + n) % lb->size; +} diff --git a/src/modules/sdlog2/logbuffer.h b/src/modules/sdlog2/logbuffer.h new file mode 100644 index 000000000..a1d29d33d --- /dev/null +++ b/src/modules/sdlog2/logbuffer.h @@ -0,0 +1,70 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file logbuffer.h + * + * Ring FIFO buffer for binary log data. + * + * @author Anton Babushkin + */ + +#ifndef SDLOG2_RINGBUFFER_H_ +#define SDLOG2_RINGBUFFER_H_ + +#include + +struct logbuffer_s { + // all pointers are in bytes + int write_ptr; + int read_ptr; + int size; + char *data; +}; + +void logbuffer_init(struct logbuffer_s *lb, int size); + +int logbuffer_free(struct logbuffer_s *lb); + +int logbuffer_count(struct logbuffer_s *lb); + +int logbuffer_is_empty(struct logbuffer_s *lb); + +bool logbuffer_write(struct logbuffer_s *lb, void *ptr, int size); + +int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part); + +void logbuffer_mark_read(struct logbuffer_s *lb, int n); + +#endif diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk index 5a9936635..f53129688 100644 --- a/src/modules/sdlog2/module.mk +++ b/src/modules/sdlog2/module.mk @@ -40,4 +40,4 @@ MODULE_COMMAND = sdlog2 MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30" SRCS = sdlog2.c \ - sdlog2_ringbuffer.c + logbuffer.c diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 2422a15f4..6f509b917 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -60,6 +60,7 @@ #include #include +#include #include #include #include @@ -68,6 +69,7 @@ #include #include #include +#include #include #include #include @@ -80,40 +82,64 @@ #include -#include "sdlog2_ringbuffer.h" +#include "logbuffer.h" #include "sdlog2_format.h" #include "sdlog2_messages.h" +#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \ + log_msgs_written++; \ + } else { \ + log_msgs_skipped++; \ + /*printf("skip\n");*/ \ + } + +//#define SDLOG2_DEBUG + static bool thread_should_exit = false; /**< Deamon exit flag */ -static bool thread_running = false; /**< Deamon status flag */ -static int deamon_task; /**< Handle of deamon task / thread */ +static bool thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ +static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */ static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */ -static const int LOG_BUFFER_SIZE = 2048; -static const int MAX_WRITE_CHUNK = 1024; +static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */ +static const int LOG_BUFFER_SIZE = 8192; +static const int MAX_WRITE_CHUNK = 512; +static const int MIN_BYTES_TO_WRITE = 512; static const char *mountpoint = "/fs/microsd"; int log_file = -1; int mavlink_fd = -1; -struct sdlog2_logbuffer lb; +struct logbuffer_s lb; /* mutex / condition to synchronize threads */ pthread_mutex_t logbuffer_mutex; pthread_cond_t logbuffer_cond; -/** - * System state vector log buffer writing - */ -static void *sdlog2_logbuffer_write_thread(void *arg); +char folder_path[64]; -/** - * Create the thread to write the system vector - */ -pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf); +/* statistics counters */ +unsigned long log_bytes_written = 0; +uint64_t start_time = 0; +unsigned long log_msgs_written = 0; +unsigned long log_msgs_skipped = 0; + +/* current state of logging */ +bool logging_enabled = false; +/* enable logging on start (-e option) */ +bool log_on_start = false; +/* enable logging when armed (-a option) */ +bool log_when_armed = false; +/* delay = 1 / rate (rate defined by -r option) */ +useconds_t poll_delay = 0; + +/* helper flag to track system state changes */ +bool flag_system_armed = false; + +pthread_t logwriter_pthread = 0; /** - * Write a header to log file: list of message formats + * Log buffer writing thread. Open and close file here. */ -void sdlog2_write_formats(int fd); +static void *logwriter_thread(void *arg); /** * SD log management function. @@ -128,26 +154,49 @@ int sdlog2_thread_main(int argc, char *argv[]); /** * Print the correct usage. */ -static void usage(const char *reason); +static void sdlog2_usage(const char *reason); -static int file_exist(const char *filename); +/** + * Print the current status. + */ +static void sdlog2_status(void); + +/** + * Start logging: create new file and start log writer thread. + */ +void sdlog2_start_log(); + +/** + * Stop logging: stop log writer thread and close log file. + */ +void sdlog2_stop_log(); + +/** + * Write a header to log file: list of message formats. + */ +void write_formats(int fd); + + +static bool file_exist(const char *filename); static int file_copy(const char *file_old, const char *file_new); static void handle_command(struct vehicle_command_s *cmd); +static void handle_status(struct vehicle_status_s *cmd); + /** - * Print the current status. + * Create folder for current logging session. Store folder name in 'log_folder'. */ -static void print_sdlog2_status(void); +static int create_logfolder(); /** - * Create folder for current logging session. + * Select first free log file name and open it. */ -static int create_logfolder(char *folder_path); +static int open_logfile(); static void -usage(const char *reason) +sdlog2_usage(const char *reason) { if (reason) fprintf(stderr, "%s\n", reason); @@ -158,16 +207,8 @@ usage(const char *reason) "\t-a\tLog only when armed (can be still overriden by command)\n\n"); } -unsigned long log_bytes_written = 0; -uint64_t start_time = 0; - -/* logging on or off, default to true */ -bool logging_enabled = false; -bool log_when_armed = false; -useconds_t poll_delay = 0; - /** - * The sd log deamon app only briefly exists to start + * The logger deamon app only briefly exists to start * the background job. The stack size assigned in the * Makefile does only apply to this management task. * @@ -177,7 +218,7 @@ useconds_t poll_delay = 0; int sdlog2_main(int argc, char *argv[]) { if (argc < 1) - usage("missing command"); + sdlog2_usage("missing command"); if (!strcmp(argv[1], "start")) { @@ -191,7 +232,7 @@ int sdlog2_main(int argc, char *argv[]) deamon_task = task_spawn("sdlog2", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT - 30, - 4096, + 2048, sdlog2_thread_main, (const char **)argv); exit(0); @@ -208,7 +249,7 @@ int sdlog2_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - print_sdlog2_status(); + sdlog2_status(); } else { printf("\tsdlog2 not started\n"); @@ -217,20 +258,20 @@ int sdlog2_main(int argc, char *argv[]) exit(0); } - usage("unrecognized command"); + sdlog2_usage("unrecognized command"); exit(1); } -int create_logfolder(char *folder_path) +int create_logfolder() { /* make folder on sdcard */ - uint16_t foldernumber = 1; // start with folder 0001 + uint16_t folder_number = 1; // start with folder sess001 int mkdir_ret; /* look for the next folder that does not exist */ - while (foldernumber < MAX_NO_LOGFOLDER) { - /* set up file path: e.g. /mnt/sdcard/sensorfile0001.txt */ - sprintf(folder_path, "%s/session%04u", mountpoint, foldernumber); + while (folder_number <= MAX_NO_LOGFOLDER) { + /* set up folder path: e.g. /fs/microsd/sess001 */ + sprintf(folder_path, "%s/sess%03u", mountpoint, folder_number); mkdir_ret = mkdir(folder_path, S_IRWXU | S_IRWXG | S_IRWXO); /* the result is -1 if the folder exists */ @@ -256,7 +297,7 @@ int create_logfolder(char *folder_path) } else if (mkdir_ret == -1) { /* folder exists already */ - foldernumber++; + folder_number++; continue; } else { @@ -265,63 +306,126 @@ int create_logfolder(char *folder_path) } } - if (foldernumber >= MAX_NO_LOGFOLDER) { + if (folder_number >= MAX_NO_LOGFOLDER) { /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */ - warn("all %d possible folders exist already", MAX_NO_LOGFOLDER); + warnx("all %d possible folders exist already.\n", MAX_NO_LOGFOLDER); + return -1; + } + + return 0; +} + +int open_logfile() +{ + /* make folder on sdcard */ + uint16_t file_number = 1; // start with file log001 + + /* string to hold the path to the log */ + char path_buf[64] = ""; + + int fd = 0; + + /* look for the next file that does not exist */ + while (file_number <= MAX_NO_LOGFILE) { + /* set up file path: e.g. /fs/microsd/sess001/log001.bin */ + sprintf(path_buf, "%s/log%03u.bin", folder_path, file_number); + + if (file_exist(path_buf)) { + file_number++; + continue; + } + + fd = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC); + + if (fd == 0) { + errx(1, "opening %s failed.\n", path_buf); + } + + warnx("logging to: %s\n", path_buf); + + return fd; + } + + if (file_number > MAX_NO_LOGFILE) { + /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */ + warn("all %d possible files exist already\n", MAX_NO_LOGFILE); return -1; } return 0; } -static void * -sdlog2_logbuffer_write_thread(void *arg) +static void *logwriter_thread(void *arg) { /* set name */ - prctl(PR_SET_NAME, "sdlog2 microSD I/O", 0); + prctl(PR_SET_NAME, "sdlog2_writer", 0); + + struct logbuffer_s *logbuf = (struct logbuffer_s *)arg; - struct sdlog2_logbuffer *logbuf = (struct sdlog2_logbuffer *)arg; + int log_file = open_logfile(); + + /* write log messages formats */ + write_formats(log_file); int poll_count = 0; void *read_ptr; int n = 0; + bool should_wait = false; + bool is_part = false; - while (!thread_should_exit) { + while (!thread_should_exit && !logwriter_should_exit) { /* make sure threads are synchronized */ pthread_mutex_lock(&logbuffer_mutex); /* update read pointer if needed */ if (n > 0) { - sdlog2_logbuffer_mark_read(&lb, n); + logbuffer_mark_read(&lb, n); } /* only wait if no data is available to process */ - if (sdlog2_logbuffer_is_empty(logbuf)) { + if (should_wait) { /* blocking wait for new data at this line */ pthread_cond_wait(&logbuffer_cond, &logbuffer_mutex); } /* only get pointer to thread-safe data, do heavy I/O a few lines down */ - n = sdlog2_logbuffer_get_ptr(logbuf, &read_ptr); + int available = logbuffer_get_ptr(logbuf, &read_ptr, &is_part); /* continue */ pthread_mutex_unlock(&logbuffer_mutex); - if (n > 0) { + if (available > 0) { /* do heavy IO here */ - if (n > MAX_WRITE_CHUNK) + if (available > MAX_WRITE_CHUNK) { n = MAX_WRITE_CHUNK; + } else { + n = available; + } + n = write(log_file, read_ptr, n); + should_wait = (n == available) && !is_part; +#ifdef SDLOG2_DEBUG + printf("%i wrote: %i of %i, is_part=%i, should_wait=%i\n", poll_count, n, available, (int)is_part, (int)should_wait); +#endif + + if (n < 0) { + thread_should_exit = true; + err(1, "error writing log file"); + } + if (n > 0) { log_bytes_written += n; } + + } else { + should_wait = true; } - if (poll_count % 100 == 0) { + if (poll_count % 10 == 0) { fsync(log_file); } @@ -329,12 +433,22 @@ sdlog2_logbuffer_write_thread(void *arg) } fsync(log_file); + close(log_file); return OK; } -pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf) +void sdlog2_start_log() { + warnx("start logging.\n"); + + /* initialize statistics counter */ + log_bytes_written = 0; + start_time = hrt_absolute_time(); + log_msgs_written = 0; + log_msgs_skipped = 0; + + /* initialize log buffer emptying thread */ pthread_attr_t receiveloop_attr; pthread_attr_init(&receiveloop_attr); @@ -345,14 +459,39 @@ pthread_t sdlog2_logwriter_start(struct sdlog2_logbuffer *logbuf) pthread_attr_setstacksize(&receiveloop_attr, 2048); + logwriter_should_exit = false; pthread_t thread; - pthread_create(&thread, &receiveloop_attr, sdlog2_logbuffer_write_thread, logbuf); - return thread; + /* start log buffer emptying thread */ + if (0 != pthread_create(&thread, &receiveloop_attr, logwriter_thread, &lb)) { + errx(1, "error creating logwriter thread\n"); + } + + logging_enabled = true; // XXX we have to destroy the attr at some point } -void sdlog2_write_formats(int fd) +void sdlog2_stop_log() +{ + warnx("stop logging.\n"); + + logging_enabled = true; + logwriter_should_exit = true; + + /* wake up write thread one last time */ + pthread_mutex_lock(&logbuffer_mutex); + pthread_cond_signal(&logbuffer_cond); + /* unlock, now the writer thread may return */ + pthread_mutex_unlock(&logbuffer_mutex); + + /* wait for write thread to return */ + (void)pthread_join(logwriter_pthread, NULL); + + sdlog2_status(); +} + + +void write_formats(int fd) { /* construct message format packet */ struct { @@ -378,7 +517,7 @@ int sdlog2_thread_main(int argc, char *argv[]) mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); if (mavlink_fd < 0) { - warnx("ERROR: Failed to open MAVLink log stream, start mavlink app first.\n"); + warnx("failed to open MAVLink log stream, start mavlink app first.\n"); } /* log every n'th value (skip three per default) */ @@ -404,7 +543,7 @@ int sdlog2_thread_main(int argc, char *argv[]) break; case 'e': - logging_enabled = true; + log_on_start = true; break; case 'a': @@ -423,39 +562,48 @@ int sdlog2_thread_main(int argc, char *argv[]) } default: - usage("unrecognized flag"); - errx(1, "exiting."); + sdlog2_usage("unrecognized flag"); + errx(1, "exiting\n"); } } - if (file_exist(mountpoint) != OK) { - errx(1, "logging mount point %s not present, exiting.", mountpoint); + if (!file_exist(mountpoint)) { + errx(1, "logging mount point %s not present, exiting.\n", mountpoint); } - char folder_path[64]; - - if (create_logfolder(folder_path)) - errx(1, "unable to create logging folder, exiting."); - - /* string to hold the path to the sensorfile */ - char path_buf[64] = ""; + if (create_logfolder()) + errx(1, "unable to create logging folder, exiting.\n"); /* only print logging path, important to find log file later */ - warnx("logging to directory %s\n", folder_path); + warnx("logging to directory %s.\n", folder_path); - /* set up file path: e.g. /mnt/sdcard/session0001/actuator_controls0.bin */ - sprintf(path_buf, "%s/%s.bin", folder_path, "log"); + /* logging control buffers and subscriptions */ + struct { + struct vehicle_command_s cmd; + struct vehicle_status_s status; + } buf_control; + memset(&buf_control, 0, sizeof(buf_control)); - if (0 == (log_file = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC))) { - errx(1, "opening %s failed.\n", path_buf); - } + struct { + int cmd_sub; + int status_sub; + } subs_control; - /* write log messages formats */ - sdlog2_write_formats(log_file); + /* file descriptors to wait for */ + struct pollfd fds_control[2]; + /* --- VEHICLE COMMAND --- */ + subs_control.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); + fds_control[0].fd = subs_control.cmd_sub; + fds_control[0].events = POLLIN; + + /* --- VEHICLE STATUS --- */ + subs_control.status_sub = orb_subscribe(ORB_ID(vehicle_status)); + fds_control[1].fd = subs_control.status_sub; + fds_control[1].events = POLLIN; /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 13; + const ssize_t fdsc = 12; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -469,8 +617,8 @@ int sdlog2_thread_main(int argc, char *argv[]) struct actuator_outputs_s act_outputs; struct actuator_controls_s act_controls; struct actuator_controls_effective_s act_controls_effective; - struct vehicle_command_s cmd; struct vehicle_local_position_s local_pos; + struct vehicle_local_position_setpoint_s local_pos_sp; struct vehicle_global_position_s global_pos; struct vehicle_gps_position_s gps_pos; struct vehicle_vicon_position_s vicon_pos; @@ -482,7 +630,6 @@ int sdlog2_thread_main(int argc, char *argv[]) memset(&buf, 0, sizeof(buf)); struct { - int cmd_sub; int sensor_sub; int att_sub; int att_sp_sub; @@ -490,6 +637,7 @@ int sdlog2_thread_main(int argc, char *argv[]) int act_controls_sub; int act_controls_effective_sub; int local_pos_sub; + int local_pos_sp_sub; int global_pos_sub; int gps_pos_sub; int vicon_pos_sub; @@ -519,33 +667,25 @@ int sdlog2_thread_main(int argc, char *argv[]) #pragma pack(pop) memset(&log_msg.body, 0, sizeof(log_msg.body)); - /* --- MANAGEMENT - LOGGING COMMAND --- */ - /* subscribe to ORB for vehicle command */ - subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); - fds[fdsc_count].fd = subs.cmd_sub; - fds[fdsc_count].events = POLLIN; - fdsc_count++; - /* --- GPS POSITION --- */ subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); fds[fdsc_count].fd = subs.gps_pos_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- SENSORS RAW VALUE --- */ + /* --- SENSORS COMBINED --- */ subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); fds[fdsc_count].fd = subs.sensor_sub; - /* do not rate limit, instead use skip counter (aliasing on rate limit) */ fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- ATTITUDE VALUE --- */ + /* --- ATTITUDE --- */ subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); fds[fdsc_count].fd = subs.att_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- ATTITUDE SETPOINT VALUE --- */ + /* --- ATTITUDE SETPOINT --- */ subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); fds[fdsc_count].fd = subs.att_sp_sub; fds[fdsc_count].events = POLLIN; @@ -557,13 +697,13 @@ int sdlog2_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- ACTUATOR CONTROL VALUE --- */ + /* --- ACTUATOR CONTROL --- */ subs.act_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); fds[fdsc_count].fd = subs.act_controls_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */ + /* --- ACTUATOR CONTROL EFFECTIVE --- */ subs.act_controls_effective_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE); fds[fdsc_count].fd = subs.act_controls_effective_sub; fds[fdsc_count].events = POLLIN; @@ -575,6 +715,12 @@ int sdlog2_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; + /* --- LOCAL POSITION SETPOINT --- */ + subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); + fds[fdsc_count].fd = subs.local_pos_sp_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + /* --- GLOBAL POSITION --- */ subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); fds[fdsc_count].fd = subs.global_pos_sub; @@ -587,7 +733,7 @@ int sdlog2_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; - /* --- FLOW measurements --- */ + /* --- OPTICAL FLOW --- */ subs.flow_sub = orb_subscribe(ORB_ID(optical_flow)); fds[fdsc_count].fd = subs.flow_sub; fds[fdsc_count].events = POLLIN; @@ -610,26 +756,19 @@ int sdlog2_thread_main(int argc, char *argv[]) /* * set up poll to block for new data, - * wait for a maximum of 1000 ms (1 second) + * wait for a maximum of 1000 ms */ const int poll_timeout = 1000; thread_running = true; /* initialize log buffer with specified size */ - sdlog2_logbuffer_init(&lb, LOG_BUFFER_SIZE); + logbuffer_init(&lb, LOG_BUFFER_SIZE); /* initialize thread synchronization */ pthread_mutex_init(&logbuffer_mutex, NULL); pthread_cond_init(&logbuffer_cond, NULL); - /* start logbuffer emptying thread */ - pthread_t logwriter_pthread = sdlog2_logwriter_start(&lb); - - /* initialize statistics counter */ - log_bytes_written = 0; - start_time = hrt_absolute_time(); - /* track changes in sensor_combined topic */ uint16_t gyro_counter = 0; uint16_t accelerometer_counter = 0; @@ -637,19 +776,44 @@ int sdlog2_thread_main(int argc, char *argv[]) uint16_t baro_counter = 0; uint16_t differential_pressure_counter = 0; + /* enable logging on start if needed */ + if (log_on_start) + sdlog2_start_log(); + while (!thread_should_exit) { - if (!logging_enabled) { - usleep(100000); + /* poll control topics */ + int poll_control_ret = poll(fds_control, sizeof(fds_control) / sizeof(fds_control[0]), logging_enabled ? 0 : 500); + + /* handle the poll result */ + if (poll_control_ret < 0) { + warnx("ERROR: poll control topics error, stop logging.\n"); + thread_should_exit = true; continue; + + } else if (poll_control_ret > 0) { + /* --- VEHICLE COMMAND --- */ + if (fds[0].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_command), subs_control.cmd_sub, &buf_control.cmd); + handle_command(&buf_control.cmd); + } + + /* --- VEHICLE STATUS --- */ + if (fds[1].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_status), subs_control.status_sub, &buf_control.status); + handle_status(&buf_control.status); + } } - /* poll all topics */ + if (!logging_enabled) + continue; + + /* poll data topics */ int poll_ret = poll(fds, fdsc, poll_delay == 0 ? poll_timeout : 0); /* handle the poll result */ if (poll_ret < 0) { - printf("ERROR: Poll error, stop logging\n"); - thread_should_exit = false; + warnx("ERROR: poll error, stop logging.\n"); + thread_should_exit = true; } else if (poll_ret > 0) { @@ -660,14 +824,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* write time stamp message */ log_msg.msg_type = LOG_TIME_MSG; log_msg.body.log_TIME.t = hrt_absolute_time(); - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(TIME)); - - /* --- VEHICLE COMMAND --- */ - if (fds[ifds++].revents & POLLIN) { - /* copy command into local buffer */ - orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd); - handle_command(&buf.cmd); - } + LOGBUFFER_WRITE_AND_COUNT(TIME); /* --- GPS POSITION --- */ if (fds[ifds++].revents & POLLIN) { @@ -684,7 +841,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s; log_msg.body.log_GPS.cog = buf.gps_pos.cog_rad; log_msg.body.log_GPS.vel_valid = (uint8_t) buf.gps_pos.vel_ned_valid; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(GPS)); + LOGBUFFER_WRITE_AND_COUNT(GPS); } /* --- SENSOR COMBINED --- */ @@ -729,7 +886,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer_ga[0]; log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer_ga[1]; log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2]; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(IMU)); + LOGBUFFER_WRITE_AND_COUNT(IMU); } if (write_SENS) { @@ -738,7 +895,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter; log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius; log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure_pa; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(SENS)); + LOGBUFFER_WRITE_AND_COUNT(SENS); } } @@ -749,7 +906,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_ATT.roll = buf.att.roll; log_msg.body.log_ATT.pitch = buf.att.pitch; log_msg.body.log_ATT.yaw = buf.att.yaw; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATT)); + LOGBUFFER_WRITE_AND_COUNT(ATT); } /* --- ATTITUDE SETPOINT --- */ @@ -759,7 +916,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body; log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body; log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(ATSP)); + LOGBUFFER_WRITE_AND_COUNT(ATSP); } /* --- ACTUATOR OUTPUTS --- */ @@ -794,7 +951,18 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_LPOS.home_lat = buf.local_pos.home_lat; log_msg.body.log_LPOS.home_lon = buf.local_pos.home_lon; log_msg.body.log_LPOS.home_alt = buf.local_pos.home_alt; - sdlog2_logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(LPOS)); + LOGBUFFER_WRITE_AND_COUNT(LPOS); + } + + /* --- LOCAL POSITION SETPOINT --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_local_position_setpoint), subs.local_pos_sp_sub, &buf.local_pos_sp); + log_msg.msg_type = LOG_LPSP_MSG; + log_msg.body.log_LPSP.x = buf.local_pos_sp.x; + log_msg.body.log_LPSP.y = buf.local_pos_sp.y; + log_msg.body.log_LPSP.z = buf.local_pos_sp.z; + log_msg.body.log_LPSP.yaw = buf.local_pos_sp.yaw; + LOGBUFFER_WRITE_AND_COUNT(LPSP); } /* --- GLOBAL POSITION --- */ @@ -822,7 +990,10 @@ int sdlog2_thread_main(int argc, char *argv[]) } /* signal the other thread new data, but not yet unlock */ - if (sdlog2_logbuffer_count(&lb) > (lb.size / 2)) { + if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) { +#ifdef SDLOG2_DEBUG + printf("signal %i\n", logbuffer_count(&lb)); +#endif /* only request write if several packets can be written at once */ pthread_cond_signal(&logbuffer_cond); } @@ -836,42 +1007,34 @@ int sdlog2_thread_main(int argc, char *argv[]) } } - print_sdlog2_status(); - - /* wake up write thread one last time */ - pthread_mutex_lock(&logbuffer_mutex); - pthread_cond_signal(&logbuffer_cond); - /* unlock, now the writer thread may return */ - pthread_mutex_unlock(&logbuffer_mutex); - - /* wait for write thread to return */ - (void)pthread_join(logwriter_pthread, NULL); + if (logging_enabled) + sdlog2_stop_log(); pthread_mutex_destroy(&logbuffer_mutex); pthread_cond_destroy(&logbuffer_cond); - warnx("exiting.\n\n"); + warnx("exiting.\n"); thread_running = false; return 0; } -void print_sdlog2_status() +void sdlog2_status() { float mebibytes = log_bytes_written / 1024.0f / 1024.0f; float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; - warnx("wrote %4.2f MiB (average %5.3f MiB/s).\n", (double)mebibytes, (double)(mebibytes / seconds)); + warnx("wrote %lu msgs, %4.2f MiB (average %5.3f MiB/s), skipped %lu msgs.\n", log_msgs_written, (double)mebibytes, (double)(mebibytes / seconds), log_msgs_skipped); } /** * @return 0 if file exists */ -int file_exist(const char *filename) +bool file_exist(const char *filename) { struct stat buffer; - return stat(filename, &buffer); + return stat(filename, &buffer) == 0; } int file_copy(const char *file_old, const char *file_new) @@ -881,7 +1044,7 @@ int file_copy(const char *file_old, const char *file_new) int ret = 0; if (source == NULL) { - warnx("failed opening input file to copy"); + warnx("failed opening input file to copy.\n"); return 1; } @@ -889,7 +1052,7 @@ int file_copy(const char *file_old, const char *file_new) if (target == NULL) { fclose(source); - warnx("failed to open output file to copy"); + warnx("failed to open output file to copy.\n"); return 1; } @@ -900,7 +1063,7 @@ int file_copy(const char *file_old, const char *file_new) ret = fwrite(buf, 1, nread, target); if (ret <= 0) { - warnx("error writing file"); + warnx("error writing file.\n"); ret = 1; break; } @@ -918,25 +1081,19 @@ void handle_command(struct vehicle_command_s *cmd) { /* result of the command */ uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED; + int param; /* request to set different system mode */ switch (cmd->command) { case VEHICLE_CMD_PREFLIGHT_STORAGE: + param = (int)(cmd->param3); - if (((int)(cmd->param3)) == 1) { + if (param == 1) { + sdlog2_start_log(); - /* enable logging */ - mavlink_log_info(mavlink_fd, "[log] file:"); - mavlink_log_info(mavlink_fd, "logdir"); - logging_enabled = true; - } - - if (((int)(cmd->param3)) == 0) { - - /* disable logging */ - mavlink_log_info(mavlink_fd, "[log] stopped."); - logging_enabled = false; + } else if (param == 0) { + sdlog2_stop_log(); } break; @@ -945,5 +1102,18 @@ void handle_command(struct vehicle_command_s *cmd) /* silently ignore */ break; } +} + +void handle_status(struct vehicle_status_s *status) +{ + if (log_when_armed && (status->flag_system_armed != flag_system_armed)) { + flag_system_armed = status->flag_system_armed; + if (flag_system_armed) { + sdlog2_start_log(); + + } else { + sdlog2_stop_log(); + } + } } diff --git a/src/modules/sdlog2/sdlog2_ringbuffer.c b/src/modules/sdlog2/sdlog2_ringbuffer.c deleted file mode 100644 index 022a183ba..000000000 --- a/src/modules/sdlog2/sdlog2_ringbuffer.c +++ /dev/null @@ -1,141 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013 PX4 Development Team. All rights reserved. - * Author: Anton Babushkin - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file sdlog2_ringbuffer.c - * - * Ring FIFO buffer for binary data. - * - * @author Anton Babushkin - */ - -#include -#include - -#include "sdlog2_ringbuffer.h" - -void sdlog2_logbuffer_init(struct sdlog2_logbuffer *lb, int size) -{ - lb->size = size; - lb->write_ptr = 0; - lb->read_ptr = 0; - lb->data = malloc(lb->size); -} - -int sdlog2_logbuffer_free(struct sdlog2_logbuffer *lb) -{ - int n = lb->read_ptr - lb->write_ptr - 1; - - if (n < 0) { - n += lb->size; - } - - return n; -} - -int sdlog2_logbuffer_count(struct sdlog2_logbuffer *lb) -{ - int n = lb->write_ptr - lb->read_ptr; - - if (n < 0) { - n += lb->size; - } - - return n; -} - -int sdlog2_logbuffer_is_empty(struct sdlog2_logbuffer *lb) -{ - return lb->read_ptr == lb->write_ptr; -} - -void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size) -{ - // bytes available to write - int available = lb->read_ptr - lb->write_ptr - 1; - - if (available < 0) - available += lb->size; - - if (size > available) { - // buffer overflow - return; - } - - char *c = (char *) ptr; - int n = lb->size - lb->write_ptr; // bytes to end of the buffer - - if (n < size) { - // message goes over end of the buffer - memcpy(&(lb->data[lb->write_ptr]), c, n); - lb->write_ptr = 0; - - } else { - n = 0; - } - - // now: n = bytes already written - int p = size - n; // number of bytes to write - memcpy(&(lb->data[lb->write_ptr]), &(c[n]), p); - lb->write_ptr = (lb->write_ptr + p) % lb->size; -} - -int sdlog2_logbuffer_get_ptr(struct sdlog2_logbuffer *lb, void **ptr) -{ - // bytes available to read - int available = lb->write_ptr - lb->read_ptr; - - if (available == 0) { - return 0; // buffer is empty - } - - int n = 0; - - if (available > 0) { - // read pointer is before write pointer, write all available bytes - n = available; - - } else { - // read pointer is after write pointer, write bytes from read_ptr to end - n = lb->size - lb->read_ptr; - } - - *ptr = &(lb->data[lb->read_ptr]); - return n; -} - -void sdlog2_logbuffer_mark_read(struct sdlog2_logbuffer *lb, int n) -{ - lb->read_ptr = (lb->read_ptr + n) % lb->size; -} diff --git a/src/modules/sdlog2/sdlog2_ringbuffer.h b/src/modules/sdlog2/sdlog2_ringbuffer.h deleted file mode 100644 index 287f56c34..000000000 --- a/src/modules/sdlog2/sdlog2_ringbuffer.h +++ /dev/null @@ -1,68 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013 PX4 Development Team. All rights reserved. - * Author: Anton Babushkin - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file sdlog2_ringbuffer.h - * - * Ring FIFO buffer for binary data. - * - * @author Anton Babushkin - */ - -#ifndef SDLOG2_RINGBUFFER_H_ -#define SDLOG2_RINGBUFFER_H_ - -struct sdlog2_logbuffer { - // all pointers are in bytes - int write_ptr; - int read_ptr; - int size; - char *data; -}; - -void sdlog2_logbuffer_init(struct sdlog2_logbuffer *lb, int size); - -int sdlog2_logbuffer_free(struct sdlog2_logbuffer *lb); - -int sdlog2_logbuffer_count(struct sdlog2_logbuffer *lb); - -int sdlog2_logbuffer_is_empty(struct sdlog2_logbuffer *lb); - -void sdlog2_logbuffer_write(struct sdlog2_logbuffer *lb, void *ptr, int size); - -int sdlog2_logbuffer_get_ptr(struct sdlog2_logbuffer *lb, void **ptr); - -void sdlog2_logbuffer_mark_read(struct sdlog2_logbuffer *lb, int n); - -#endif -- cgit v1.2.3 From 34d4d62acc132b8a28395c4ab943f6e424b999c6 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Jun 2013 15:59:42 +0400 Subject: sdlog2 messages cleanup, fixes --- src/modules/sdlog2/sdlog2.c | 164 ++++++++++++++++++++++---------------------- 1 file changed, 83 insertions(+), 81 deletions(-) (limited to 'src') diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 6f509b917..27efe2c62 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -93,6 +93,12 @@ /*printf("skip\n");*/ \ } +#define LOG_ORB_SUBSCRIBE(_var, _topic) subs.##_var##_sub = orb_subscribe(ORB_ID(##_topic##)); \ + fds[fdsc_count].fd = subs.##_var##_sub; \ + fds[fdsc_count].events = POLLIN; \ + fdsc_count++; + + //#define SDLOG2_DEBUG static bool thread_should_exit = false; /**< Deamon exit flag */ @@ -129,7 +135,7 @@ bool log_on_start = false; /* enable logging when armed (-a option) */ bool log_when_armed = false; /* delay = 1 / rate (rate defined by -r option) */ -useconds_t poll_delay = 0; +useconds_t sleep_delay = 0; /* helper flag to track system state changes */ bool flag_system_armed = false; @@ -204,7 +210,7 @@ sdlog2_usage(const char *reason) errx(1, "usage: sdlog2 {start|stop|status} [-r ] -e -a\n" "\t-r\tLog rate in Hz, 0 means unlimited rate\n" "\t-e\tEnable logging by default (if not, can be started by command)\n" - "\t-a\tLog only when armed (can be still overriden by command)\n\n"); + "\t-a\tLog only when armed (can be still overriden by command)\n"); } /** @@ -217,7 +223,7 @@ sdlog2_usage(const char *reason) */ int sdlog2_main(int argc, char *argv[]) { - if (argc < 1) + if (argc < 2) sdlog2_usage("missing command"); if (!strcmp(argv[1], "start")) { @@ -308,7 +314,7 @@ int create_logfolder() if (folder_number >= MAX_NO_LOGFOLDER) { /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */ - warnx("all %d possible folders exist already.\n", MAX_NO_LOGFOLDER); + warnx("all %d possible folders exist already.", MAX_NO_LOGFOLDER); return -1; } @@ -338,17 +344,18 @@ int open_logfile() fd = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC); if (fd == 0) { - errx(1, "opening %s failed.\n", path_buf); + errx(1, "opening %s failed.", path_buf); } - warnx("logging to: %s\n", path_buf); + warnx("logging to: %s", path_buf); + mavlink_log_info(mavlink_fd, "[sdlog2] logging to: %s", path_buf); return fd; } if (file_number > MAX_NO_LOGFILE) { /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */ - warn("all %d possible files exist already\n", MAX_NO_LOGFILE); + warn("all %d possible files exist already", MAX_NO_LOGFILE); return -1; } @@ -409,7 +416,7 @@ static void *logwriter_thread(void *arg) should_wait = (n == available) && !is_part; #ifdef SDLOG2_DEBUG - printf("%i wrote: %i of %i, is_part=%i, should_wait=%i\n", poll_count, n, available, (int)is_part, (int)should_wait); + printf("%i wrote: %i of %i, is_part=%i, should_wait=%i", poll_count, n, available, (int)is_part, (int)should_wait); #endif if (n < 0) { @@ -440,7 +447,8 @@ static void *logwriter_thread(void *arg) void sdlog2_start_log() { - warnx("start logging.\n"); + warnx("start logging."); + mavlink_log_info(mavlink_fd, "[sdlog2] start logging"); /* initialize statistics counter */ log_bytes_written = 0; @@ -464,7 +472,7 @@ void sdlog2_start_log() /* start log buffer emptying thread */ if (0 != pthread_create(&thread, &receiveloop_attr, logwriter_thread, &lb)) { - errx(1, "error creating logwriter thread\n"); + errx(1, "error creating logwriter thread"); } logging_enabled = true; @@ -473,7 +481,8 @@ void sdlog2_start_log() void sdlog2_stop_log() { - warnx("stop logging.\n"); + warnx("stop logging."); + mavlink_log_info(mavlink_fd, "[sdlog2] stop logging"); logging_enabled = true; logwriter_should_exit = true; @@ -517,7 +526,7 @@ int sdlog2_thread_main(int argc, char *argv[]) mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); if (mavlink_fd < 0) { - warnx("failed to open MAVLink log stream, start mavlink app first.\n"); + warnx("failed to open MAVLink log stream, start mavlink app first."); } /* log every n'th value (skip three per default) */ @@ -534,10 +543,10 @@ int sdlog2_thread_main(int argc, char *argv[]) unsigned r = strtoul(optarg, NULL, 10); if (r == 0) { - poll_delay = 0; + sleep_delay = 0; } else { - poll_delay = 1000000 / r; + sleep_delay = 1000000 / r; } } break; @@ -552,58 +561,37 @@ int sdlog2_thread_main(int argc, char *argv[]) case '?': if (optopt == 'c') { - warnx("Option -%c requires an argument.\n", optopt); + warnx("Option -%c requires an argument.", optopt); } else if (isprint(optopt)) { - warnx("Unknown option `-%c'.\n", optopt); + warnx("Unknown option `-%c'.", optopt); } else { - warnx("Unknown option character `\\x%x'.\n", optopt); + warnx("Unknown option character `\\x%x'.", optopt); } default: sdlog2_usage("unrecognized flag"); - errx(1, "exiting\n"); + errx(1, "exiting"); } } if (!file_exist(mountpoint)) { - errx(1, "logging mount point %s not present, exiting.\n", mountpoint); + errx(1, "logging mount point %s not present, exiting.", mountpoint); } if (create_logfolder()) - errx(1, "unable to create logging folder, exiting.\n"); + errx(1, "unable to create logging folder, exiting."); /* only print logging path, important to find log file later */ - warnx("logging to directory %s.\n", folder_path); - - /* logging control buffers and subscriptions */ - struct { - struct vehicle_command_s cmd; - struct vehicle_status_s status; - } buf_control; - memset(&buf_control, 0, sizeof(buf_control)); - - struct { - int cmd_sub; - int status_sub; - } subs_control; + warnx("logging to directory: %s", folder_path); /* file descriptors to wait for */ struct pollfd fds_control[2]; - /* --- VEHICLE COMMAND --- */ - subs_control.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); - fds_control[0].fd = subs_control.cmd_sub; - fds_control[0].events = POLLIN; - - /* --- VEHICLE STATUS --- */ - subs_control.status_sub = orb_subscribe(ORB_ID(vehicle_status)); - fds_control[1].fd = subs_control.status_sub; - fds_control[1].events = POLLIN; /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 12; + const ssize_t fdsc = 15; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -611,6 +599,8 @@ int sdlog2_thread_main(int argc, char *argv[]) /* warning! using union here to save memory, elements should be used separately! */ union { + struct vehicle_command_s cmd; + struct vehicle_status_s status; struct sensor_combined_s sensor; struct vehicle_attitude_s att; struct vehicle_attitude_setpoint_s att_sp; @@ -630,6 +620,8 @@ int sdlog2_thread_main(int argc, char *argv[]) memset(&buf, 0, sizeof(buf)); struct { + int cmd_sub; + int status_sub; int sensor_sub; int att_sub; int att_sp_sub; @@ -667,6 +659,18 @@ int sdlog2_thread_main(int argc, char *argv[]) #pragma pack(pop) memset(&log_msg.body, 0, sizeof(log_msg.body)); + /* --- VEHICLE COMMAND --- */ + subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); + fds[fdsc_count].fd = subs.cmd_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + + /* --- VEHICLE STATUS --- */ + subs.status_sub = orb_subscribe(ORB_ID(vehicle_status)); + fds[fdsc_count].fd = subs.status_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + /* --- GPS POSITION --- */ subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); fds[fdsc_count].fd = subs.gps_pos_sub; @@ -716,7 +720,7 @@ int sdlog2_thread_main(int argc, char *argv[]) fdsc_count++; /* --- LOCAL POSITION SETPOINT --- */ - subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); + subs.local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); fds[fdsc_count].fd = subs.local_pos_sp_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; @@ -750,7 +754,7 @@ int sdlog2_thread_main(int argc, char *argv[]) * differs from the number of messages in the above list. */ if (fdsc_count > fdsc) { - warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.\n", __FILE__, __LINE__); + warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.", __FILE__, __LINE__); fdsc_count = fdsc; } @@ -781,43 +785,41 @@ int sdlog2_thread_main(int argc, char *argv[]) sdlog2_start_log(); while (!thread_should_exit) { - /* poll control topics */ - int poll_control_ret = poll(fds_control, sizeof(fds_control) / sizeof(fds_control[0]), logging_enabled ? 0 : 500); + /* decide use usleep() or blocking poll() */ + bool use_sleep = sleep_delay > 0 && logging_enabled; + + /* poll all topics if logging enabled or only management (first 2) if not */ + int poll_ret = poll(fds, logging_enabled ? fdsc_count : 2, use_sleep ? 0 : poll_timeout); /* handle the poll result */ - if (poll_control_ret < 0) { - warnx("ERROR: poll control topics error, stop logging.\n"); + if (poll_ret < 0) { + warnx("ERROR: poll error, stop logging."); thread_should_exit = true; - continue; - } else if (poll_control_ret > 0) { + } else if (poll_ret > 0) { + + /* check all data subscriptions only if logging enabled, + * logging_enabled can be changed while checking vehicle_command and vehicle_status */ + bool check_data = logging_enabled; + int ifds = 0; + /* --- VEHICLE COMMAND --- */ - if (fds[0].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_command), subs_control.cmd_sub, &buf_control.cmd); - handle_command(&buf_control.cmd); + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd); + handle_command(&buf.cmd); } /* --- VEHICLE STATUS --- */ - if (fds[1].revents & POLLIN) { - orb_copy(ORB_ID(vehicle_status), subs_control.status_sub, &buf_control.status); - handle_status(&buf_control.status); + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf.status); + if (log_when_armed) { + handle_status(&buf.status); + } } - } - if (!logging_enabled) - continue; - - /* poll data topics */ - int poll_ret = poll(fds, fdsc, poll_delay == 0 ? poll_timeout : 0); - - /* handle the poll result */ - if (poll_ret < 0) { - warnx("ERROR: poll error, stop logging.\n"); - thread_should_exit = true; - - } else if (poll_ret > 0) { - - int ifds = 0; + if (!logging_enabled || !check_data) { + continue; + } pthread_mutex_lock(&logbuffer_mutex); @@ -992,7 +994,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* signal the other thread new data, but not yet unlock */ if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) { #ifdef SDLOG2_DEBUG - printf("signal %i\n", logbuffer_count(&lb)); + printf("signal %i", logbuffer_count(&lb)); #endif /* only request write if several packets can be written at once */ pthread_cond_signal(&logbuffer_cond); @@ -1002,8 +1004,8 @@ int sdlog2_thread_main(int argc, char *argv[]) pthread_mutex_unlock(&logbuffer_mutex); } - if (poll_delay > 0) { - usleep(poll_delay); + if (use_sleep) { + usleep(sleep_delay); } } @@ -1013,7 +1015,7 @@ int sdlog2_thread_main(int argc, char *argv[]) pthread_mutex_destroy(&logbuffer_mutex); pthread_cond_destroy(&logbuffer_cond); - warnx("exiting.\n"); + warnx("exiting."); thread_running = false; @@ -1025,7 +1027,7 @@ void sdlog2_status() float mebibytes = log_bytes_written / 1024.0f / 1024.0f; float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; - warnx("wrote %lu msgs, %4.2f MiB (average %5.3f MiB/s), skipped %lu msgs.\n", log_msgs_written, (double)mebibytes, (double)(mebibytes / seconds), log_msgs_skipped); + warnx("wrote %lu msgs, %4.2f MiB (average %5.3f MiB/s), skipped %lu msgs.", log_msgs_written, (double)mebibytes, (double)(mebibytes / seconds), log_msgs_skipped); } /** @@ -1044,7 +1046,7 @@ int file_copy(const char *file_old, const char *file_new) int ret = 0; if (source == NULL) { - warnx("failed opening input file to copy.\n"); + warnx("failed opening input file to copy."); return 1; } @@ -1052,7 +1054,7 @@ int file_copy(const char *file_old, const char *file_new) if (target == NULL) { fclose(source); - warnx("failed to open output file to copy.\n"); + warnx("failed to open output file to copy."); return 1; } @@ -1063,7 +1065,7 @@ int file_copy(const char *file_old, const char *file_new) ret = fwrite(buf, 1, nread, target); if (ret <= 0) { - warnx("error writing file.\n"); + warnx("error writing file."); ret = 1; break; } @@ -1106,7 +1108,7 @@ void handle_command(struct vehicle_command_s *cmd) void handle_status(struct vehicle_status_s *status) { - if (log_when_armed && (status->flag_system_armed != flag_system_armed)) { + if (status->flag_system_armed != flag_system_armed) { flag_system_armed = status->flag_system_armed; if (flag_system_armed) { -- cgit v1.2.3 From 9f895d87cd159205cf1e66be49cc4b1f787b54ec Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Jun 2013 17:16:12 +0400 Subject: sdlog2 mavlink msg fix --- src/modules/sdlog2/sdlog2.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src') diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 27efe2c62..83bc338e2 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -348,7 +348,7 @@ int open_logfile() } warnx("logging to: %s", path_buf); - mavlink_log_info(mavlink_fd, "[sdlog2] logging to: %s", path_buf); + mavlink_log_info(mavlink_fd, "[sdlog2] log: %s", path_buf); return fd; } -- cgit v1.2.3 From 606f68c890dfc15ca29262f6c7c2eff29c9dfec7 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Jun 2013 20:40:56 +0400 Subject: sdlog2 GPS message changes --- src/modules/sdlog2/sdlog2.c | 6 +++--- src/modules/sdlog2/sdlog2_messages.h | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) (limited to 'src') diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 83bc338e2..b5821098f 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -834,15 +834,15 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.msg_type = LOG_GPS_MSG; log_msg.body.log_GPS.gps_time = buf.gps_pos.time_gps_usec; log_msg.body.log_GPS.fix_type = buf.gps_pos.fix_type; - log_msg.body.log_GPS.satellites_visible = buf.gps_pos.satellites_visible; + log_msg.body.log_GPS.eph = buf.gps_pos.eph_m; + log_msg.body.log_GPS.epv = buf.gps_pos.epv_m; log_msg.body.log_GPS.lat = buf.gps_pos.lat; log_msg.body.log_GPS.lon = buf.gps_pos.lon; - log_msg.body.log_GPS.alt = buf.gps_pos.alt; + log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001; log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s; log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s; log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s; log_msg.body.log_GPS.cog = buf.gps_pos.cog_rad; - log_msg.body.log_GPS.vel_valid = (uint8_t) buf.gps_pos.vel_ned_valid; LOGBUFFER_WRITE_AND_COUNT(GPS); } diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 2baccc106..316459b1e 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -122,7 +122,8 @@ struct log_LPSP_s { struct log_GPS_s { uint64_t gps_time; uint8_t fix_type; - uint8_t satellites_visible; + float eph; + float epv; int32_t lat; int32_t lon; float alt; @@ -130,7 +131,6 @@ struct log_GPS_s { float vel_e; float vel_d; float cog; - uint8_t vel_valid; }; #pragma pack(pop) @@ -144,7 +144,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"), LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), - LOG_FORMAT(GPS, "QBBLLfffffB", "GPSTime,FixType,Sats,Lat,Lon,Alt,VelN,VelE,VelD,Cog,VelValid"), + LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); -- cgit v1.2.3 From 7ae2cf9d2de9a07249eccdcae10d3ac84794d0fc Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 4 Jun 2013 16:48:55 +0400 Subject: Minor sdlog2/logbuffer cleanup --- src/modules/sdlog2/logbuffer.c | 15 ++------------- src/modules/sdlog2/logbuffer.h | 2 -- 2 files changed, 2 insertions(+), 15 deletions(-) (limited to 'src') diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c index 52eda649e..4205bcf20 100644 --- a/src/modules/sdlog2/logbuffer.c +++ b/src/modules/sdlog2/logbuffer.c @@ -53,17 +53,6 @@ void logbuffer_init(struct logbuffer_s *lb, int size) lb->data = malloc(lb->size); } -int logbuffer_free(struct logbuffer_s *lb) -{ - int n = lb->read_ptr - lb->write_ptr - 1; - - if (n < 0) { - n += lb->size; - } - - return n; -} - int logbuffer_count(struct logbuffer_s *lb) { int n = lb->write_ptr - lb->read_ptr; @@ -124,12 +113,12 @@ int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part) int n = 0; if (available > 0) { - // read pointer is before write pointer, write all available bytes + // read pointer is before write pointer, all available bytes can be read n = available; *is_part = false; } else { - // read pointer is after write pointer, write bytes from read_ptr to end + // read pointer is after write pointer, read bytes from read_ptr to end of the buffer n = lb->size - lb->read_ptr; *is_part = true; } diff --git a/src/modules/sdlog2/logbuffer.h b/src/modules/sdlog2/logbuffer.h index a1d29d33d..e9635e5e7 100644 --- a/src/modules/sdlog2/logbuffer.h +++ b/src/modules/sdlog2/logbuffer.h @@ -55,8 +55,6 @@ struct logbuffer_s { void logbuffer_init(struct logbuffer_s *lb, int size); -int logbuffer_free(struct logbuffer_s *lb); - int logbuffer_count(struct logbuffer_s *lb); int logbuffer_is_empty(struct logbuffer_s *lb); -- cgit v1.2.3 From 6537759dfc58117258610bb64d621da646d7d4ea Mon Sep 17 00:00:00 2001 From: "Hyon Lim (Retina)" Date: Thu, 6 Jun 2013 21:28:40 +1000 Subject: Add detailed documentation for SO3 gains tuning. USB nsh has been removed. --- nuttx/configs/px4fmu/nsh/defconfig | 6 +-- .../attitude_estimator_so3_comp_main.cpp | 48 +++++++++++++++++----- .../attitude_estimator_so3_comp_params.c | 11 ++++- 3 files changed, 50 insertions(+), 15 deletions(-) (limited to 'src') diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 94d99112e..02e224302 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -248,7 +248,7 @@ CONFIG_SERIAL_TERMIOS=y CONFIG_SERIAL_CONSOLE_REINIT=y CONFIG_STANDARD_SERIAL=y -CONFIG_USART1_SERIAL_CONSOLE=n +CONFIG_USART1_SERIAL_CONSOLE=y CONFIG_USART2_SERIAL_CONSOLE=n CONFIG_USART3_SERIAL_CONSOLE=n CONFIG_UART4_SERIAL_CONSOLE=n @@ -561,7 +561,7 @@ CONFIG_START_MONTH=1 CONFIG_START_DAY=1 CONFIG_GREGORIAN_TIME=n CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=n +CONFIG_DEV_CONSOLE=y CONFIG_DEV_LOWCONSOLE=n CONFIG_MUTEX_TYPES=n CONFIG_PRIORITY_INHERITANCE=y @@ -925,7 +925,7 @@ CONFIG_USBDEV_TRACE_NRECORDS=512 # Size of the serial receive/transmit buffers. Default 256. # CONFIG_CDCACM=y -CONFIG_CDCACM_CONSOLE=y +CONFIG_CDCACM_CONSOLE=n #CONFIG_CDCACM_EP0MAXPACKET CONFIG_CDCACM_EPINTIN=1 #CONFIG_CDCACM_EPINTIN_FSSIZE diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 9bb749caf..3cbc62ea1 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -57,6 +57,7 @@ static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */ static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */ +static float dq0 = 0.0f, dq1 = 0.0f, dq2 = 0.0f, dq3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */ static float gyro_bias[3] = {0.0f, 0.0f, 0.0f}; /** bias estimation */ static bool bFilterInit = false; @@ -170,7 +171,7 @@ float invSqrt(float number) { //! Using accelerometer, sense the gravity vector. //! Using magnetometer, sense yaw. -void MahonyAHRSinit(float ax, float ay, float az, float mx, float my, float mz) +void NonlinearSO3AHRSinit(float ax, float ay, float az, float mx, float my, float mz) { float initialRoll, initialPitch; float cosRoll, sinRoll, cosPitch, sinPitch; @@ -218,7 +219,7 @@ void MahonyAHRSinit(float ax, float ay, float az, float mx, float my, float mz) q3q3 = q3 * q3; } -void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { +void NonlinearSO3AHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) { float recipNorm; float halfex = 0.0f, halfey = 0.0f, halfez = 0.0f; @@ -228,7 +229,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az //! unlikely happen. if(bFilterInit == false) { - MahonyAHRSinit(ax,ay,az,mx,my,mz); + NonlinearSO3AHRSinit(ax,ay,az,mx,my,mz); bFilterInit = true; } @@ -306,14 +307,25 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az gz += twoKp * halfez; } - // Integrate rate of change of quaternion + //! Integrate rate of change of quaternion +#if 0 gx *= (0.5f * dt); // pre-multiply common factors gy *= (0.5f * dt); gz *= (0.5f * dt); - q0 +=(-q1 * gx - q2 * gy - q3 * gz); - q1 += (q0 * gx + q2 * gz - q3 * gy); - q2 += (q0 * gy - q1 * gz + q3 * gx); - q3 += (q0 * gz + q1 * gy - q2 * gx); +#endif + + // Time derivative of quaternion. q_dot = 0.5*q\otimes omega. + //! q_k = q_{k-1} + dt*\dot{q} + //! \dot{q} = 0.5*q \otimes P(\omega) + dq0 = 0.5f*(-q1 * gx - q2 * gy - q3 * gz); + dq1 = 0.5f*(q0 * gx + q2 * gz - q3 * gy); + dq2 = 0.5f*(q0 * gy - q1 * gz + q3 * gx); + dq3 = 0.5f*(q0 * gz + q1 * gy - q2 * gx); + + q0 += dt*dq0; + q1 += dt*dq1; + q2 += dt*dq2; + q3 += dt*dq3; // Normalise quaternion recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); @@ -528,8 +540,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds struct sensor_combined_s raw; memset(&raw, 0, sizeof(raw)); + + //! Initialize attitude vehicle uORB message. struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); + struct vehicle_status_s state; memset(&state, 0, sizeof(state)); @@ -711,7 +726,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds // NOTE : Accelerometer is reversed. // Because proper mount of PX4 will give you a reversed accelerometer readings. - MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],-acc[0],-acc[1],-acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); + NonlinearSO3AHRSupdate(gyro[0],gyro[1],gyro[2],-acc[0],-acc[1],-acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt); // Convert q->R. Rot_matrix[0] = q0q0 + q1q1 - q2q2 - q3q3;// 11 @@ -752,14 +767,27 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds att.pitch = euler[1] - so3_comp_params.pitch_off; att.yaw = euler[2] - so3_comp_params.yaw_off; - /* FIXME : This can be a problem for rate controller. Rate in body or inertial? */ + //! Euler angle rate. But it needs to be investigated again. + /* + att.rollspeed = 2.0f*(-q1*dq0 + q0*dq1 - q3*dq2 + q2*dq3); + att.pitchspeed = 2.0f*(-q2*dq0 + q3*dq1 + q0*dq2 - q1*dq3); + att.yawspeed = 2.0f*(-q3*dq0 -q2*dq1 + q1*dq2 + q0*dq3); + */ att.rollspeed = gyro[0]; att.pitchspeed = gyro[1]; att.yawspeed = gyro[2]; + att.rollacc = 0; att.pitchacc = 0; att.yawacc = 0; + //! Quaternion + att.q[0] = q0; + att.q[1] = q1; + att.q[2] = q2; + att.q[3] = q3; + att.q_valid = true; + /* TODO: Bias estimation required */ memcpy(&att.rate_offsets, &(gyro_bias), sizeof(att.rate_offsets)); diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c index 1d5e0670a..f962515df 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c @@ -19,8 +19,15 @@ #include "attitude_estimator_so3_comp_params.h" /* This is filter gain for nonlinear SO3 complementary filter */ -PARAM_DEFINE_FLOAT(SO3_COMP_KP, 0.5f); -PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.0f); +/* NOTE : How to tune the gain? First of all, stick with this default gain. And let the quad in stable place. + Log the steady state reponse of filter. If it is too slow, increase SO3_COMP_KP. + If you are flying from ground to high altitude in short amount of time, please increase SO3_COMP_KI which + will compensate gyro bias which depends on temperature and vibration of your vehicle */ +PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f); //! This parameter will give you about 15 seconds convergence time. + //! You can set this gain higher if you want more fast response. + //! But note that higher gain will give you also higher overshoot. +PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.05f); //! This gain will incorporate slow time-varying bias (e.g., temperature change) + //! This gain is depend on your vehicle status. /* offsets in roll, pitch and yaw of sensor plane and body */ PARAM_DEFINE_FLOAT(ATT_ROLL_OFFS, 0.0f); -- cgit v1.2.3 From b09fc1468c8db65ea99dd94f59f5c075dfce5c7e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 6 Jun 2013 17:25:47 +0200 Subject: Hotfix: Fix typos in tutorial code --- src/examples/px4_daemon_app/px4_daemon_app.c | 53 +++++++++++++++------------- 1 file changed, 28 insertions(+), 25 deletions(-) (limited to 'src') diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c index a5d847777..26f31b9e6 100644 --- a/src/examples/px4_daemon_app/px4_daemon_app.c +++ b/src/examples/px4_daemon_app/px4_daemon_app.c @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: @author Example User + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,27 +32,32 @@ ****************************************************************************/ /** - * @file px4_deamon_app.c - * Deamon application example for PX4 autopilot + * @file px4_daemon_app.c + * daemon application example for PX4 autopilot + * + * @author Example User */ #include +#include #include #include -static bool thread_should_exit = false; /**< Deamon exit flag */ -static bool thread_running = false; /**< Deamon status flag */ -static int deamon_task; /**< Handle of deamon task / thread */ +#include + +static bool thread_should_exit = false; /**< daemon exit flag */ +static bool thread_running = false; /**< daemon status flag */ +static int daemon_task; /**< Handle of daemon task / thread */ /** - * Deamon management function. + * daemon management function. */ -__EXPORT int px4_deamon_app_main(int argc, char *argv[]); +__EXPORT int px4_daemon_app_main(int argc, char *argv[]); /** - * Mainloop of deamon. + * Mainloop of daemon. */ -int px4_deamon_thread_main(int argc, char *argv[]); +int px4_daemon_thread_main(int argc, char *argv[]); /** * Print the correct usage. @@ -64,20 +68,19 @@ static void usage(const char *reason) { if (reason) - fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: deamon {start|stop|status} [-p ]\n\n"); - exit(1); + warnx("%s\n", reason); + errx(1, "usage: daemon {start|stop|status} [-p ]\n\n"); } /** - * The deamon app only briefly exists to start + * The daemon app only briefly exists to start * the background job. The stack size assigned in the * Makefile does only apply to this management task. * * The actual stack size should be set in the call * to task_create(). */ -int px4_deamon_app_main(int argc, char *argv[]) +int px4_daemon_app_main(int argc, char *argv[]) { if (argc < 1) usage("missing command"); @@ -85,17 +88,17 @@ int px4_deamon_app_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (thread_running) { - printf("deamon already running\n"); + warnx("daemon already running\n"); /* this is not an error */ exit(0); } thread_should_exit = false; - deamon_task = task_spawn("deamon", + daemon_task = task_spawn("daemon", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 4096, - px4_deamon_thread_main, + px4_daemon_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); exit(0); } @@ -107,9 +110,9 @@ int px4_deamon_app_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tdeamon app is running\n"); + printf("\tdaemon app is running\n"); } else { - printf("\tdeamon app not started\n"); + printf("\tdaemon app not started\n"); } exit(0); } @@ -118,18 +121,18 @@ int px4_deamon_app_main(int argc, char *argv[]) exit(1); } -int px4_deamon_thread_main(int argc, char *argv[]) { +int px4_daemon_thread_main(int argc, char *argv[]) { - printf("[deamon] starting\n"); + printf("[daemon] starting\n"); thread_running = true; while (!thread_should_exit) { - printf("Hello Deamon!\n"); + printf("Hello daemon!\n"); sleep(10); } - printf("[deamon] exiting.\n"); + printf("[daemon] exiting.\n"); thread_running = false; -- cgit v1.2.3 From fa1b057bb158ab62babef625c57956b2b63707e0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 6 Jun 2013 17:27:01 +0200 Subject: Minor cleanup --- src/examples/px4_daemon_app/px4_daemon_app.c | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) (limited to 'src') diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c index 26f31b9e6..4dd5165c8 100644 --- a/src/examples/px4_daemon_app/px4_daemon_app.c +++ b/src/examples/px4_daemon_app/px4_daemon_app.c @@ -110,9 +110,9 @@ int px4_daemon_app_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tdaemon app is running\n"); + warnx("\trunning\n"); } else { - printf("\tdaemon app not started\n"); + warnx("\tnot started\n"); } exit(0); } @@ -123,16 +123,16 @@ int px4_daemon_app_main(int argc, char *argv[]) int px4_daemon_thread_main(int argc, char *argv[]) { - printf("[daemon] starting\n"); + warnx("[daemon] starting\n"); thread_running = true; while (!thread_should_exit) { - printf("Hello daemon!\n"); + warnx("Hello daemon!\n"); sleep(10); } - printf("[daemon] exiting.\n"); + warnx("[daemon] exiting.\n"); thread_running = false; -- cgit v1.2.3