Rover: configuration of Precision Landing for custom build server

This commit is contained in:
tzarjakob 2023-03-22 09:45:41 +01:00 committed by Peter Barker
parent dc037b9825
commit caee9f271a
7 changed files with 10 additions and 15 deletions

View File

@ -1063,7 +1063,7 @@ void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg)
*/
void GCS_MAVLINK_Rover::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
{
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
rover.precland.handle_msg(packet, timestamp_ms);
#endif
}

View File

@ -297,7 +297,7 @@ const AP_Param::Info Rover::var_info[] = {
GOBJECT(camera, "CAM", AP_Camera),
#endif
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
// @Group: PLND_
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
GOBJECT(precland, "PLND_", AC_PrecLand),

View File

@ -98,7 +98,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
#if AP_GRIPPER_ENABLED
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69),
#endif
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
SCHED_TASK(update_precland, 400, 50, 70),
#endif
#if AP_RPM_ENABLED

View File

@ -42,6 +42,7 @@
#include <AP_Mission/AP_Mission_ChangeDetector.h>
#include <AR_WPNav/AR_WPNav_OA.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AC_PrecLand/AC_PrecLand_config.h>
// Configuration
#include "defines.h"
@ -61,10 +62,10 @@
#include "GCS_Mavlink.h"
#include "GCS_Rover.h"
#include "AP_Rally.h"
#include "RC_Channel.h" // RC Channel Library
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
#include <AC_PrecLand/AC_PrecLand.h>
#endif
#include "RC_Channel.h" // RC Channel Library
#include "mode.h"
@ -145,7 +146,7 @@ private:
#if OSD_ENABLED || OSD_PARAM_ENABLED
AP_OSD osd;
#endif
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
AC_PrecLand precland;
#endif
// GCS handling

View File

@ -38,12 +38,6 @@
#define AP_RALLY ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Precision Landing with companion computer or IRLock sensor
#ifndef PRECISION_LANDING
# define PRECISION_LANDING ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// NAVL1
//
@ -70,7 +64,7 @@
//////////////////////////////////////////////////////////////////////////////
// Dock mode - allows vehicle to dock to a docking target
#ifndef MODE_DOCK_ENABLED
# define MODE_DOCK_ENABLED PRECISION_LANDING
# define MODE_DOCK_ENABLED AC_PRECLAND_ENABLED
#endif

View File

@ -4,7 +4,7 @@
#include "Rover.h"
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
void Rover::init_precland()
{

View File

@ -117,7 +117,7 @@ void Rover::init_ardupilot()
camera.init();
#endif
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
// initialise precision landing
init_precland();
#endif