mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Mount: Alexmos minor comment fix
This commit is contained in:
parent
6423a2dfb9
commit
6303a7d958
@ -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)
|
||||
{
|
||||
|
@ -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)))
|
||||
|
Loading…
Reference in New Issue
Block a user