Skip to content

Commit 43db855

Browse files
committed
AP_SmartRTL: use enum class for Action, number entries
we log these values, so number them explicitly
1 parent c388943 commit 43db855

File tree

2 files changed

+30
-30
lines changed

2 files changed

+30
-30
lines changed

libraries/AP_SmartRTL/AP_SmartRTL.cpp

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,7 @@ void AP_SmartRTL::init()
117117

118118
// check if memory allocation failed
119119
if (_path == nullptr || _prune.loops == nullptr || _simplify.stack == nullptr) {
120-
log_action(SRTL_DEACTIVATED_INIT_FAILED);
120+
log_action(Action::DEACTIVATED_INIT_FAILED);
121121
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "SmartRTL deactivated: init failed");
122122
free(_path);
123123
free(_prune.loops);
@@ -150,7 +150,7 @@ bool AP_SmartRTL::pop_point(Vector3f& point)
150150

151151
// get semaphore
152152
if (!_path_sem.take_nonblocking()) {
153-
log_action(SRTL_POP_FAILED_NO_SEMAPHORE);
153+
log_action(Action::POP_FAILED_NO_SEMAPHORE);
154154
return false;
155155
}
156156

@@ -180,7 +180,7 @@ bool AP_SmartRTL::peek_point(Vector3f& point)
180180

181181
// get semaphore
182182
if (!_path_sem.take_nonblocking()) {
183-
log_action(SRTL_PEEK_FAILED_NO_SEMAPHORE);
183+
log_action(Action::PEEK_FAILED_NO_SEMAPHORE);
184184
return false;
185185
}
186186

