ardupilot/Rover/config.h

108 lines
2.3 KiB
C
Raw Normal View History

#pragma once
#include "defines.h"
#ifndef MAV_SYSTEM_ID
#define MAV_SYSTEM_ID 1
#endif
2017-11-30 21:54:45 -04:00
#ifndef ARM_DELAY_MS
#define ARM_DELAY_MS 2000
#endif
//////////////////////////////////////////////////////////////////////////////
// FrSky telemetry support
//
#ifndef FRSKY_TELEM_ENABLED
#define FRSKY_TELEM_ENABLED ENABLED
#endif
#ifndef CH7_OPTION
#define CH7_OPTION CH7_SAVE_WP
#endif
//////////////////////////////////////////////////////////////////////////////
// MODE
// MODE_CHANNEL
//
#ifndef MODE_CHANNEL
#define MODE_CHANNEL 8
#endif
#if (MODE_CHANNEL != 5) && (MODE_CHANNEL != 6) && (MODE_CHANNEL != 7) && (MODE_CHANNEL != 8)
#error XXX
#error XXX You must set MODE_CHANNEL to 5, 6, 7 or 8
#error XXX
#endif
//////////////////////////////////////////////////////////////////////////////
// CAMERA control
//
#ifndef CAMERA
#define CAMERA ENABLED
#endif
2019-02-07 19:45:23 -04:00
//////////////////////////////////////////////////////////////////////////////
// GRIPPER control
//
#ifndef GRIPPER_ENABLED
# define GRIPPER_ENABLED ENABLED
#endif
2018-08-29 21:34:39 -03:00
//////////////////////////////////////////////////////////////////////////////
// RALLY POINTS
//
2018-08-29 22:00:56 -03:00
#ifndef AP_RALLY
#define AP_RALLY ENABLED
2018-08-29 21:34:39 -03:00
#endif
//////////////////////////////////////////////////////////////////////////////
// NAVL1
//
#ifndef NAVL1
#define NAVL1_PERIOD 8
#endif
//////////////////////////////////////////////////////////////////////////////
// CRUISE_SPEED default
//
#ifndef CRUISE_SPEED
#define CRUISE_SPEED 2 // in m/s
#endif
//////////////////////////////////////////////////////////////////////////////
2019-02-11 04:10:43 -04:00
// Logging control
//
#ifndef LOGGING_ENABLED
#define LOGGING_ENABLED ENABLED
#endif
#define DEFAULT_LOG_BITMASK 0xffff
//////////////////////////////////////////////////////////////////////////////
// Developer Items
//
// if RESET_SWITCH_CH is not zero, then this is the PWM value on
// that channel where we reset the control mode to the current switch
// position (to for example return to switched mode after failsafe or
// fence breach)
#ifndef RESET_SWITCH_CHAN_PWM
#define RESET_SWITCH_CHAN_PWM 1750
#endif
2017-01-30 10:21:55 -04:00
#ifndef ADVANCED_FAILSAFE
#define ADVANCED_FAILSAFE DISABLED
#endif
2018-02-28 08:23:09 -04:00
#ifndef STATS_ENABLED
# define STATS_ENABLED ENABLED
#endif
#ifndef OSD_ENABLED
#define OSD_ENABLED DISABLED
#endif