mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Mount: minor comment fix to has_pan_control
This commit is contained in:
parent
38360b8c7b
commit
de3d763e36
@ -96,7 +96,7 @@ void AP_Mount_Alexmos::update()
|
|||||||
control_axis(_angle_rad);
|
control_axis(_angle_rad);
|
||||||
}
|
}
|
||||||
|
|
||||||
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
// has_pan_control - returns true if this mount can control its pan (required for multicopters)
|
||||||
bool AP_Mount_Alexmos::has_pan_control() const
|
bool AP_Mount_Alexmos::has_pan_control() const
|
||||||
{
|
{
|
||||||
return _gimbal_3axis && yaw_range_valid();
|
return _gimbal_3axis && yaw_range_valid();
|
||||||
|
@ -29,7 +29,7 @@ public:
|
|||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
// has_pan_control - returns true if this mount can control its pan (required for multicopters)
|
||||||
bool has_pan_control() const override { return yaw_range_valid(); }
|
bool has_pan_control() const override { return yaw_range_valid(); }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
@ -32,7 +32,7 @@ public:
|
|||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
// has_pan_control - returns true if this mount can control its pan (required for multicopters)
|
||||||
bool has_pan_control() const override { return yaw_range_valid(); };
|
bool has_pan_control() const override { return yaw_range_valid(); };
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
@ -29,7 +29,7 @@ public:
|
|||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
// has_pan_control - returns true if this mount can control its pan (required for multicopters)
|
||||||
bool has_pan_control() const override { return false; }
|
bool has_pan_control() const override { return false; }
|
||||||
|
|
||||||
// handle a GIMBAL_REPORT message
|
// handle a GIMBAL_REPORT message
|
||||||
|
Loading…
Reference in New Issue
Block a user