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

Copter: fix options to disable MOUNT/ADSB #16536

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
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
2 changes: 1 addition & 1 deletion ArduCopter/APM_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)
//#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
//#define MOUNT_ENABLED DISABLED // disable the camera gimbal to save 8K of flash space
//#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash
//#define AC_FENCE DISABLED // disable fence to save 2k of flash
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -276,7 +276,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
#endif

// check adsb avoidance failsafe
#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
if (copter.failsafe.adsb) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "ADSB threat detected");
return false;
Expand Down Expand Up @@ -690,7 +690,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
}

// check adsb
#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS)) {
if (copter.failsafe.adsb) {
check_failed(ARMING_CHECK_PARAMETERS, true, "ADSB threat detected");
Expand Down
8 changes: 4 additions & 4 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(lost_vehicle_check, 10, 50),
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_receive, 400, 180),
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_send, 400, 550),
#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75),
#endif
#if CAMERA == ENABLED
Expand All @@ -166,7 +166,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(compass_cal_update, 100, 100),
SCHED_TASK(accel_cal_update, 10, 100),
SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100),
#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
SCHED_TASK(avoidance_adsb_update, 10, 100),
#endif
#if ADVANCED_FAILSAFE == ENABLED
Expand Down Expand Up @@ -254,7 +254,7 @@ void Copter::fast_loop()
// check if we've landed or crashed
update_land_and_crash_detectors();

#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
// camera mount's fast update
camera_mount.update_fast();
#endif
Expand Down Expand Up @@ -507,7 +507,7 @@ void Copter::one_hz_loop()
// log terrain data
terrain_logging();

#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
adsb.set_is_flying(!ap.land_complete);
#endif

Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@
#include "UserParameters.h"
#endif
#include "Parameters.h"
#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
#include "avoidance_adsb.h"
#endif

Expand Down Expand Up @@ -485,7 +485,7 @@ class Copter : public AP_Vehicle {
#endif

// Camera/Antenna mount tracking and stabilisation stuff
#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
AP_Mount camera_mount;
#endif

Expand Down Expand Up @@ -532,7 +532,7 @@ class Copter : public AP_Vehicle {
AC_InputManager_Heli input_manager;
#endif

#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
AP_ADSB adsb;

// avoidance of adsb enabled vehicles (normally manned vehicles)
Expand Down Expand Up @@ -664,7 +664,7 @@ class Copter : public AP_Vehicle {
void rotate_body_frame_to_NE(float &x, float &y);
uint16_t get_pilot_speed_dn() const;

#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
// avoidance_adsb.cpp
void avoidance_adsb_update(void);
#endif
Expand Down Expand Up @@ -945,7 +945,7 @@ class Copter : public AP_Vehicle {
#if MODE_SYSTEMID_ENABLED == ENABLED
ModeSystemId mode_systemid;
#endif
#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
ModeAvoidADSB mode_avoid_adsb;
#endif
#if MODE_THROW_ENABLED == ENABLED
Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -297,7 +297,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
break;

case MSG_ADSB_VEHICLE: {
#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
copter.adsb.send_adsb_vehicle(chan);
#endif
Expand Down Expand Up @@ -520,7 +520,7 @@ void GCS_MAVLINK_Copter::handle_change_alt_request(AP_Mission::Mission_Command &
void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status,
const mavlink_message_t &msg)
{
#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
if (copter.g2.dev_options.get() & DevOptionADSBMAVLink) {
// optional handling of GLOBAL_POSITION_INT as a MAVLink based avoidance source
copter.avoidance_adsb.handle_msg(msg);
Expand Down Expand Up @@ -676,7 +676,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t
{
// if the mount doesn't do pan control then yaw the entire vehicle instead:
switch (packet.command) {
#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
case MAV_CMD_DO_MOUNT_CONTROL:
if (!copter.camera_mount.has_pan_control()) {
copter.flightmode->auto_yaw.set_fixed_yaw(
Expand Down Expand Up @@ -942,7 +942,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
{
switch (msg.msgid) {
#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
case MAVLINK_MSG_ID_MOUNT_CONTROL:
if (!copter.camera_mount.has_pan_control()) {
// if the mount doesn't do pan control then yaw the entire vehicle instead:
Expand Down Expand Up @@ -1317,7 +1317,7 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG:
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC:
case MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT:
#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
copter.adsb.handle_message(chan, msg);
#endif
break;
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -588,7 +588,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT(ahrs, "AHRS_", AP_AHRS),

#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
// @Group: MNT
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
GOBJECT(camera_mount, "MNT", AP_Mount),
Expand Down Expand Up @@ -719,7 +719,7 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECT(rpm_sensor, "RPM", AP_RPM),
#endif

#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
// @Group: ADSB_
// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
GOBJECT(adsb, "ADSB_", AP_ADSB),
Expand Down
8 changes: 4 additions & 4 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,14 +140,14 @@ void Mode::AutoYaw::set_roi(const Location &roi_location)
if (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0) {
// set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
auto_yaw.set_mode_to_default(false);
#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
// switch off the camera tracking if enabled
if (copter.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
copter.camera_mount.set_mode_to_default();
}
#endif // HAL_MOUNT_ENABLED
#endif // MOUNT_ENABLED
} else {
#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
// check if mount type requires us to rotate the quad
if (!copter.camera_mount.has_pan_control()) {
if (roi_location.get_vector_from_origin_NEU(roi)) {
Expand All @@ -168,7 +168,7 @@ void Mode::AutoYaw::set_roi(const Location &roi_location)
if (roi_location.get_vector_from_origin_NEU(roi)) {
auto_yaw.set_mode(AUTO_YAW_ROI);
}
#endif // HAL_MOUNT_ENABLED
#endif // MOUNT_ENABLED
}
}

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/avoidance_adsb.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include "Copter.h"
#include <AP_Notify/AP_Notify.h>

#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
void Copter::avoidance_adsb_update(void)
{
adsb.update();
Expand Down
14 changes: 13 additions & 1 deletion ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -377,6 +377,18 @@
# define BUTTON_ENABLED ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
// Mount - camera gimbal
#ifndef MOUNT_ENABLED
# define MOUNT_ENABLED HAL_MOUNT_ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
// ADSB support
#ifndef ADSB_ENABLED
# define ADSB_ENABLED HAL_ADSB_ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION
//////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -714,7 +726,7 @@
#error SmartRTL requires ModeRTL which is disabled
#endif

#if HAL_ADSB_ENABLED && !MODE_GUIDED_ENABLED
#if ADSB_ENABLED && !MODE_GUIDED_ENABLED
#error ADSB requires ModeGuided which is disabled
#endif

Expand Down
8 changes: 4 additions & 4 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ Mode *Copter::mode_from_mode_num(const Mode::Number mode)
break;
#endif

#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
case Mode::Number::AVOID_ADSB:
ret = &mode_avoid_adsb;
break;
Expand Down Expand Up @@ -280,7 +280,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
logger.Write_Mode((uint8_t)control_mode, reason);
gcs().send_message(MSG_HEARTBEAT);

#if HAL_ADSB_ENABLED
#if ADSB_ENABLED
adsb.set_is_auto_mode((mode == Mode::Number::AUTO) || (mode == Mode::Number::RTL) || (mode == Mode::Number::GUIDED));
#endif

Expand Down Expand Up @@ -339,9 +339,9 @@ void Copter::exit_mode(Mode *&old_flightmode,
if (mode_auto.mission.state() == AP_Mission::MISSION_RUNNING) {
mode_auto.mission.stop();
}
#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
camera_mount.set_mode_to_default();
#endif // HAL_MOUNT_ENABLED
#endif // MOUNT_ENABLED
}
#endif

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1446,7 +1446,7 @@ void ModeAuto::do_roi(const AP_Mission::Mission_Command& cmd)
// point the camera to a specified angle
void ModeAuto::do_mount_control(const AP_Mission::Mission_Command& cmd)
{
#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
if (!copter.camera_mount.has_pan_control()) {
auto_yaw.set_fixed_yaw(cmd.content.mount_control.yaw,0.0f,0,0);
}
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ void Copter::init_ardupilot()
// init the optical flow sensor
init_optflow();

#if HAL_MOUNT_ENABLED
#if MOUNT_ENABLED
// initialise camera mount
camera_mount.init();
#endif
Expand Down