Mount_SToRM32_serial: fix angle request

This commit is contained in:
Randy Mackay 2015-05-26 18:30:38 +09:00
parent 9b04a67e63
commit fb2d29364e
1 changed files with 3 additions and 3 deletions

View File

@ -179,9 +179,9 @@ void AP_Mount_SToRM32_serial::send_target_angles(float pitch_deg, float roll_deg
yaw_deg = -yaw_deg;
// send CMD_SETANGLE
cmd_set_angles_data.pitch = pitch_deg*100;
cmd_set_angles_data.roll = roll_deg*100;
cmd_set_angles_data.yaw = yaw_deg*100;
cmd_set_angles_data.pitch = pitch_deg;
cmd_set_angles_data.roll = roll_deg;
cmd_set_angles_data.yaw = yaw_deg;
uint8_t* buf = (uint8_t*)&cmd_set_angles_data;