AP_Mount: support MAV_MOUNT_MODE_HOME_LOCATION to point at HOME

This commit is contained in:
Peter Barker 2020-12-21 20:07:43 +11:00 committed by Peter Barker
parent cfb1213f43
commit 7b9fbe3b30
6 changed files with 67 additions and 3 deletions

View File

@ -57,6 +57,18 @@ void AP_Mount_Alexmos::update()
}
break;
case MAV_MOUNT_MODE_HOME_LOCATION:
// constantly update the home location:
if (!AP::ahrs().home_is_set()) {
break;
}
_state._roi_target = AP::ahrs().get_home();
_state._roi_target_set = true;
if (calc_angle_to_roi_target(_angle_ef_target_rad, true, false)) {
control_axis(_angle_ef_target_rad, false);
}
break;
case MAV_MOUNT_MODE_SYSID_TARGET:
if (calc_angle_to_sysid_target(_angle_ef_target_rad,
true,

View File

@ -85,6 +85,13 @@ void AP_Mount_Backend::control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_
break;
}
case MAV_MOUNT_MODE_HOME_LOCATION: {
// set the target gps location
_state._roi_target = AP::ahrs().get_home();
_state._roi_target_set = true;
break;
}
default:
// do nothing
break;

View File

@ -64,6 +64,18 @@ void AP_Mount_SToRM32::update()
}
break;
case MAV_MOUNT_MODE_HOME_LOCATION:
// constantly update the home location:
if (!AP::ahrs().home_is_set()) {
break;
}
_state._roi_target = AP::ahrs().get_home();
_state._roi_target_set = true;
if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) {
resend_now = true;
}
break;
case MAV_MOUNT_MODE_SYSID_TARGET:
if (calc_angle_to_sysid_target(_angle_ef_target_rad, true, true)) {
resend_now = true;

View File

@ -80,6 +80,18 @@ void AP_Mount_SToRM32_serial::update()
}
break;
case MAV_MOUNT_MODE_HOME_LOCATION:
// constantly update the home location:
if (!AP::ahrs().home_is_set()) {
break;
}
_state._roi_target = AP::ahrs().get_home();
_state._roi_target_set = true;
if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) {
resend_now = true;
}
break;
case MAV_MOUNT_MODE_SYSID_TARGET:
if (calc_angle_to_sysid_target(_angle_ef_target_rad,
true,

View File

@ -76,6 +76,18 @@ void AP_Mount_Servo::update()
break;
}
case MAV_MOUNT_MODE_HOME_LOCATION:
// constantly update the home location:
if (!AP::ahrs().home_is_set()) {
break;
}
_state._roi_target = AP::ahrs().get_home();
_state._roi_target_set = true;
if (calc_angle_to_roi_target(_angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, false)) {
stabilize();
}
break;
case MAV_MOUNT_MODE_SYSID_TARGET:
if (calc_angle_to_sysid_target(_angle_ef_target_rad,
_flags.tilt_control,

View File

@ -69,13 +69,22 @@ void AP_Mount_SoloGimbal::update()
// point mount to a GPS point given by the mission planner
case MAV_MOUNT_MODE_GPS_POINT:
_gimbal.set_lockedToBody(false);
if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) {
UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true));
break;
case MAV_MOUNT_MODE_HOME_LOCATION:
// constantly update the home location:
if (!AP::ahrs().home_is_set()) {
break;
}
_state._roi_target = AP::ahrs().get_home();
_state._roi_target_set = true;
_gimbal.set_lockedToBody(false);
UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true));
break;
case MAV_MOUNT_MODE_SYSID_TARGET:
if (calc_angle_to_sysid_target(_angle_ef_target_rad, true, true)) {
}
UNUSED_RESULT(calc_angle_to_sysid_target(_angle_ef_target_rad, true, true));
break;
default: