Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

move AC_Avoidance defines into libraries #26466

Merged
merged 15 commits into from
Mar 11, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
Rover: move AC_Avoidance defines into libraries
  • Loading branch information
peterbarker committed Mar 10, 2024
commit a0f2ef58858c853236b3f4c2e1dd64b5a4f0fac1
4 changes: 4 additions & 0 deletions Rover/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,9 @@ bool AP_Arming_Rover::pre_arm_checks(bool report)

return (AP_Arming::pre_arm_checks(report)
& motor_checks(report)
#if AP_OAPATHPLANNER_ENABLED
& oa_check(report)
#endif
& parameter_checks(report)
& mode_checks(report));
}
Expand Down Expand Up @@ -157,6 +159,7 @@ bool AP_Arming_Rover::disarm(const AP_Arming::Method method, bool do_disarm_chec
return true;
}

#if AP_OAPATHPLANNER_ENABLED
// check object avoidance has initialised correctly
bool AP_Arming_Rover::oa_check(bool report)
{
Expand All @@ -173,6 +176,7 @@ bool AP_Arming_Rover::oa_check(bool report)
}
return false;
}
#endif // AP_OAPATHPLANNER_ENABLED

// perform parameter checks
bool AP_Arming_Rover::parameter_checks(bool report)
Expand Down
3 changes: 3 additions & 0 deletions Rover/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <AP_RPM/AP_RPM_config.h>
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
#include <AP_EFI/AP_EFI_config.h>
#include <AC_Avoidance/AP_OADatabase.h>

MAV_TYPE GCS_Rover::frame_type() const
{
Expand Down Expand Up @@ -380,6 +381,7 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
rover.g2.windvane.send_wind(chan);
break;

#if AP_OADATABASE_ENABLED
case MSG_ADSB_VEHICLE: {
AP_OADatabase *oadb = AP::oadatabase();
if (oadb != nullptr) {
Expand All @@ -391,6 +393,7 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
}
break;
}
#endif

default:
return GCS_MAVLINK::try_send_message(id);
Expand Down
2 changes: 2 additions & 0 deletions Rover/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -608,9 +608,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: sailboat.cpp
AP_SUBGROUPINFO(sailboat, "SAIL_", 44, ParametersG2, Sailboat),

#if AP_OAPATHPLANNER_ENABLED
// @Group: OA_
// @Path: ../libraries/AC_Avoidance/AP_OAPathPlanner.cpp
AP_SUBGROUPINFO(oa, "OA_", 45, ParametersG2, AP_OAPathPlanner),
#endif

// @Param: SPEED_MAX
// @DisplayName: Speed maximum
Expand Down
2 changes: 2 additions & 0 deletions Rover/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -397,8 +397,10 @@ class ParametersG2 {
// Sailboat functions
Sailboat sailboat;

#if AP_OAPATHPLANNER_ENABLED
// object avoidance path planning
AP_OAPathPlanner oa;
#endif

// maximum speed for vehicle
AP_Float speed_max;
Expand Down
2 changes: 2 additions & 0 deletions Rover/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,8 +116,10 @@ void Rover::init_ardupilot()
// initialize SmartRTL
g2.smart_rtl.init();

#if AP_OAPATHPLANNER_ENABLED
// initialise object avoidance
g2.oa.init();
#endif

startup_ground();

Expand Down