Copter: integrate get_angle_target_for_reporting

Used for logging and sending to GCS
This commit is contained in:
Randy Mackay 2014-02-03 22:04:08 +09:00 committed by Andrew Tridgell
parent d579325e2a
commit e8c4e8a472
2 changed files with 10 additions and 6 deletions

View File

@ -246,11 +246,13 @@ static void NOINLINE send_location(mavlink_channel_t chan)
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
{
Vector3f targets;
get_angle_targets_for_reporting(targets);
mavlink_msg_nav_controller_output_send(
chan,
control_roll / 1.0e2f,
control_pitch / 1.0e2f,
control_yaw / 1.0e2f,
targets.x / 1.0e2f,
targets.y / 1.0e2f,
targets.z / 1.0e2f,
wp_bearing / 1.0e2f,
wp_distance / 1.0e2f,
pos_control.get_alt_error() / 1.0e2f,

View File

@ -469,14 +469,16 @@ struct PACKED log_Attitude {
// Write an attitude packet
static void Log_Write_Attitude()
{
Vector3f targets;
get_angle_targets_for_reporting(targets);
struct log_Attitude pkt = {
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
time_ms : hal.scheduler->millis(),
control_roll : (int16_t)control_roll,
control_roll : (int16_t)targets.x,
roll : (int16_t)ahrs.roll_sensor,
control_pitch : (int16_t)control_pitch,
control_pitch : (int16_t)targets.y,
pitch : (int16_t)ahrs.pitch_sensor,
control_yaw : (uint16_t)control_yaw,
control_yaw : (uint16_t)targets.z,
yaw : (uint16_t)ahrs.yaw_sensor
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));