mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
APMrover2: Remove post_ignore check since is always true
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
de2cf89b60
commit
21e5922b2e
@ -863,19 +863,19 @@ void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg)
|
||||
// GCS will need to monitor desired location to
|
||||
// see if they are having an effect.
|
||||
}
|
||||
} else if (pos_ignore && !vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
||||
} else if (!vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
||||
// consume velocity
|
||||
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
||||
} else if (pos_ignore && !vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
||||
} else if (!vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
||||
// consume velocity and turn rate
|
||||
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, speed_dir * target_speed);
|
||||
} else if (pos_ignore && !vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
||||
} else if (!vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
||||
// consume velocity and heading
|
||||
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
||||
} else if (pos_ignore && vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
||||
} else if (vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
||||
// consume just target heading (probably only skid steering vehicles can do this)
|
||||
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, 0.0f);
|
||||
} else if (pos_ignore && vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
||||
} else if (vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
||||
// consume just turn rate (probably only skid steering vehicles can do this)
|
||||
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
|
||||
}
|
||||
@ -968,19 +968,19 @@ void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg)
|
||||
// GCS will just need to look at desired location
|
||||
// outputs to see if it having an effect.
|
||||
}
|
||||
} else if (pos_ignore && !vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
||||
} else if (!vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
||||
// consume velocity
|
||||
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
||||
} else if (pos_ignore && !vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
||||
} else if (!vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
||||
// consume velocity and turn rate
|
||||
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, speed_dir * target_speed);
|
||||
} else if (pos_ignore && !vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
||||
} else if (!vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
||||
// consume velocity
|
||||
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
||||
} else if (pos_ignore && vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
||||
} else if (vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
||||
// consume just target heading (probably only skid steering vehicles can do this)
|
||||
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, 0.0f);
|
||||
} else if (pos_ignore && vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
||||
} else if (vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
||||
// consume just turn rate(probably only skid steering vehicles can do this)
|
||||
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user