Rover: bring rover mission callback inline with copter and plane

This commit is contained in:
Tom Pittenger 2015-07-24 01:20:49 -07:00 committed by Randy Mackay
parent 4af7e454df
commit 9c75900746
3 changed files with 12 additions and 10 deletions

View File

@ -32,7 +32,7 @@ Rover::Rover(void) :
steerController(ahrs), steerController(ahrs),
mission(ahrs, mission(ahrs,
FUNCTOR_BIND_MEMBER(&Rover::start_command, bool, const AP_Mission::Mission_Command&), FUNCTOR_BIND_MEMBER(&Rover::start_command, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&Rover::verify_command, bool, const AP_Mission::Mission_Command&), FUNCTOR_BIND_MEMBER(&Rover::verify_command_callback, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)), FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)),
num_gcs(MAVLINK_COMM_NUM_BUFFERS), num_gcs(MAVLINK_COMM_NUM_BUFFERS),
ServoRelayEvents(relay), ServoRelayEvents(relay),

View File

@ -490,6 +490,7 @@ private:
void print_mode(AP_HAL::BetterStream *port, uint8_t mode); void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
bool start_command(const AP_Mission::Mission_Command& cmd); bool start_command(const AP_Mission::Mission_Command& cmd);
bool verify_command(const AP_Mission::Mission_Command& cmd); bool verify_command(const AP_Mission::Mission_Command& cmd);
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
void do_nav_wp(const AP_Mission::Mission_Command& cmd); void do_nav_wp(const AP_Mission::Mission_Command& cmd);
bool verify_nav_wp(const AP_Mission::Mission_Command& cmd); bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
void do_wait_delay(const AP_Mission::Mission_Command& cmd); void do_wait_delay(const AP_Mission::Mission_Command& cmd);

View File

@ -122,6 +122,16 @@ void Rover::exit_mission()
} }
} }
// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
bool Plane::verify_command_callback(const AP_Mission::Mission_Command& cmd)
{
if (control_mode == AUTO) {
bool cmd_complete = verify_command(cmd);
return cmd_complete;
}
return false;
}
/********************************************************************************/ /********************************************************************************/
// Verify command Handlers // Verify command Handlers
// Returns true if command complete // Returns true if command complete
@ -129,12 +139,6 @@ void Rover::exit_mission()
bool Rover::verify_command(const AP_Mission::Mission_Command& cmd) bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
{ {
// exit immediately if not in AUTO mode
// we return true or we will continue to be called by ap-mission
if (control_mode != AUTO) {
return true;
}
switch(cmd.id) { switch(cmd.id) {
case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_WAYPOINT:
@ -145,11 +149,9 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
case MAV_CMD_CONDITION_DELAY: case MAV_CMD_CONDITION_DELAY:
return verify_wait_delay(); return verify_wait_delay();
break;
case MAV_CMD_CONDITION_DISTANCE: case MAV_CMD_CONDITION_DISTANCE:
return verify_within_distance(); return verify_within_distance();
break;
default: default:
if (cmd.id > MAV_CMD_CONDITION_LAST) { if (cmd.id > MAV_CMD_CONDITION_LAST) {
@ -158,7 +160,6 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
} }
gcs_send_text_P(SEVERITY_HIGH,PSTR("verify_conditon: Unsupported command")); gcs_send_text_P(SEVERITY_HIGH,PSTR("verify_conditon: Unsupported command"));
return true; return true;
break;
} }
return false; return false;
} }