@@ -117,7 +117,7 @@ void AP_SmartRTL::init()
117
117
118
118
// check if memory allocation failed
119
119
if (_path == nullptr || _prune.loops == nullptr || _simplify.stack == nullptr ) {
120
- log_action (SRTL_DEACTIVATED_INIT_FAILED );
120
+ log_action (Action::DEACTIVATED_INIT_FAILED );
121
121
GCS_SEND_TEXT (MAV_SEVERITY_WARNING, " SmartRTL deactivated: init failed" );
122
122
free (_path);
123
123
free (_prune.loops );
@@ -150,7 +150,7 @@ bool AP_SmartRTL::pop_point(Vector3f& point)
150
150
151
151
// get semaphore
152
152
if (!_path_sem.take_nonblocking ()) {
153
- log_action (SRTL_POP_FAILED_NO_SEMAPHORE );
153
+ log_action (Action::POP_FAILED_NO_SEMAPHORE );
154
154
return false ;
155
155
}
156
156
@@ -180,7 +180,7 @@ bool AP_SmartRTL::peek_point(Vector3f& point)
180
180
181
181
// get semaphore
182
182
if (!_path_sem.take_nonblocking ()) {
183
- log_action (SRTL_PEEK_FAILED_NO_SEMAPHORE );
183
+ log_action (Action::PEEK_FAILED_NO_SEMAPHORE );
184
184
return false ;
185
185
}
186
186
@@ -268,12 +268,12 @@ void AP_SmartRTL::update(bool position_ok, const Vector3f& current_pos)
268
268
_last_position_save_ms = now;
269
269
} else if (AP_HAL::millis () - _last_position_save_ms > SMARTRTL_TIMEOUT) {
270
270
// 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" );
272
272
}
273
273
} else {
274
274
// check for timeout due to bad position
275
275
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" );
277
277
return ;
278
278
}
279
279
}
@@ -322,7 +322,7 @@ bool AP_SmartRTL::add_point(const Vector3f& point)
322
322
{
323
323
// get semaphore
324
324
if (!_path_sem.take_nonblocking ()) {
325
- log_action (SRTL_ADD_FAILED_NO_SEMAPHORE , point);
325
+ log_action (Action::ADD_FAILED_NO_SEMAPHORE , point);
326
326
return false ;
327
327
}
328
328
@@ -338,13 +338,13 @@ bool AP_SmartRTL::add_point(const Vector3f& point)
338
338
// check we have space in the path
339
339
if (_path_points_count >= _path_points_max) {
340
340
_path_sem.give ();
341
- log_action (SRTL_ADD_FAILED_PATH_FULL , point);
341
+ log_action (Action::ADD_FAILED_PATH_FULL , point);
342
342
return false ;
343
343
}
344
344
345
345
// add point to path
346
346
_path[_path_points_count++] = point;
347
- log_action (SRTL_POINT_ADD , point);
347
+ log_action (Action::POINT_ADD , point);
348
348
349
349
_path_sem.give ();
350
350
return true ;
@@ -672,7 +672,7 @@ void AP_SmartRTL::remove_points_by_simplify_bitmask()
672
672
uint16_t removed = 0 ;
673
673
for (uint16_t src = 1 ; src < _path_points_count; src++) {
674
674
if (!_simplify.bitmask .get (src)) {
675
- log_action (SRTL_POINT_SIMPLIFY , _path[src]);
675
+ log_action (Action::POINT_SIMPLIFY , _path[src]);
676
676
removed++;
677
677
} else {
678
678
_path[dest] = _path[src];
@@ -687,7 +687,7 @@ void AP_SmartRTL::remove_points_by_simplify_bitmask()
687
687
_simplify.path_points_completed = _simplify.path_points_count ;
688
688
} else {
689
689
// 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" );
691
691
}
692
692
693
693
_path_sem.give ();
@@ -724,7 +724,7 @@ bool AP_SmartRTL::remove_points_by_loops(uint16_t num_points_to_remove)
724
724
// shift points after the end of the loop down by the number of points in the loop
725
725
uint16_t loop_num_points_to_remove = loop.end_index - loop.start_index ;
726
726
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]);
728
728
_path[dest] = _path[dest + loop_num_points_to_remove];
729
729
}
730
730
@@ -733,7 +733,7 @@ bool AP_SmartRTL::remove_points_by_loops(uint16_t num_points_to_remove)
733
733
removed_points += loop_num_points_to_remove;
734
734
} else {
735
735
// 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" );
737
737
_path_sem.give ();
738
738
// we return true so thorough_cleanup does not get stuck
739
739
return true ;
@@ -862,7 +862,7 @@ AP_SmartRTL::dist_point AP_SmartRTL::segment_segment_dist(const Vector3f &p1, co
862
862
}
863
863
864
864
// 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)
866
866
{
867
867
_active = false ;
868
868
log_action (action);
@@ -871,7 +871,7 @@ void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason)
871
871
872
872
#if HAL_LOGGING_ENABLED
873
873
// 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
875
875
{
876
876
if (!_example_mode) {
877
877
AP::logger ().Write_SRTL (_active, _path_points_count, _path_points_max, action, point);
0 commit comments