Copter: Remove support for CONDITION_CHANGE_ALT

This commit is contained in:
Michael du Breuil 2016-04-26 04:27:40 -07:00 committed by Randy Mackay
parent de1e299754
commit c97888f524
2 changed files with 0 additions and 20 deletions

View File

@ -704,7 +704,6 @@ private:
bool verify_loiter_time();
bool verify_RTL();
bool verify_wait_delay();
bool verify_change_alt();
bool verify_within_distance();
bool verify_yaw();
void do_take_picture();
@ -1017,7 +1016,6 @@ private:
#endif
void do_wait_delay(const AP_Mission::Mission_Command& cmd);
void do_within_distance(const AP_Mission::Mission_Command& cmd);
void do_change_alt(const AP_Mission::Mission_Command& cmd);
void do_yaw(const AP_Mission::Mission_Command& cmd);
void do_change_speed(const AP_Mission::Mission_Command& cmd);
void do_set_home(const AP_Mission::Mission_Command& cmd);

View File

@ -64,10 +64,6 @@ bool Copter::start_command(const AP_Mission::Mission_Command& cmd)
do_within_distance(cmd);
break;
case MAV_CMD_CONDITION_CHANGE_ALT: // 113
do_change_alt(cmd);
break;
case MAV_CMD_CONDITION_YAW: // 115
do_yaw(cmd);
break;
@ -225,9 +221,6 @@ bool Copter::verify_command(const AP_Mission::Mission_Command& cmd)
case MAV_CMD_CONDITION_DISTANCE:
return verify_within_distance();
case MAV_CMD_CONDITION_CHANGE_ALT:
return verify_change_alt();
case MAV_CMD_CONDITION_YAW:
return verify_yaw();
@ -736,11 +729,6 @@ void Copter::do_wait_delay(const AP_Mission::Mission_Command& cmd)
condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds
}
void Copter::do_change_alt(const AP_Mission::Mission_Command& cmd)
{
// To-Do: store desired altitude in a variable so that it can be verified later
}
void Copter::do_within_distance(const AP_Mission::Mission_Command& cmd)
{
condition_value = cmd.content.distance.meters * 100;
@ -769,12 +757,6 @@ bool Copter::verify_wait_delay()
return false;
}
bool Copter::verify_change_alt()
{
// To-Do: use recorded target altitude to verify we have reached the target
return true;
}
bool Copter::verify_within_distance()
{
// update distance calculation