mirror of https://github.com/ArduPilot/ardupilot
Logging fix's
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1888 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
0f5505e529
commit
dc615e6320
|
@ -611,7 +611,7 @@ void medium_loop()
|
|||
medium_loopCounter++;
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED && (g.log_bitmask & MASK_LOG_ATTITUDE_FAST == 0))
|
||||
Log_Write_Attitude((int)dcm.roll_sensor, (int)dcm.pitch_sensor, (int)dcm.yaw_sensor);
|
||||
Log_Write_Attitude((int)dcm.roll_sensor, (int)dcm.pitch_sensor, (uint16_t)dcm.yaw_sensor);
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
if (g.log_bitmask & MASK_LOG_CTUN)
|
||||
|
|
|
@ -185,10 +185,10 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
|
|||
motor_out[1],
|
||||
motor_out[2],
|
||||
motor_out[3],
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0);
|
||||
motor_out[4],
|
||||
motor_out[5],
|
||||
motor_out[6],
|
||||
motor_out[7]);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -276,4 +276,4 @@ void mavlink_acknowledge(mavlink_channel_t chan, uint8_t id, uint8_t sum1, uint8
|
|||
|
||||
#endif // mavlink in use
|
||||
|
||||
#endif // inclusion guard
|
||||
#endif // inclusion guard
|
||||
|
|
|
@ -71,7 +71,7 @@ set_servos_4()
|
|||
|
||||
// limit Yaw control so we don't clip and loose altitude
|
||||
// this is only a partial solution.
|
||||
g.rc_4.pwm_out = min(g.rc_4.pwm_out, (g.rc_3.radio_out - out_min));
|
||||
//g.rc_4.pwm_out = min(g.rc_4.pwm_out, (g.rc_3.radio_out - out_min));
|
||||
|
||||
//Serial.printf("out: %d %d %d %d\n", g.rc_1.radio_out, g.rc_2.radio_out, g.rc_3.radio_out, g.rc_4.radio_out);
|
||||
//Serial.printf("yaw: %d ", g.rc_4.radio_out);
|
||||
|
|
Loading…
Reference in New Issue