mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Rover: add const to mode::speed_error
This commit is contained in:
parent
8f08f5189a
commit
22ef276484
@ -82,7 +82,7 @@ public:
|
|||||||
virtual void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed);
|
virtual void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed);
|
||||||
|
|
||||||
// get speed error in m/s, returns zero for modes that do not control speed
|
// get speed error in m/s, returns zero for modes that do not control speed
|
||||||
float speed_error() { return _speed_error; }
|
float speed_error() const { return _speed_error; }
|
||||||
|
|
||||||
// Navigation control variables
|
// Navigation control variables
|
||||||
// The instantaneous desired lateral acceleration in m/s/s
|
// The instantaneous desired lateral acceleration in m/s/s
|
||||||
|
Loading…
Reference in New Issue
Block a user