mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: configuration of Precision Landing for custom build server
This commit is contained in:
parent
dc037b9825
commit
caee9f271a
@ -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)
|
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);
|
rover.precland.handle_msg(packet, timestamp_ms);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -297,7 +297,7 @@ const AP_Param::Info Rover::var_info[] = {
|
|||||||
GOBJECT(camera, "CAM", AP_Camera),
|
GOBJECT(camera, "CAM", AP_Camera),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if AC_PRECLAND_ENABLED
|
||||||
// @Group: PLND_
|
// @Group: PLND_
|
||||||
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
|
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
|
||||||
GOBJECT(precland, "PLND_", AC_PrecLand),
|
GOBJECT(precland, "PLND_", AC_PrecLand),
|
||||||
|
@ -98,7 +98,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||||||
#if AP_GRIPPER_ENABLED
|
#if AP_GRIPPER_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69),
|
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69),
|
||||||
#endif
|
#endif
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if AC_PRECLAND_ENABLED
|
||||||
SCHED_TASK(update_precland, 400, 50, 70),
|
SCHED_TASK(update_precland, 400, 50, 70),
|
||||||
#endif
|
#endif
|
||||||
#if AP_RPM_ENABLED
|
#if AP_RPM_ENABLED
|
||||||
|
@ -42,6 +42,7 @@
|
|||||||
#include <AP_Mission/AP_Mission_ChangeDetector.h>
|
#include <AP_Mission/AP_Mission_ChangeDetector.h>
|
||||||
#include <AR_WPNav/AR_WPNav_OA.h>
|
#include <AR_WPNav/AR_WPNav_OA.h>
|
||||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||||
|
#include <AC_PrecLand/AC_PrecLand_config.h>
|
||||||
|
|
||||||
// Configuration
|
// Configuration
|
||||||
#include "defines.h"
|
#include "defines.h"
|
||||||
@ -61,10 +62,10 @@
|
|||||||
#include "GCS_Mavlink.h"
|
#include "GCS_Mavlink.h"
|
||||||
#include "GCS_Rover.h"
|
#include "GCS_Rover.h"
|
||||||
#include "AP_Rally.h"
|
#include "AP_Rally.h"
|
||||||
#include "RC_Channel.h" // RC Channel Library
|
#if AC_PRECLAND_ENABLED
|
||||||
#if PRECISION_LANDING == ENABLED
|
|
||||||
#include <AC_PrecLand/AC_PrecLand.h>
|
#include <AC_PrecLand/AC_PrecLand.h>
|
||||||
#endif
|
#endif
|
||||||
|
#include "RC_Channel.h" // RC Channel Library
|
||||||
|
|
||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
|
|
||||||
@ -145,7 +146,7 @@ private:
|
|||||||
#if OSD_ENABLED || OSD_PARAM_ENABLED
|
#if OSD_ENABLED || OSD_PARAM_ENABLED
|
||||||
AP_OSD osd;
|
AP_OSD osd;
|
||||||
#endif
|
#endif
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if AC_PRECLAND_ENABLED
|
||||||
AC_PrecLand precland;
|
AC_PrecLand precland;
|
||||||
#endif
|
#endif
|
||||||
// GCS handling
|
// GCS handling
|
||||||
|
@ -38,12 +38,6 @@
|
|||||||
#define AP_RALLY ENABLED
|
#define AP_RALLY ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// Precision Landing with companion computer or IRLock sensor
|
|
||||||
#ifndef PRECISION_LANDING
|
|
||||||
# define PRECISION_LANDING ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// NAVL1
|
// NAVL1
|
||||||
//
|
//
|
||||||
@ -70,7 +64,7 @@
|
|||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Dock mode - allows vehicle to dock to a docking target
|
// Dock mode - allows vehicle to dock to a docking target
|
||||||
#ifndef MODE_DOCK_ENABLED
|
#ifndef MODE_DOCK_ENABLED
|
||||||
# define MODE_DOCK_ENABLED PRECISION_LANDING
|
# define MODE_DOCK_ENABLED AC_PRECLAND_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
@ -4,7 +4,7 @@
|
|||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if AC_PRECLAND_ENABLED
|
||||||
|
|
||||||
void Rover::init_precland()
|
void Rover::init_precland()
|
||||||
{
|
{
|
||||||
|
@ -117,7 +117,7 @@ void Rover::init_ardupilot()
|
|||||||
camera.init();
|
camera.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if AC_PRECLAND_ENABLED
|
||||||
// initialise precision landing
|
// initialise precision landing
|
||||||
init_precland();
|
init_precland();
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user