Skip to content

Commit

Permalink
Rover: Change division to multiplication
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Apr 20, 2024
1 parent 7fce1cd commit bf8c1f5
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 9 deletions.
6 changes: 3 additions & 3 deletions Rover/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,11 +124,11 @@ void GCS_MAVLINK_Rover::send_servo_out()
{
float motor1, motor3;
if (rover.g2.motors.have_skid_steering()) {
motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleLeft) / 1000.0f);
motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleRight) / 1000.0f);
motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleLeft) * 0.001f);
motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleRight) * 0.001f);
} else {
motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_steering) / 4500.0f);
motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) / 100.0f);
motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01f);
}
mavlink_msg_rc_channels_scaled_send(
chan,
Expand Down
8 changes: 4 additions & 4 deletions Rover/Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -244,19 +244,19 @@ bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float &
control_value = constrain_float(g2.motors.get_walking_height(), -1.0f, 1.0f);
return true;
case AP_Vehicle::ControlOutput::Throttle:
control_value = constrain_float(g2.motors.get_throttle() / 100.0f, -1.0f, 1.0f);
control_value = constrain_float(g2.motors.get_throttle() * 0.01f, -1.0f, 1.0f);
return true;
case AP_Vehicle::ControlOutput::Yaw:
control_value = constrain_float(g2.motors.get_steering() / 4500.0f, -1.0f, 1.0f);
return true;
case AP_Vehicle::ControlOutput::Lateral:
control_value = constrain_float(g2.motors.get_lateral() / 100.0f, -1.0f, 1.0f);
control_value = constrain_float(g2.motors.get_lateral() * 0.01f, -1.0f, 1.0f);
return true;
case AP_Vehicle::ControlOutput::MainSail:
control_value = constrain_float(g2.motors.get_mainsail() / 100.0f, -1.0f, 1.0f);
control_value = constrain_float(g2.motors.get_mainsail() * 0.01f, -1.0f, 1.0f);
return true;
case AP_Vehicle::ControlOutput::WingSail:
control_value = constrain_float(g2.motors.get_wingsail() / 100.0f, -1.0f, 1.0f);
control_value = constrain_float(g2.motors.get_wingsail() * 0.01f, -1.0f, 1.0f);
return true;
default:
return false;
Expand Down
2 changes: 1 addition & 1 deletion Rover/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ void Mode::get_pilot_desired_steering_and_throttle(float &steering_out, float &t
// we proportionally reduce steering and throttle
if (g2.motors.have_skid_steering()) {
const float steer_normalised = constrain_float(steering_out / 4500.0f, -1.0f, 1.0f);
const float throttle_normalised = constrain_float(throttle_out / 100.0f, -1.0f, 1.0f);
const float throttle_normalised = constrain_float(throttle_out * 0.01f, -1.0f, 1.0f);
const float saturation_value = fabsf(steer_normalised) + fabsf(throttle_normalised);
if (saturation_value > 1.0f) {
steering_out /= saturation_value;
Expand Down
2 changes: 1 addition & 1 deletion Rover/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ void ModeGuided::update()
}
if (have_attitude_target) {
// run steering and throttle controllers
float steering_out = attitude_control.get_steering_out_rate(radians(_desired_yaw_rate_cds / 100.0f),
float steering_out = attitude_control.get_steering_out_rate(radians(_desired_yaw_rate_cds * 0.01f),
g2.motors.limit.steer_left,
g2.motors.limit.steer_right,
rover.G_Dt);
Expand Down

0 comments on commit bf8c1f5

Please sign in to comment.