AP_Mount: Alexmos minor comment fix

This commit is contained in:
Randy Mackay 2022-06-03 12:36:18 +09:00
parent 6423a2dfb9
commit 6303a7d958
2 changed files with 2 additions and 2 deletions

View File

@ -145,7 +145,7 @@ void AP_Mount_Alexmos::get_boardinfo()
}
/*
control_axis : send new angles to the gimbal at a fixed speed of 30 deg/s2
control_axis : send new angles to the gimbal at a fixed speed of 30 deg/s
*/
void AP_Mount_Alexmos::control_axis(const Vector3f& angle, bool target_in_degrees)
{

View File

@ -55,7 +55,7 @@
#define AP_MOUNT_ALEXMOS_MODE_SPEED_ANGLE 3
#define AP_MOUNT_ALEXMOS_MODE_RC 4
#define AP_MOUNT_ALEXMOS_SPEED 30 // degree/s2
#define AP_MOUNT_ALEXMOS_SPEED 30 // deg/s
#define VALUE_TO_DEGREE(d) ((float)((d * 720) >> 15))
#define DEGREE_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/0.02197265625f)))