mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: use float qualifier and functions
This commit is contained in:
parent
1f0c985dec
commit
8ab3e83a3c
@ -442,8 +442,8 @@ void Rover::update_current_mode(void)
|
||||
gcs_send_mission_item_reached_message(0);
|
||||
}
|
||||
g2.motors.set_throttle(g.throttle_min.get());
|
||||
g2.motors.set_steering(0);
|
||||
lateral_acceleration = 0;
|
||||
g2.motors.set_steering(0.0f);
|
||||
lateral_acceleration = 0.0f;
|
||||
} else {
|
||||
calc_lateral_acceleration();
|
||||
calc_nav_steer();
|
||||
@ -502,8 +502,8 @@ void Rover::update_current_mode(void)
|
||||
|
||||
case HOLD:
|
||||
// hold position - stop motors and center steering
|
||||
g2.motors.set_throttle(0);
|
||||
g2.motors.set_steering(0);
|
||||
g2.motors.set_throttle(0.0f);
|
||||
g2.motors.set_steering(0.0f);
|
||||
if (!in_auto_reverse) {
|
||||
set_reverse(false);
|
||||
}
|
||||
@ -553,8 +553,8 @@ void Rover::update_navigation()
|
||||
if (rtl_complete || verify_RTL()) {
|
||||
// we have reached destination so stop where we are
|
||||
g2.motors.set_throttle(g.throttle_min.get());
|
||||
g2.motors.set_steering(0);
|
||||
lateral_acceleration = 0;
|
||||
g2.motors.set_steering(0.0f);
|
||||
lateral_acceleration = 0.0f;
|
||||
} else {
|
||||
calc_lateral_acceleration();
|
||||
calc_nav_steer();
|
||||
|
@ -200,9 +200,9 @@ void AP_MotorsUGV::output_skid_steering(bool armed, float steering, float thrott
|
||||
void AP_MotorsUGV::slew_limit_throttle(float dt)
|
||||
{
|
||||
if (_use_slew_rate && (_slew_rate > 0)) {
|
||||
float temp = _slew_rate * dt * 0.01f * 100; // TODO : get THROTTLE MIN and THROTTLE MAX
|
||||
if (temp < 1) {
|
||||
temp = 1;
|
||||
float temp = _slew_rate * dt * 0.01f * 100.0f; // TODO : get THROTTLE MIN and THROTTLE MAX
|
||||
if (temp < 1.0f) {
|
||||
temp = 1.0f;
|
||||
}
|
||||
_throttle = constrain_int16(_throttle, _last_throttle - temp, _last_throttle + temp);
|
||||
}
|
||||
|
@ -104,7 +104,7 @@ void Rover::calc_throttle(float target_speed) {
|
||||
g2.motors.set_throttle(g.throttle_min.get());
|
||||
// Stop rotation in case of loitering and skid steering
|
||||
if (g2.motors.have_skid_steering()) {
|
||||
g2.motors.set_steering(0);
|
||||
g2.motors.set_steering(0.0f);
|
||||
}
|
||||
return;
|
||||
}
|
||||
@ -172,7 +172,7 @@ void Rover::calc_throttle(float target_speed) {
|
||||
if (guided_mode != Guided_Velocity) {
|
||||
if (use_pivot_steering()) {
|
||||
// In Guided Velocity, only the steering input is used to calculate the pivot turn.
|
||||
g2.motors.set_throttle(0);
|
||||
g2.motors.set_throttle(0.0f);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -223,7 +223,7 @@ void Rover::calc_lateral_acceleration() {
|
||||
void Rover::calc_nav_steer() {
|
||||
// check to see if the rover is loitering
|
||||
if (in_stationary_loiter()) {
|
||||
g2.motors.set_steering(0);
|
||||
g2.motors.set_steering(0.0f);
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -378,7 +378,7 @@ void Rover::nav_set_yaw_speed()
|
||||
if ((millis() - guided_control.msg_time_ms) > 3000) {
|
||||
gcs_send_text(MAV_SEVERITY_WARNING, "NAV_SET_YAW_SPEED not recvd last 3secs, stopping");
|
||||
g2.motors.set_throttle(g.throttle_min.get());
|
||||
g2.motors.set_steering(0);
|
||||
g2.motors.set_steering(0.0f);
|
||||
lateral_acceleration = 0.0f;
|
||||
return;
|
||||
}
|
||||
@ -401,7 +401,7 @@ void Rover::nav_set_speed()
|
||||
if ((millis() - guided_control.msg_time_ms) > 3000) {
|
||||
gcs_send_text(MAV_SEVERITY_WARNING, "SET_VELOCITY not recvd last 3secs, stopping");
|
||||
g2.motors.set_throttle(g.throttle_min.get());
|
||||
g2.motors.set_steering(0);
|
||||
g2.motors.set_steering(0.0f);
|
||||
lateral_acceleration = 0.0f;
|
||||
prev_WP = current_loc;
|
||||
next_WP = current_loc;
|
||||
@ -473,9 +473,9 @@ bool Rover::do_yaw_rotation()
|
||||
|
||||
// check if we are within 5 degrees of the target heading
|
||||
if (error_to_target_yaw <= 500) {
|
||||
g2.motors.set_steering(0); // stop the current rotation
|
||||
g2.motors.set_steering(0.0f); // stop the current rotation
|
||||
condition_value = condition_start; // reset the condition value to its previous value
|
||||
g2.motors.set_throttle(0);
|
||||
g2.motors.set_throttle(0.0f);
|
||||
next_navigation_leg_cd = mission.get_next_ground_course_cd(0);
|
||||
do_auto_rotation = false;
|
||||
return true;
|
||||
|
@ -158,9 +158,9 @@ void Rover::read_radio()
|
||||
|
||||
// Check if the throttle value is above 50% and we need to nudge
|
||||
// Make sure its above 50% in the direction we are travelling
|
||||
if ((fabs(g2.motors.get_throttle()) > 50) &&
|
||||
(((g2.motors.get_throttle() < 0) && in_reverse) ||
|
||||
((g2.motors.get_throttle() > 0) && !in_reverse))) {
|
||||
if ((fabsf(g2.motors.get_throttle()) > 50.0f) &&
|
||||
((is_negative(g2.motors.get_throttle()) && in_reverse) ||
|
||||
(is_positive(g2.motors.get_throttle()) && !in_reverse))) {
|
||||
throttle_nudge = (g.throttle_max - g.throttle_cruise) *
|
||||
((fabsf(channel_throttle->norm_input()) - 0.5f) / 0.5f);
|
||||
} else {
|
||||
|
Loading…
Reference in New Issue
Block a user