mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: formatting and comment fixes to mode class
This commit is contained in:
parent
4368df7f11
commit
848df551ac
@ -34,7 +34,7 @@ void Mode::set_desired_location(const struct Location& destination)
|
|||||||
_desired_speed = g.speed_cruise;
|
_desired_speed = g.speed_cruise;
|
||||||
|
|
||||||
// initialise distance
|
// initialise distance
|
||||||
_distance_to_destination = get_distance(rover.current_loc, _destination);
|
_distance_to_destination = get_distance(_origin, _destination);
|
||||||
_reached_destination = false;
|
_reached_destination = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -106,7 +106,7 @@ protected:
|
|||||||
class AP_AHRS &ahrs;
|
class AP_AHRS &ahrs;
|
||||||
class Parameters &g;
|
class Parameters &g;
|
||||||
class ParametersG2 &g2;
|
class ParametersG2 &g2;
|
||||||
class RC_Channel *&channel_steer; // TODO : Pointer reference ?
|
class RC_Channel *&channel_steer;
|
||||||
class RC_Channel *&channel_throttle;
|
class RC_Channel *&channel_throttle;
|
||||||
class AP_Mission &mission;
|
class AP_Mission &mission;
|
||||||
|
|
||||||
|
@ -133,7 +133,7 @@ void ModeGuided::set_desired_heading_delta_and_speed(float yaw_delta_cd, float t
|
|||||||
_guided_mode = ModeGuided::Guided_HeadingAndSpeed;
|
_guided_mode = ModeGuided::Guided_HeadingAndSpeed;
|
||||||
_desired_yaw_cd = ahrs.yaw_sensor;
|
_desired_yaw_cd = ahrs.yaw_sensor;
|
||||||
}
|
}
|
||||||
set_desired_heading_and_speed(wrap_180_cd(_desired_yaw_cd+yaw_delta_cd), target_speed);
|
set_desired_heading_and_speed(wrap_180_cd(_desired_yaw_cd + yaw_delta_cd), target_speed);
|
||||||
}
|
}
|
||||||
|
|
||||||
// set desired velocity
|
// set desired velocity
|
||||||
|
Loading…
Reference in New Issue
Block a user