GCS_MAVLink: log vision data pitch/roll/yaw in degree

This commit is contained in:
chobits 2018-09-14 13:59:06 +08:00 committed by Randy Mackay
parent e51d842ca5
commit ed12c6719d

View File

@ -2216,15 +2216,15 @@ void GCS_MAVLINK::log_vision_position_estimate_data(const uint64_t usec,
const float yaw) const float yaw)
{ {
DataFlash_Class::instance()->Log_Write("VISP", "TimeUS,RemTimeUS,PX,PY,PZ,Roll,Pitch,Yaw", DataFlash_Class::instance()->Log_Write("VISP", "TimeUS,RemTimeUS,PX,PY,PZ,Roll,Pitch,Yaw",
"ssmmmrrr", "FF000000", "QQffffff", "ssmmmddh", "FF000000", "QQffffff",
(uint64_t)AP_HAL::micros64(), (uint64_t)AP_HAL::micros64(),
(uint64_t)usec, (uint64_t)usec,
(double)x, (double)x,
(double)y, (double)y,
(double)z, (double)z,
(double)roll, (double)(roll * RAD_TO_DEG),
(double)pitch, (double)(pitch * RAD_TO_DEG),
(double)yaw); (double)(yaw * RAD_TO_DEG));
} }
void GCS_MAVLINK::handle_att_pos_mocap(mavlink_message_t *msg) void GCS_MAVLINK::handle_att_pos_mocap(mavlink_message_t *msg)