mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
AP_Mission: const writing of commands to storage
This commit is contained in:
parent
b2c5d7f04a
commit
402be4eaca
@ -320,7 +320,7 @@ bool AP_Mission::add_cmd(Mission_Command& cmd)
|
|||||||
/// replace_cmd - replaces the command at position 'index' in the command list with the provided cmd
|
/// replace_cmd - replaces the command at position 'index' in the command list with the provided cmd
|
||||||
/// replacing the current active command will have no effect until the command is restarted
|
/// replacing the current active command will have no effect until the command is restarted
|
||||||
/// returns true if successfully replaced, false on failure
|
/// returns true if successfully replaced, false on failure
|
||||||
bool AP_Mission::replace_cmd(uint16_t index, Mission_Command& cmd)
|
bool AP_Mission::replace_cmd(uint16_t index, const Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
// sanity check index
|
// sanity check index
|
||||||
if (index >= (unsigned)_cmd_total) {
|
if (index >= (unsigned)_cmd_total) {
|
||||||
@ -586,7 +586,7 @@ bool AP_Mission::stored_in_location(uint16_t id)
|
|||||||
/// write_cmd_to_storage - write a command to storage
|
/// write_cmd_to_storage - write a command to storage
|
||||||
/// index is used to calculate the storage location
|
/// index is used to calculate the storage location
|
||||||
/// true is returned if successful
|
/// true is returned if successful
|
||||||
bool AP_Mission::write_cmd_to_storage(uint16_t index, Mission_Command& cmd)
|
bool AP_Mission::write_cmd_to_storage(uint16_t index, const Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
WITH_SEMAPHORE(_rsem);
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
|
@ -381,7 +381,7 @@ public:
|
|||||||
/// replace_cmd - replaces the command at position 'index' in the command list with the provided cmd
|
/// replace_cmd - replaces the command at position 'index' in the command list with the provided cmd
|
||||||
/// replacing the current active command will have no effect until the command is restarted
|
/// replacing the current active command will have no effect until the command is restarted
|
||||||
/// returns true if successfully replaced, false on failure
|
/// returns true if successfully replaced, false on failure
|
||||||
bool replace_cmd(uint16_t index, Mission_Command& cmd);
|
bool replace_cmd(uint16_t index, const Mission_Command& cmd);
|
||||||
|
|
||||||
/// is_nav_cmd - returns true if the command's id is a "navigation" command, false if "do" or "conditional" command
|
/// is_nav_cmd - returns true if the command's id is a "navigation" command, false if "do" or "conditional" command
|
||||||
static bool is_nav_cmd(const Mission_Command& cmd);
|
static bool is_nav_cmd(const Mission_Command& cmd);
|
||||||
@ -433,7 +433,7 @@ public:
|
|||||||
/// write_cmd_to_storage - write a command to storage
|
/// write_cmd_to_storage - write a command to storage
|
||||||
/// cmd.index is used to calculate the storage location
|
/// cmd.index is used to calculate the storage location
|
||||||
/// true is returned if successful
|
/// true is returned if successful
|
||||||
bool write_cmd_to_storage(uint16_t index, Mission_Command& cmd);
|
bool write_cmd_to_storage(uint16_t index, const Mission_Command& cmd);
|
||||||
|
|
||||||
/// write_home_to_storage - writes the special purpose cmd 0 (home) to storage
|
/// write_home_to_storage - writes the special purpose cmd 0 (home) to storage
|
||||||
/// home is taken directly from ahrs
|
/// home is taken directly from ahrs
|
||||||
|
Loading…
Reference in New Issue
Block a user