SITL: Added comment to clarify IMU acceleration value
[ardupilot.git] / libraries / AP_Mount / AP_Mount_Backend.cpp
blob71a581b288c6bd9f785c87e4f27aa82e421fde9a
1 #include "AP_Mount_config.h"
3 #if HAL_MOUNT_ENABLED
5 #include "AP_Mount_Backend.h"
7 #include <AP_AHRS/AP_AHRS.h>
8 #include <GCS_MAVLink/GCS.h>
9 #include <AP_Logger/AP_Logger.h>
10 #include <AP_Terrain/AP_Terrain.h>
12 extern const AP_HAL::HAL& hal;
14 #define AP_MOUNT_UPDATE_DT 0.02 // update rate in seconds. update() should be called at this rate
15 #define AP_MOUNT_POI_REQUEST_TIMEOUT_MS 30000 // POI calculations continue to be updated for this many seconds after last request
16 #define AP_MOUNT_POI_RESULT_TIMEOUT_MS 3000 // POI calculations valid for 3 seconds
17 #define AP_MOUNT_POI_DIST_M_MAX 10000 // POI calculations limit of 10,000m (10km)
19 // Default init function for every mount
20 void AP_Mount_Backend::init()
22 // setting default target sysid from parameters
23 _target_sysid = _params.sysid_default.get();
25 #if AP_MOUNT_POI_TO_LATLONALT_ENABLED
26 // create a calculation thread for poi.
27 if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Mount_Backend::calculate_poi, void),
28 "mount_calc_poi",
29 8192, AP_HAL::Scheduler::PRIORITY_IO, -1)) {
30 GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mount: failed to start POI thread");
32 #endif
35 // set device id of this instance, for MNTx_DEVID parameter
36 void AP_Mount_Backend::set_dev_id(uint32_t id)
38 _params.dev_id.set_and_save(int32_t(id));
41 // return true if this mount accepts roll targets
42 bool AP_Mount_Backend::has_roll_control() const
44 return (_params.roll_angle_min < _params.roll_angle_max);
47 // return true if this mount accepts pitch targets
48 bool AP_Mount_Backend::has_pitch_control() const
50 return (_params.pitch_angle_min < _params.pitch_angle_max);
53 bool AP_Mount_Backend::valid_mode(MAV_MOUNT_MODE mode) const
55 switch (mode) {
56 case MAV_MOUNT_MODE_RETRACT...MAV_MOUNT_MODE_HOME_LOCATION:
57 return true;
58 case MAV_MOUNT_MODE_ENUM_END:
59 return false;
61 return false;
64 bool AP_Mount_Backend::set_mode(MAV_MOUNT_MODE mode)
66 if (!valid_mode(mode)) {
67 return false;
69 _mode = mode;
70 return true;
73 // called when mount mode is RC-targetting, updates the mnt_target object from RC inputs:
74 void AP_Mount_Backend::update_mnt_target_from_rc_target()
76 if (rc().in_rc_failsafe()) {
77 if (option_set(Options::NEUTRAL_ON_RC_FS)) {
78 mnt_target.angle_rad.set(_params.neutral_angles.get() * DEG_TO_RAD, false);
79 mnt_target.target_type = MountTargetType::ANGLE;
80 return;
84 MountTarget rc_target;
85 get_rc_target(mnt_target.target_type, rc_target);
86 switch (mnt_target.target_type) {
87 case MountTargetType::ANGLE:
88 mnt_target.angle_rad = rc_target;
89 break;
90 case MountTargetType::RATE:
91 mnt_target.rate_rads = rc_target;
92 break;
96 // set angle target in degrees
97 // roll and pitch are in earth-frame
98 // yaw_is_earth_frame (aka yaw_lock) should be true if yaw angle is earth-frame, false if body-frame
99 void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float yaw_deg, bool yaw_is_earth_frame)
101 // enforce angle limits
102 roll_deg = constrain_float(roll_deg, _params.roll_angle_min, _params.roll_angle_max);
103 pitch_deg = constrain_float(pitch_deg, _params.pitch_angle_min, _params.pitch_angle_max);
104 if (!yaw_is_earth_frame) {
105 // only limit yaw if in body-frame. earth-frame yaw limiting is backend specific
106 // custom wrap code (instead of wrap_180) to better handle yaw of <= -180
107 if (yaw_deg > 180) {
108 yaw_deg -= 360;
110 yaw_deg = constrain_float(yaw_deg, _params.yaw_angle_min, _params.yaw_angle_max);
113 // set angle targets
114 mnt_target.target_type = MountTargetType::ANGLE;
115 mnt_target.angle_rad.roll = radians(roll_deg);
116 mnt_target.angle_rad.pitch = radians(pitch_deg);
117 mnt_target.angle_rad.yaw = radians(yaw_deg);
118 mnt_target.angle_rad.yaw_is_ef = yaw_is_earth_frame;
120 // set the mode to mavlink targeting
121 set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING);
123 // optionally set RC_TARGETING yaw lock state
124 if (option_set(Options::RCTARGETING_LOCK_FROM_PREVMODE)) {
125 set_yaw_lock(yaw_is_earth_frame);
129 // sets rate target in deg/s
130 // yaw_lock should be true if the yaw rate is earth-frame, false if body-frame (e.g. rotates with body of vehicle)
131 void AP_Mount_Backend::set_rate_target(float roll_degs, float pitch_degs, float yaw_degs, bool yaw_is_earth_frame)
133 // set rate targets
134 mnt_target.target_type = MountTargetType::RATE;
135 mnt_target.rate_rads.roll = radians(roll_degs);
136 mnt_target.rate_rads.pitch = radians(pitch_degs);
137 mnt_target.rate_rads.yaw = radians(yaw_degs);
138 mnt_target.rate_rads.yaw_is_ef = yaw_is_earth_frame;
140 // set the mode to mavlink targeting
141 set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING);
143 // optionally set RC_TARGETING yaw lock state
144 if (option_set(Options::RCTARGETING_LOCK_FROM_PREVMODE)) {
145 set_yaw_lock(yaw_is_earth_frame);
149 // set_roi_target - sets target location that mount should attempt to point towards
150 void AP_Mount_Backend::set_roi_target(const Location &target_loc)
152 // set the target gps location
153 _roi_target = target_loc;
154 _roi_target_set = true;
156 // set the mode to GPS tracking mode
157 set_mode(MAV_MOUNT_MODE_GPS_POINT);
159 // optionally set RC_TARGETING yaw lock state
160 if (option_set(Options::RCTARGETING_LOCK_FROM_PREVMODE)) {
161 set_yaw_lock(true);
165 // clear_roi_target - clears target location that mount should attempt to point towards
166 void AP_Mount_Backend::clear_roi_target()
168 // clear the target GPS location
169 _roi_target_set = false;
171 // reset the mode if in GPS tracking mode
172 if (get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
173 MAV_MOUNT_MODE default_mode = (MAV_MOUNT_MODE)_params.default_mode.get();
174 set_mode(default_mode);
178 // set_sys_target - sets system that mount should attempt to point towards
179 void AP_Mount_Backend::set_target_sysid(uint8_t sysid)
181 _target_sysid = sysid;
183 // set the mode to sysid tracking mode
184 set_mode(MAV_MOUNT_MODE_SYSID_TARGET);
186 // optionally set RC_TARGETING yaw lock state
187 if (option_set(Options::RCTARGETING_LOCK_FROM_PREVMODE)) {
188 set_yaw_lock(true);
192 #if HAL_GCS_ENABLED
193 // send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
194 void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan)
196 if (suppress_heartbeat()) {
197 // block heartbeat from transmitting to the GCS
198 GCS_MAVLINK::disable_channel_routing(chan);
201 Quaternion att_quat;
202 if (!get_attitude_quaternion(att_quat)) {
203 return;
205 Vector3f ang_velocity { nanf(""), nanf(""), nanf("") };
206 IGNORE_RETURN(get_angular_velocity(ang_velocity));
208 // construct quaternion array
209 const float quat_array[4] = {att_quat.q1, att_quat.q2, att_quat.q3, att_quat.q4};
211 mavlink_msg_gimbal_device_attitude_status_send(chan,
212 0, // target system
213 0, // target component
214 AP_HAL::millis(), // autopilot system time
215 get_gimbal_device_flags(),
216 quat_array, // attitude expressed as quaternion
217 ang_velocity.x, // roll axis angular velocity (NaN for unknown)
218 ang_velocity.y, // pitch axis angular velocity (NaN for unknown)
219 ang_velocity.z, // yaw axis angular velocity (NaN for unknown)
220 0, // failure flags (not supported)
221 std::numeric_limits<double>::quiet_NaN(), // delta_yaw (NaN for unknonw)
222 std::numeric_limits<double>::quiet_NaN(), // delta_yaw_velocity (NaN for unknonw)
223 _instance + 1); // gimbal_device_id
225 #endif
227 // return gimbal manager capability flags used by GIMBAL_MANAGER_INFORMATION message
228 uint32_t AP_Mount_Backend::get_gimbal_manager_capability_flags() const
230 uint32_t cap_flags = GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT |
231 GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL |
232 GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS |
233 GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL |
234 GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL;
236 // roll control
237 if (has_roll_control()) {
238 cap_flags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS |
239 GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW |
240 GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK;
243 // pitch control
244 if (has_pitch_control()) {
245 cap_flags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS |
246 GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW |
247 GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK;
250 // yaw control
251 if (has_pan_control()) {
252 cap_flags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS |
253 GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW |
254 GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK;
257 return cap_flags;
260 // send a GIMBAL_MANAGER_INFORMATION message to GCS
261 void AP_Mount_Backend::send_gimbal_manager_information(mavlink_channel_t chan)
263 mavlink_msg_gimbal_manager_information_send(chan,
264 AP_HAL::millis(), // autopilot system time
265 get_gimbal_manager_capability_flags(), // bitmap of gimbal manager capability flags
266 _instance + 1, // gimbal device id
267 radians(_params.roll_angle_min), // roll_min in radians
268 radians(_params.roll_angle_max), // roll_max in radians
269 radians(_params.pitch_angle_min), // pitch_min in radians
270 radians(_params.pitch_angle_max), // pitch_max in radians
271 radians(_params.yaw_angle_min), // yaw_min in radians
272 radians(_params.yaw_angle_max)); // yaw_max in radians
275 // send a GIMBAL_MANAGER_STATUS message to GCS
276 void AP_Mount_Backend::send_gimbal_manager_status(mavlink_channel_t chan)
278 uint32_t flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK | GIMBAL_MANAGER_FLAGS_PITCH_LOCK;
280 if (_yaw_lock) {
281 flags |= GIMBAL_MANAGER_FLAGS_YAW_LOCK;
284 mavlink_msg_gimbal_manager_status_send(chan,
285 AP_HAL::millis(), // autopilot system time
286 flags, // bitmap of gimbal manager flags
287 _instance + 1, // gimbal device id
288 mavlink_control_id.sysid, // primary control system id
289 mavlink_control_id.compid, // primary control component id
290 0, // secondary control system id
291 0); // secondary control component id
294 // handle do_mount_control command. Returns MAV_RESULT_ACCEPTED on success
295 MAV_RESULT AP_Mount_Backend::handle_command_do_mount_control(const mavlink_command_int_t &packet)
297 const MAV_MOUNT_MODE new_mode = (MAV_MOUNT_MODE)packet.z;
299 // interpret message fields based on mode
300 switch (new_mode) {
301 case MAV_MOUNT_MODE_RETRACT:
302 case MAV_MOUNT_MODE_NEUTRAL:
303 case MAV_MOUNT_MODE_RC_TARGETING:
304 case MAV_MOUNT_MODE_HOME_LOCATION:
305 // simply set mode
306 set_mode(new_mode);
307 return MAV_RESULT_ACCEPTED;
309 case MAV_MOUNT_MODE_MAVLINK_TARGETING: {
310 // set target angles (in degrees) from mavlink message
311 const float pitch_deg = packet.param1; // param1: pitch (earth-frame, degrees)
312 const float roll_deg = packet.param2; // param2: roll (earth-frame, degrees)
313 const float yaw_deg = packet.param3; // param3: yaw (body-frame, degrees)
315 // warn if angles are invalid to catch angles sent in centi-degrees
316 if ((fabsf(pitch_deg) > 90) || (fabsf(roll_deg) > 180) || (fabsf(yaw_deg) > 360)) {
317 send_warning_to_GCS("invalid angle targets");
318 return MAV_RESULT_FAILED;
321 set_angle_target(packet.param2, packet.param1, packet.param3, false);
322 return MAV_RESULT_ACCEPTED;
325 case MAV_MOUNT_MODE_GPS_POINT: {
326 // set lat, lon, alt position targets from mavlink message
328 // warn if lat, lon appear to be in param1,2 instead of param x,y as this indicates
329 // sender is relying on a bug in AP-4.2's (and earlier) handling of MAV_CMD_DO_MOUNT_CONTROL
330 if (!is_zero(packet.param1) && !is_zero(packet.param2) && packet.x == 0 && packet.y == 0) {
331 send_warning_to_GCS("GPS_POINT target invalid");
332 return MAV_RESULT_FAILED;
335 // param4: altitude in meters
336 // x: latitude in degrees * 1E7
337 // y: longitude in degrees * 1E7
338 const Location target_location {
339 packet.x, // latitude in degrees * 1E7
340 packet.y, // longitude in degrees * 1E7
341 (int32_t)packet.param4 * 100, // alt converted from meters to cm
342 Location::AltFrame::ABOVE_HOME
344 set_roi_target(target_location);
345 return MAV_RESULT_ACCEPTED;
348 default:
349 // invalid mode
350 return MAV_RESULT_FAILED;
354 // handle do_gimbal_manager_configure. Returns MAV_RESULT_ACCEPTED on success
355 // requires original message in order to extract caller's sysid and compid
356 MAV_RESULT AP_Mount_Backend::handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
358 // sanity check param1 and param2 values
359 if ((packet.param1 < -3) || (packet.param1 > UINT8_MAX) || (packet.param2 < -3) || (packet.param2 > UINT8_MAX)) {
360 return MAV_RESULT_FAILED;
363 // backup the current values so we can detect a change
364 mavlink_control_id_t prev_control_id = mavlink_control_id;
366 // convert negative packet1 and packet2 values
367 int16_t new_sysid = packet.param1;
368 switch (new_sysid) {
369 case -1:
370 // leave unchanged
371 break;
372 case -2:
373 // set itself in control
374 mavlink_control_id.sysid = msg.sysid;
375 mavlink_control_id.compid = msg.compid;
376 break;
377 case -3:
378 // remove control if currently in control
379 if ((mavlink_control_id.sysid == msg.sysid) && (mavlink_control_id.compid == msg.compid)) {
380 mavlink_control_id.sysid = 0;
381 mavlink_control_id.compid = 0;
383 break;
384 default:
385 mavlink_control_id.sysid = packet.param1;
386 mavlink_control_id.compid = packet.param2;
387 break;
390 // send gimbal_manager_status if control has changed
391 if (prev_control_id != mavlink_control_id) {
392 GCS_SEND_MESSAGE(MSG_GIMBAL_MANAGER_STATUS);
395 return MAV_RESULT_ACCEPTED;
398 // handle a GLOBAL_POSITION_INT message
399 bool AP_Mount_Backend::handle_global_position_int(uint8_t msg_sysid, const mavlink_global_position_int_t &packet)
401 if (_target_sysid != msg_sysid) {
402 return false;
405 _target_sysid_location.lat = packet.lat;
406 _target_sysid_location.lng = packet.lon;
407 // global_position_int.alt is *UP*, so is location.
408 _target_sysid_location.set_alt_cm(packet.alt*0.1, Location::AltFrame::ABSOLUTE);
409 _target_sysid_location_set = true;
411 return true;
414 #if HAL_LOGGING_ENABLED
415 // write mount log packet
416 void AP_Mount_Backend::write_log(uint64_t timestamp_us)
418 // return immediately if no yaw estimate
419 float ahrs_yaw = AP::ahrs().get_yaw();
420 if (isnan(ahrs_yaw)) {
421 return;
424 const auto nanf = AP::logger().quiet_nanf();
426 // get_attitude_quaternion and convert to Euler angles
427 float roll = nanf;
428 float pitch = nanf;
429 float yaw_bf = nanf;
430 float yaw_ef = nanf;
431 if (_frontend.get_attitude_euler(_instance, roll, pitch, yaw_bf)) {
432 yaw_ef = wrap_180(yaw_bf + degrees(ahrs_yaw));
435 // get mount's target (desired) angles and convert yaw to earth frame
436 float target_roll = nanf;
437 float target_pitch = nanf;
438 float target_yaw = nanf;
439 bool target_yaw_is_ef = false;
440 IGNORE_RETURN(get_angle_target(target_roll, target_pitch, target_yaw, target_yaw_is_ef));
442 // get rangefinder distance
443 float rangefinder_dist = nanf;
444 IGNORE_RETURN(get_rangefinder_distance(rangefinder_dist));
446 const struct log_Mount pkt {
447 LOG_PACKET_HEADER_INIT(static_cast<uint8_t>(LOG_MOUNT_MSG)),
448 time_us : (timestamp_us > 0) ? timestamp_us : AP_HAL::micros64(),
449 instance : _instance,
450 desired_roll : target_roll,
451 actual_roll : roll,
452 desired_pitch : target_pitch,
453 actual_pitch : pitch,
454 desired_yaw_bf: target_yaw_is_ef ? nanf : target_yaw,
455 actual_yaw_bf : yaw_bf,
456 desired_yaw_ef: target_yaw_is_ef ? target_yaw : nanf,
457 actual_yaw_ef : yaw_ef,
458 rangefinder_dist : rangefinder_dist,
460 AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
462 #endif
464 #if AP_MOUNT_POI_TO_LATLONALT_ENABLED
465 // get poi information. Returns true on success and fills in gimbal attitude, location and poi location
466 bool AP_Mount_Backend::get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc)
468 WITH_SEMAPHORE(poi_calculation.sem);
470 // record time of request
471 const uint32_t now_ms = AP_HAL::millis();
472 poi_calculation.poi_request_ms = now_ms;
474 // check if poi calculated recently
475 if (now_ms - poi_calculation.poi_update_ms > AP_MOUNT_POI_RESULT_TIMEOUT_MS) {
476 return false;
479 // check attitude is valid
480 if (poi_calculation.att_quat.is_nan()) {
481 return false;
484 quat = poi_calculation.att_quat;
485 loc = poi_calculation.loc;
486 poi_loc = poi_calculation.poi_loc;
487 return true;
490 // calculate the Location that the gimbal is pointing at
491 void AP_Mount_Backend::calculate_poi()
493 while (true) {
494 // run this loop at 10hz
495 hal.scheduler->delay(100);
497 // calculate poi if requested within last 30 seconds
499 WITH_SEMAPHORE(poi_calculation.sem);
500 if ((poi_calculation.poi_request_ms == 0) ||
501 (AP_HAL::millis() - poi_calculation.poi_request_ms > AP_MOUNT_POI_REQUEST_TIMEOUT_MS)) {
502 continue;
506 // get the current location of vehicle
507 const AP_AHRS &ahrs = AP::ahrs();
508 Location curr_loc;
509 if (!ahrs.get_location(curr_loc)) {
510 continue;
513 // change vehicle alt to AMSL
514 curr_loc.change_alt_frame(Location::AltFrame::ABSOLUTE);
516 // project forward from vehicle looking for terrain
517 // start testing at vehicle's location
518 Location test_loc = curr_loc;
519 Location prev_test_loc = curr_loc;
521 // get terrain altitude (AMSL) at test_loc
522 auto terrain = AP_Terrain::get_singleton();
523 float terrain_amsl_m;
524 if ((terrain == nullptr) || !terrain->height_amsl(test_loc, terrain_amsl_m, true)) {
525 continue;
528 // retrieve gimbal attitude
529 Quaternion quat;
530 if (!get_attitude_quaternion(quat)) {
531 // gimbal attitude unavailable
532 continue;
535 // iteratively move test_loc forward until its alt-above-sea-level is below terrain-alt-above-sea-level
536 const float dist_increment_m = MAX(terrain->get_grid_spacing(), 10);
537 const float mount_pitch_deg = degrees(quat.get_euler_pitch());
538 const float mount_yaw_ef_deg = wrap_180(degrees(quat.get_euler_yaw()) + degrees(ahrs.get_yaw()));
539 float total_dist_m = 0;
540 bool get_terrain_alt_success = true;
541 float prev_terrain_amsl_m = terrain_amsl_m;
542 while (total_dist_m < AP_MOUNT_POI_DIST_M_MAX && (test_loc.alt * 0.01) > terrain_amsl_m) {
543 total_dist_m += dist_increment_m;
545 // backup previous test location and terrain amsl
546 prev_test_loc = test_loc;
547 prev_terrain_amsl_m = terrain_amsl_m;
549 // move test location forward
550 test_loc.offset_bearing_and_pitch(mount_yaw_ef_deg, mount_pitch_deg, dist_increment_m);
552 // get terrain's alt-above-sea-level (at test_loc)
553 // fail if terrain alt cannot be retrieved
554 if (!terrain->height_amsl(test_loc, terrain_amsl_m, true) || std::isnan(terrain_amsl_m)) {
555 get_terrain_alt_success = false;
556 continue;
560 // if a fail occurred above when getting terrain alt then restart calculations from the beginning
561 if (!get_terrain_alt_success) {
562 continue;
565 if (total_dist_m >= AP_MOUNT_POI_DIST_M_MAX) {
566 // unable to find terrain within dist_max
567 continue;
570 // test location has dropped below terrain
571 // interpolate along line between prev_test_loc and test_loc
572 float dist_interp_m = linear_interpolate(0, dist_increment_m, 0, prev_test_loc.alt * 0.01 - prev_terrain_amsl_m, test_loc.alt * 0.01 - terrain_amsl_m);
574 WITH_SEMAPHORE(poi_calculation.sem);
575 poi_calculation.poi_loc = prev_test_loc;
576 poi_calculation.poi_loc.offset_bearing_and_pitch(mount_yaw_ef_deg, mount_pitch_deg, dist_interp_m);
577 poi_calculation.att_quat = {quat[0], quat[1], quat[2], quat[3]};
578 poi_calculation.loc = curr_loc;
579 poi_calculation.poi_update_ms = AP_HAL::millis();
583 #endif
585 // change to RC_TARGETING mode if rc inputs have changed by more than the dead zone
586 // should be called on every update
587 void AP_Mount_Backend::set_rctargeting_on_rcinput_change()
589 // exit immediately if no RC input
590 if (!rc().has_valid_input()) {
591 return;
594 const RC_Channel *roll_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_ROLL : RC_Channel::AUX_FUNC::MOUNT2_ROLL);
595 const RC_Channel *pitch_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_PITCH : RC_Channel::AUX_FUNC::MOUNT2_PITCH);
596 const RC_Channel *yaw_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_YAW : RC_Channel::AUX_FUNC::MOUNT2_YAW);
598 // get rc input
599 const int16_t roll_in = (roll_ch == nullptr) ? 0 : roll_ch->get_radio_in();
600 const int16_t pitch_in = (pitch_ch == nullptr) ? 0 : pitch_ch->get_radio_in();
601 const int16_t yaw_in = (yaw_ch == nullptr) ? 0 : yaw_ch->get_radio_in();
603 if (!last_rc_input.initialised) {
604 // The first time through, initial RC inputs should be set, but not used
605 last_rc_input.initialised = true;
606 last_rc_input.roll_in = roll_in;
607 last_rc_input.pitch_in = pitch_in;
608 last_rc_input.yaw_in = yaw_in;
610 // if not in RC_TARGETING or RETRACT modes then check for RC change
611 if (get_mode() != MAV_MOUNT_MODE_RC_TARGETING && get_mode() != MAV_MOUNT_MODE_RETRACT) {
612 // get dead zones
613 const int16_t roll_dz = (roll_ch == nullptr) ? 10 : MAX(roll_ch->get_dead_zone(), 10);
614 const int16_t pitch_dz = (pitch_ch == nullptr) ? 10 : MAX(pitch_ch->get_dead_zone(), 10);
615 const int16_t yaw_dz = (yaw_ch == nullptr) ? 10 : MAX(yaw_ch->get_dead_zone(), 10);
617 // check if RC input has changed by more than the dead zone
618 if ((abs(last_rc_input.roll_in - roll_in) > roll_dz) ||
619 (abs(last_rc_input.pitch_in - pitch_in) > pitch_dz) ||
620 (abs(last_rc_input.yaw_in - yaw_in) > yaw_dz)) {
621 set_mode(MAV_MOUNT_MODE_RC_TARGETING);
625 // if NOW in RC_TARGETING or RETRACT mode then store last RC input (mode might have changed)
626 if (get_mode() == MAV_MOUNT_MODE_RC_TARGETING || get_mode() == MAV_MOUNT_MODE_RETRACT) {
627 last_rc_input.roll_in = roll_in;
628 last_rc_input.pitch_in = pitch_in;
629 last_rc_input.yaw_in = yaw_in;
633 // get pilot input (in the range -1 to +1) received through RC
634 void AP_Mount_Backend::get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const
636 const RC_Channel *roll_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_ROLL : RC_Channel::AUX_FUNC::MOUNT2_ROLL);
637 const RC_Channel *pitch_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_PITCH : RC_Channel::AUX_FUNC::MOUNT2_PITCH);
638 const RC_Channel *yaw_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_YAW : RC_Channel::AUX_FUNC::MOUNT2_YAW);
640 roll_in = 0;
641 if ((roll_ch != nullptr) && (roll_ch->get_radio_in() > 0)) {
642 roll_in = roll_ch->norm_input_dz();
645 pitch_in = 0;
646 if ((pitch_ch != nullptr) && (pitch_ch->get_radio_in() > 0)) {
647 pitch_in = pitch_ch->norm_input_dz();
650 yaw_in = 0;
651 if ((yaw_ch != nullptr) && (yaw_ch->get_radio_in() > 0)) {
652 yaw_in = yaw_ch->norm_input_dz();
656 // get angle or rate targets from pilot RC
657 // target_type will be either ANGLE or RATE, rpy will be the target angle in deg or rate in deg/s
658 void AP_Mount_Backend::get_rc_target(MountTargetType& target_type, MountTarget& target_rpy) const
660 // get RC input from pilot
661 float roll_in, pitch_in, yaw_in;
662 get_rc_input(roll_in, pitch_in, yaw_in);
664 // yaw frame
665 target_rpy.yaw_is_ef = _yaw_lock;
667 // if RC_RATE is zero, targets are angle
668 if (_params.rc_rate_max <= 0) {
669 target_type = MountTargetType::ANGLE;
671 // roll angle
672 target_rpy.roll = radians(((roll_in + 1.0f) * 0.5f * (_params.roll_angle_max - _params.roll_angle_min) + _params.roll_angle_min));
674 // pitch angle
675 target_rpy.pitch = radians(((pitch_in + 1.0f) * 0.5f * (_params.pitch_angle_max - _params.pitch_angle_min) + _params.pitch_angle_min));
677 // yaw angle
678 if (target_rpy.yaw_is_ef) {
679 // if yaw is earth-frame pilot yaw input control angle from -180 to +180 deg
680 target_rpy.yaw = yaw_in * M_PI;
681 } else {
682 // yaw target in body frame so apply body frame limits
683 target_rpy.yaw = radians(((yaw_in + 1.0f) * 0.5f * (_params.yaw_angle_max - _params.yaw_angle_min) + _params.yaw_angle_min));
685 return;
688 // calculate rate targets
689 target_type = MountTargetType::RATE;
690 const float rc_rate_max_rads = radians(_params.rc_rate_max.get());
691 target_rpy.roll = roll_in * rc_rate_max_rads;
692 target_rpy.pitch = pitch_in * rc_rate_max_rads;
693 target_rpy.yaw = yaw_in * rc_rate_max_rads;
696 // get angle targets (in radians) to a Location
697 // returns true on success, false on failure
698 bool AP_Mount_Backend::get_angle_target_to_location(const Location &loc, MountTarget& angle_rad) const
700 // exit immediately if vehicle's location is unavailable
701 Location current_loc;
702 if (!AP::ahrs().get_location(current_loc)) {
703 return false;
706 // exit immediate if location is invalid
707 if (!loc.initialised()) {
708 return false;
711 const float GPS_vector_x = Location::diff_longitude(loc.lng, current_loc.lng)*cosf(ToRad((current_loc.lat + loc.lat) * 0.00000005f)) * 0.01113195f;
712 const float GPS_vector_y = (loc.lat - current_loc.lat) * 0.01113195f;
713 int32_t target_alt_cm = 0;
714 if (!loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, target_alt_cm)) {
715 return false;
717 int32_t current_alt_cm = 0;
718 if (!current_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, current_alt_cm)) {
719 return false;
721 float GPS_vector_z = target_alt_cm - current_alt_cm;
722 float target_distance = 100.0f*norm(GPS_vector_x, GPS_vector_y); // Careful , centimeters here locally. Baro/alt is in cm, lat/lon is in meters.
724 // calculate roll, pitch, yaw angles
725 angle_rad.roll = 0;
726 angle_rad.pitch = atan2f(GPS_vector_z, target_distance);
727 angle_rad.yaw = atan2f(GPS_vector_x, GPS_vector_y);
728 angle_rad.yaw_is_ef = true;
730 return true;
733 // get angle targets (in radians) to ROI location
734 // returns true on success, false on failure
735 bool AP_Mount_Backend::get_angle_target_to_roi(MountTarget& angle_rad) const
737 if (!_roi_target_set) {
738 return false;
740 return get_angle_target_to_location(_roi_target, angle_rad);
743 // return body-frame yaw angle from a mount target
744 float AP_Mount_Backend::MountTarget::get_bf_yaw() const
746 if (yaw_is_ef) {
747 // convert to body-frame
748 return wrap_PI(yaw - AP::ahrs().get_yaw());
751 // target is already body-frame
752 return yaw;
755 // return earth-frame yaw angle from a mount target
756 float AP_Mount_Backend::MountTarget::get_ef_yaw() const
758 if (yaw_is_ef) {
759 // target is already earth-frame
760 return yaw;
763 // convert to earth-frame
764 return wrap_PI(yaw + AP::ahrs().get_yaw());
767 // sets roll, pitch, yaw and yaw_is_ef
768 void AP_Mount_Backend::MountTarget::set(const Vector3f& rpy, bool yaw_is_ef_in)
770 roll = rpy.x;
771 pitch = rpy.y;
772 yaw = rpy.z;
773 yaw_is_ef = yaw_is_ef_in;
776 // update angle targets using a given rate target
777 // the resulting angle_rad yaw frame will match the rate_rad yaw frame
778 // assumes a 50hz update rate
779 void AP_Mount_Backend::update_angle_target_from_rate(const MountTarget& rate_rad, MountTarget& angle_rad) const
781 // update roll and pitch angles and apply limits
782 angle_rad.roll = constrain_float(angle_rad.roll + rate_rad.roll * AP_MOUNT_UPDATE_DT, radians(_params.roll_angle_min), radians(_params.roll_angle_max));
783 angle_rad.pitch = constrain_float(angle_rad.pitch + rate_rad.pitch * AP_MOUNT_UPDATE_DT, radians(_params.pitch_angle_min), radians(_params.pitch_angle_max));
785 // ensure angle yaw frames matches rate yaw frame
786 if (angle_rad.yaw_is_ef != rate_rad.yaw_is_ef) {
787 if (rate_rad.yaw_is_ef) {
788 angle_rad.yaw = angle_rad.get_ef_yaw();
789 } else {
790 angle_rad.yaw = angle_rad.get_bf_yaw();
792 angle_rad.yaw_is_ef = rate_rad.yaw_is_ef;
795 // update yaw angle target
796 angle_rad.yaw = angle_rad.yaw + rate_rad.yaw * AP_MOUNT_UPDATE_DT;
797 if (angle_rad.yaw_is_ef) {
798 // if earth-frame yaw wraps between += 180 degrees
799 angle_rad.yaw = wrap_PI(angle_rad.yaw);
800 } else {
801 // if body-frame constrain yaw to body-frame limits
802 angle_rad.yaw = constrain_float(angle_rad.yaw, radians(_params.yaw_angle_min), radians(_params.yaw_angle_max));
806 // helper function to provide GIMBAL_DEVICE_FLAGS for use in GIMBAL_DEVICE_ATTITUDE_STATUS message
807 uint16_t AP_Mount_Backend::get_gimbal_device_flags() const
809 // get yaw lock state by mode
810 bool yaw_lock_state = false;
811 switch (_mode) {
812 case MAV_MOUNT_MODE_RETRACT:
813 case MAV_MOUNT_MODE_NEUTRAL:
814 // these modes always use body-frame yaw (aka follow)
815 yaw_lock_state = false;
816 break;
817 case MAV_MOUNT_MODE_MAVLINK_TARGETING:
818 switch (mnt_target.target_type) {
819 case MountTargetType::RATE:
820 yaw_lock_state = mnt_target.rate_rads.yaw_is_ef;
821 break;
822 case MountTargetType::ANGLE:
823 yaw_lock_state = mnt_target.angle_rad.yaw_is_ef;
824 break;
826 break;
827 case MAV_MOUNT_MODE_RC_TARGETING:
828 yaw_lock_state = _yaw_lock;
829 break;
830 case MAV_MOUNT_MODE_GPS_POINT:
831 case MAV_MOUNT_MODE_SYSID_TARGET:
832 case MAV_MOUNT_MODE_HOME_LOCATION:
833 // these modes always use earth-frame yaw (aka lock)
834 yaw_lock_state = true;
835 break;
836 case MAV_MOUNT_MODE_ENUM_END:
837 // unsupported
838 yaw_lock_state = false;
839 break;
842 const uint16_t flags = (get_mode() == MAV_MOUNT_MODE_RETRACT ? GIMBAL_DEVICE_FLAGS_RETRACT : 0) |
843 (get_mode() == MAV_MOUNT_MODE_NEUTRAL ? GIMBAL_DEVICE_FLAGS_NEUTRAL : 0) |
844 GIMBAL_DEVICE_FLAGS_ROLL_LOCK | // roll angle is always earth-frame
845 GIMBAL_DEVICE_FLAGS_PITCH_LOCK| // pitch angle is always earth-frame, yaw_angle is always body-frame
846 GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME | // yaw angle is always in vehicle-frame
847 (yaw_lock_state ? GIMBAL_DEVICE_FLAGS_YAW_LOCK : 0);
848 return flags;
851 // get angle targets (in radians) to home location
852 // returns true on success, false on failure
853 bool AP_Mount_Backend::get_angle_target_to_home(MountTarget& angle_rad) const
855 // exit immediately if home is not set
856 if (!AP::ahrs().home_is_set()) {
857 return false;
859 return get_angle_target_to_location(AP::ahrs().get_home(), angle_rad);
862 // get angle targets (in radians) to a vehicle with sysid of _target_sysid
863 // returns true on success, false on failure
864 bool AP_Mount_Backend::get_angle_target_to_sysid(MountTarget& angle_rad) const
866 // exit immediately if sysid is not set or no location available
867 if (!_target_sysid_location_set) {
868 return false;
870 if (!_target_sysid) {
871 return false;
873 return get_angle_target_to_location(_target_sysid_location, angle_rad);
876 // get target rate in deg/sec. returns true on success
877 bool AP_Mount_Backend::get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame)
879 if (mnt_target.target_type == MountTargetType::RATE) {
880 roll_degs = degrees(mnt_target.rate_rads.roll);
881 pitch_degs = degrees(mnt_target.rate_rads.pitch);
882 yaw_degs = degrees(mnt_target.rate_rads.yaw);
883 yaw_is_earth_frame = mnt_target.rate_rads.yaw_is_ef;
884 return true;
886 return false;
889 // get target angle in deg. returns true on success
890 bool AP_Mount_Backend::get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame)
892 if (mnt_target.target_type == MountTargetType::ANGLE) {
893 roll_deg = degrees(mnt_target.angle_rad.roll);
894 pitch_deg = degrees(mnt_target.angle_rad.pitch);
895 yaw_deg = degrees(mnt_target.angle_rad.yaw);
896 yaw_is_earth_frame = mnt_target.angle_rad.yaw_is_ef;
897 return true;
899 return false;
902 // sent warning to GCS. Warnings are throttled to at most once every 30 seconds
903 void AP_Mount_Backend::send_warning_to_GCS(const char* warning_str)
905 uint32_t now_ms = AP_HAL::millis();
906 if (now_ms - _last_warning_ms < 30000) {
907 return;
910 GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Mount: %s", warning_str);
911 _last_warning_ms = now_ms;
914 #endif // HAL_MOUNT_ENABLED