From df55ae86c433c0cf5d54d69272b5cc27f922c7e3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 6 Aug 2014 16:17:11 +1000 Subject: [PATCH] AP_Mission: added last_change_time_ms() call will be used by terrain lib for scanning waypoints --- libraries/AP_Mission/AP_Mission.cpp | 5 +++++ libraries/AP_Mission/AP_Mission.h | 9 ++++++++- 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 620b1c29d4..b0f5f216a7 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -42,6 +42,8 @@ void AP_Mission::init() if (sizeof(union Content) != 12) { hal.scheduler->panic(PSTR("AP_Mission Content must be 12 bytes")); } + + _last_change_time_ms = hal.scheduler->millis(); } /// start - resets current commands to point to the beginning of the mission @@ -423,6 +425,9 @@ bool AP_Mission::write_cmd_to_storage(uint16_t index, Mission_Command& cmd) hal.storage->write_word(pos_in_storage+1, cmd.p1); hal.storage->write_block(pos_in_storage+3, cmd.content.bytes, 12); + // remember when the mission last changed + _last_change_time_ms = hal.scheduler->millis(); + // return success return true; } diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index a91086c9d5..ee8c43c903 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -189,7 +189,8 @@ public: _cmd_start_fn(cmd_start_fn), _cmd_verify_fn(cmd_verify_fn), _mission_complete_fn(mission_complete_fn), - _prev_nav_cmd_index(AP_MISSION_CMD_INDEX_NONE) + _prev_nav_cmd_index(AP_MISSION_CMD_INDEX_NONE), + _last_change_time_ms(0) { // load parameter defaults AP_Param::setup_object_defaults(this, var_info); @@ -320,6 +321,9 @@ public: // return true on success, false on failure static bool mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_t& packet); + // return the last time the mission changed in milliseconds + uint32_t last_change_time_ms(void) const { return _last_change_time_ms; } + // user settable parameters static const struct AP_Param::GroupInfo var_info[]; @@ -403,6 +407,9 @@ private: uint16_t index; // index of do-jump commands in mission int16_t num_times_run; // number of times this jump command has been run } _jump_tracking[AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS]; + + // last time that mission changed + uint32_t _last_change_time_ms; }; #endif