APM:Copter
fence.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // Code to integrate AC_Fence library with main ArduCopter code
4 
5 #if AC_FENCE == ENABLED
6 
7 // fence_check - ask fence library to check for breaches and initiate the response
8 // called at 1hz
10 {
11  // ignore any fence activity when not armed
12  if(!motors->armed()) {
13  return;
14  }
15 
16  const uint8_t orig_breaches = fence.get_breaches();
17 
18  // check for new breaches; new_breaches is bitmask of fence types breached
19  const uint8_t new_breaches = fence.check();
20 
21  // if there is a new breach take action
22  if (new_breaches) {
23 
24  // if the user wants some kind of response and motors are armed
26 
27  // disarm immediately if we think we are on the ground or in a manual flight mode with zero throttle
28  // don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down
29  if (ap.land_complete || (flightmode->has_manual_throttle() && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0))){
31  }else{
32  // if we are within 100m of the fence, RTL
36  }
37  }else{
38  // if more than 100m outside the fence just force a land
40  }
41  }
42  }
43 
44  // log an error in the dataflash
46 
47  } else if (orig_breaches) {
48  // record clearing of breach
50  }
51 }
52 
53 // fence_send_mavlink_status - send fence status to ground station
54 void Copter::fence_send_mavlink_status(mavlink_channel_t chan)
55 {
56  if (fence.enabled()) {
57  // traslate fence library breach types to mavlink breach types
58  uint8_t mavlink_breach_type = FENCE_BREACH_NONE;
59  uint8_t breaches = fence.get_breaches();
60  if ((breaches & AC_FENCE_TYPE_ALT_MAX) != 0) {
61  mavlink_breach_type = FENCE_BREACH_MAXALT;
62  }
63  if ((breaches & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) != 0) {
64  mavlink_breach_type = FENCE_BREACH_BOUNDARY;
65  }
66 
67  // send status
68  mavlink_msg_fence_status_send(chan,
69  (int8_t)(fence.get_breaches()!=0),
71  mavlink_breach_type,
73  }
74 }
75 
76 #endif
AC_Fence fence
Definition: Copter.h:527
#define ERROR_SUBSYSTEM_FAILSAFE_FENCE
Definition: defines.h:401
#define AC_FENCE_ACTION_REPORT_ONLY
#define AC_FENCE_TYPE_CIRCLE
uint8_t get_breaches() const
Definition: defines.h:100
void fence_check()
Definition: fence.cpp:9
uint8_t check()
MOTOR_CLASS * motors
Definition: Copter.h:422
float get_breach_distance(uint8_t fence_type) const
uint16_t get_breach_count() const
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
Definition: Log.cpp:328
Mode * flightmode
Definition: Copter.h:955
uint8_t get_action() const
bool set_mode(control_mode_t mode, mode_reason_t reason)
Definition: mode.cpp:171
void fence_send_mavlink_status(mavlink_channel_t chan)
Definition: fence.cpp:54
struct Copter::@2 failsafe
void init_disarm_motors()
Definition: motors.cpp:241
virtual bool has_manual_throttle() const =0
#define AC_FENCE_TYPE_POLYGON
#define ERROR_CODE_ERROR_RESOLVED
Definition: defines.h:418
#define AC_FENCE_GIVE_UP_DISTANCE
uint32_t get_breach_time() const
bool enabled() const
#define AC_FENCE_TYPE_ALT_MAX
Definition: defines.h:98