@@ -268,12 +268,12 @@ void AP_SmartRTL::update(bool position_ok, const Vector3f& current_pos)
268268
_last_position_save_ms = now;
269269
} else if (AP_HAL::millis() - _last_position_save_ms > SMARTRTL_TIMEOUT) {
270270
// deactivate after timeout due to failure to save points to path (most likely due to buffer filling up)
271-
deactivate(SRTL_DEACTIVATED_PATH_FULL_TIMEOUT, "buffer full");
271+
deactivate(Action::DEACTIVATED_PATH_FULL_TIMEOUT, "buffer full");
272272
}
273273
} else {
274274
// check for timeout due to bad position
275275
if (AP_HAL::millis() - _last_good_position_ms > SMARTRTL_TIMEOUT) {
276-
deactivate(SRTL_DEACTIVATED_BAD_POSITION_TIMEOUT, "bad position");
276+
deactivate(Action::DEACTIVATED_BAD_POSITION_TIMEOUT, "bad position");
277277
return;
278278
}
279279
}
@@ -322,7 +322,7 @@ bool AP_SmartRTL::add_point(const Vector3f& point)
322322
{
323323
// get semaphore
324324
if (!_path_sem.take_nonblocking()) {
325-
log_action(SRTL_ADD_FAILED_NO_SEMAPHORE, point);
325+
log_action(Action::ADD_FAILED_NO_SEMAPHORE, point);
326326
return false;
327327
}
328328

@@ -338,13 +338,13 @@ bool AP_SmartRTL::add_point(const Vector3f& point)
338338
// check we have space in the path
339339
if (_path_points_count >= _path_points_max) {
340340
_path_sem.give();
341-
log_action(SRTL_ADD_FAILED_PATH_FULL, point);
341+
log_action(Action::ADD_FAILED_PATH_FULL, point);
342342
return false;
343343
}
344344

345345
// add point to path
346346
_path[_path_points_count++] = point;
347-
log_action(SRTL_POINT_ADD, point);
347+
log_action(Action::POINT_ADD, point);
348348

349349
_path_sem.give();
350350
return true;
@@ -672,7 +672,7 @@ void AP_SmartRTL::remove_points_by_simplify_bitmask()
672672
uint16_t removed = 0;
673673
for (uint16_t src = 1; src < _path_points_count; src++) {
674674
if (!_simplify.bitmask.get(src)) {
675-
log_action(SRTL_POINT_SIMPLIFY, _path[src]);
675+
log_action(Action::POINT_SIMPLIFY, _path[src]);
676676
removed++;
677677
} else {
678678
_path[dest] = _path[src];
@@ -687,7 +687,7 @@ void AP_SmartRTL::remove_points_by_simplify_bitmask()
687687
_simplify.path_points_completed = _simplify.path_points_count;
688688
} else {
689689
// this is an error that should never happen so deactivate
690-
deactivate(SRTL_DEACTIVATED_PROGRAM_ERROR, "program error");
690+
deactivate(Action::DEACTIVATED_PROGRAM_ERROR, "program error");
691691
}
692692

693693
_path_sem.give();
@@ -724,7 +724,7 @@ bool AP_SmartRTL::remove_points_by_loops(uint16_t num_points_to_remove)
724724
// shift points after the end of the loop down by the number of points in the loop
725725
uint16_t loop_num_points_to_remove = loop.end_index - loop.start_index;
726726
for (uint16_t dest = loop.start_index + 1; dest < _path_points_count - loop_num_points_to_remove; dest++) {
727-
log_action(SRTL_POINT_PRUNE, _path[dest]);
727+
log_action(Action::POINT_PRUNE, _path[dest]);
728728
_path[dest] = _path[dest + loop_num_points_to_remove];
729729
}
730730

@@ -733,7 +733,7 @@ bool AP_SmartRTL::remove_points_by_loops(uint16_t num_points_to_remove)
733733
removed_points += loop_num_points_to_remove;
734734
} else {
735735
// this is an error that should never happen so deactivate
736-
deactivate(SRTL_DEACTIVATED_PROGRAM_ERROR, "program error");
736+
deactivate(Action::DEACTIVATED_PROGRAM_ERROR, "program error");
737737
_path_sem.give();
738738
// we return true so thorough_cleanup does not get stuck
739739
return true;
@@ -862,7 +862,7 @@ AP_SmartRTL::dist_point AP_SmartRTL::segment_segment_dist(const Vector3f &p1, co
862862
}
863863

864864
// de-activate SmartRTL, send warning to GCS and logger
865-
void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason)
865+
void AP_SmartRTL::deactivate(Action action, const char *reason)
866866
{
867867
_active = false;
868868
log_action(action);
@@ -871,7 +871,7 @@ void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason)
871871

872872
#if HAL_LOGGING_ENABLED
873873
// logging
874-
void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point) const
874+
void AP_SmartRTL::log_action(Action action, const Vector3f &point) const
875875
{
876876
if (!_example_mode) {
877877
AP::logger().Write_SRTL(_active, _path_points_count, _path_points_max, action, point);

libraries/AP_SmartRTL/AP_SmartRTL.h

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -88,19 +88,19 @@ class AP_SmartRTL {
8888
private:
8989

9090
// enums for logging latest actions
91-
enum SRTL_Actions {
92-
SRTL_POINT_ADD,
93-
SRTL_POINT_PRUNE,
94-
SRTL_POINT_SIMPLIFY,
95-
SRTL_ADD_FAILED_NO_SEMAPHORE,
96-
SRTL_ADD_FAILED_PATH_FULL,
97-
SRTL_POP_FAILED_NO_SEMAPHORE,
98-
SRTL_PEEK_FAILED_NO_SEMAPHORE,
99-
SRTL_DEACTIVATED_INIT_FAILED,
100-
SRTL_DEACTIVATED_BAD_POSITION,
101-
SRTL_DEACTIVATED_BAD_POSITION_TIMEOUT,
102-
SRTL_DEACTIVATED_PATH_FULL_TIMEOUT,
103-
SRTL_DEACTIVATED_PROGRAM_ERROR,
91+
enum Action : uint8_t {
92+
POINT_ADD = 0,
93+
POINT_PRUNE = 1,
94+
POINT_SIMPLIFY = 2,
95+
ADD_FAILED_NO_SEMAPHORE = 3,
96+
ADD_FAILED_PATH_FULL = 4,
97+
POP_FAILED_NO_SEMAPHORE = 5,
98+
PEEK_FAILED_NO_SEMAPHORE = 6,
99+
DEACTIVATED_INIT_FAILED = 7,
100+
// DEACTIVATED_BAD_POSITION = 8, unused, but historical
101+
DEACTIVATED_BAD_POSITION_TIMEOUT = 9,
102+
DEACTIVATED_PATH_FULL_TIMEOUT = 10,
103+
DEACTIVATED_PROGRAM_ERROR = 11,
104104
};
105105

106106
// enum for SRTL_OPTIONS parameter
@@ -171,13 +171,13 @@ class AP_SmartRTL {
171171
static dist_point segment_segment_dist(const Vector3f& p1, const Vector3f& p2, const Vector3f& p3, const Vector3f& p4);
172172

173173
// de-activate SmartRTL, send warning to GCS and logger
174-
void deactivate(SRTL_Actions action, const char *reason);
174+
void deactivate(Actions action, const char *reason);
175175

176176
#if HAL_LOGGING_ENABLED
177177
// logging
178-
void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const;
178+
void log_action(Actions action, const Vector3f &point = Vector3f()) const;
179179
#else
180-
void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const {}
180+
void log_action(Actions action, const Vector3f &point = Vector3f()) const {}
181181
#endif
182182

183183
// parameters

0 commit comments

Comments
 (0)