APM:Libraries
AP_Mount_SoloGimbal.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include <AP_AHRS/AP_AHRS.h>
3 #if AP_AHRS_NAVEKF_AVAILABLE
4 
5 #include "AP_Mount_SoloGimbal.h"
6 #include "SoloGimbal.h"
7 #include <DataFlash/DataFlash.h>
9 #include <GCS_MAVLink/GCS.h>
10 
11 extern const AP_HAL::HAL& hal;
12 
13 AP_Mount_SoloGimbal::AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
14  AP_Mount_Backend(frontend, state, instance),
15  _initialised(false),
16  _gimbal(frontend._ahrs)
17 {}
18 
19 // init - performs any required initialisation for this instance
21 {
22  _initialised = true;
23  set_mode((enum MAV_MOUNT_MODE)_state._default_mode.get());
24 }
25 
26 void AP_Mount_SoloGimbal::update_fast()
27 {
28  _gimbal.update_fast();
29 }
30 
31 // update mount position - should be called periodically
32 void AP_Mount_SoloGimbal::update()
33 {
34  // exit immediately if not initialised
35  if (!_initialised) {
36  return;
37  }
38 
39  // update based on mount mode
40  switch(get_mode()) {
41  // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism
42  case MAV_MOUNT_MODE_RETRACT:
43  _gimbal.set_lockedToBody(true);
44  break;
45 
46  // move mount to a neutral position, typically pointing forward
47  case MAV_MOUNT_MODE_NEUTRAL:
48  {
49  _gimbal.set_lockedToBody(false);
50  const Vector3f &target = _state._neutral_angles.get();
51  _angle_ef_target_rad.x = ToRad(target.x);
52  _angle_ef_target_rad.y = ToRad(target.y);
53  _angle_ef_target_rad.z = ToRad(target.z);
54  }
55  break;
56 
57  // point to the angles given by a mavlink message
58  case MAV_MOUNT_MODE_MAVLINK_TARGETING:
59  _gimbal.set_lockedToBody(false);
60  // do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS
61  break;
62 
63  // RC radio manual angle control, but with stabilization from the AHRS
64  case MAV_MOUNT_MODE_RC_TARGETING:
65  _gimbal.set_lockedToBody(false);
66  // update targets using pilot's rc inputs
68  break;
69 
70  // point mount to a GPS point given by the mission planner
71  case MAV_MOUNT_MODE_GPS_POINT:
72  _gimbal.set_lockedToBody(false);
73  if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
75  }
76  break;
77 
78  default:
79  // we do not know this mode so do nothing
80  break;
81  }
82 }
83 
84 // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
85 bool AP_Mount_SoloGimbal::has_pan_control() const
86 {
87  // we do not have yaw control
88  return false;
89 }
90 
91 // set_mode - sets mount's mode
92 void AP_Mount_SoloGimbal::set_mode(enum MAV_MOUNT_MODE mode)
93 {
94  // exit immediately if not initialised
95  if (!_initialised) {
96  return;
97  }
98 
99  // record the mode change
100  _state._mode = mode;
101 }
102 
103 // status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
104 void AP_Mount_SoloGimbal::status_msg(mavlink_channel_t chan)
105 {
106  if (_gimbal.aligned()) {
107  mavlink_msg_mount_status_send(chan, 0, 0, degrees(_angle_ef_target_rad.y)*100, degrees(_angle_ef_target_rad.x)*100, degrees(_angle_ef_target_rad.z)*100);
108  }
109 
110  // block heartbeat from transmitting to the GCS
112 }
113 
114 /*
115  handle a GIMBAL_REPORT message
116  */
117 void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
118 {
119  _gimbal.update_target(_angle_ef_target_rad);
120  _gimbal.receive_feedback(chan,msg);
121 
123  if (df == nullptr) {
124  return;
125  }
126 
127  if(!_params_saved && df->logging_started()) {
128  _gimbal.fetch_params(); //last parameter save might not be stored in dataflash so retry
129  _params_saved = true;
130  }
131 
132  if (_gimbal.get_log_dt() > 1.0f/25.0f) {
133  _gimbal.write_logs();
134  }
135 }
136 
137 void AP_Mount_SoloGimbal::handle_param_value(mavlink_message_t *msg)
138 {
139  _gimbal.handle_param_value(msg);
140 }
141 
142 /*
143  handle a GIMBAL_REPORT message
144  */
145 void AP_Mount_SoloGimbal::handle_gimbal_torque_report(mavlink_channel_t chan, mavlink_message_t *msg)
146 {
147  _gimbal.disable_torque_report();
148 }
149 
150 /*
151  send a GIMBAL_REPORT message to the GCS
152  */
153 void AP_Mount_SoloGimbal::send_gimbal_report(mavlink_channel_t chan)
154 {
155 }
156 
157 #endif // AP_AHRS_NAVEKF_AVAILABLE
MAV_MOUNT_MODE _mode
Definition: AP_Mount.h:182
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
Vector3f _angle_ef_target_rad
#define ToRad(x)
Definition: AP_Common.h:53
Interface definition for the various Ground Control System.
bool logging_started(void)
Definition: DataFlash.cpp:548
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
AP_Mount::mount_state & _state
void calc_angle_to_location(const struct Location &target, Vector3f &angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan=true)
T y
Definition: vector3.h:67
struct Location _roi_target
Definition: AP_Mount.h:183
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
static int state
Definition: Util.cpp:20
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
AP_Vector3f _neutral_angles
Definition: AP_Mount.h:177
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void init()
Generic board initialization function.
Definition: system.cpp:136
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
virtual void set_mode(enum MAV_MOUNT_MODE mode)
#define degrees(x)
Definition: moduletest.c:23
MAV_MOUNT_MODE get_mode(void) const
T x
Definition: vector3.h:67