mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: Add clear_roi_target() function
This commit is contained in:
parent
e12d9e38c7
commit
5d39dd45be
@ -595,6 +595,16 @@ void AP_Mount::set_roi_target(uint8_t instance, const Location &target_loc)
|
|||||||
backend->set_roi_target(target_loc);
|
backend->set_roi_target(target_loc);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// clear_roi_target - clears target location that mount should attempt to point towards
|
||||||
|
void AP_Mount::clear_roi_target(uint8_t instance)
|
||||||
|
{
|
||||||
|
auto *backend = get_instance(instance);
|
||||||
|
if (backend == nullptr) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
backend->clear_roi_target();
|
||||||
|
}
|
||||||
|
|
||||||
//
|
//
|
||||||
// camera controls for gimbals that include a camera
|
// camera controls for gimbals that include a camera
|
||||||
//
|
//
|
||||||
|
@ -139,6 +139,10 @@ public:
|
|||||||
void set_roi_target(const Location &target_loc) { set_roi_target(_primary,target_loc); }
|
void set_roi_target(const Location &target_loc) { set_roi_target(_primary,target_loc); }
|
||||||
void set_roi_target(uint8_t instance, const Location &target_loc);
|
void set_roi_target(uint8_t instance, const Location &target_loc);
|
||||||
|
|
||||||
|
// clear_roi_target - clears target location that mount should attempt to point towards
|
||||||
|
void clear_roi_target() { clear_roi_target(_primary); }
|
||||||
|
void clear_roi_target(uint8_t instance);
|
||||||
|
|
||||||
// point at system ID sysid
|
// point at system ID sysid
|
||||||
void set_target_sysid(uint8_t sysid) { set_target_sysid(_primary, sysid); }
|
void set_target_sysid(uint8_t sysid) { set_target_sysid(_primary, sysid); }
|
||||||
void set_target_sysid(uint8_t instance, uint8_t sysid);
|
void set_target_sysid(uint8_t instance, uint8_t sysid);
|
||||||
|
@ -48,6 +48,19 @@ void AP_Mount_Backend::set_roi_target(const Location &target_loc)
|
|||||||
set_mode(MAV_MOUNT_MODE_GPS_POINT);
|
set_mode(MAV_MOUNT_MODE_GPS_POINT);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// clear_roi_target - clears target location that mount should attempt to point towards
|
||||||
|
void AP_Mount_Backend::clear_roi_target()
|
||||||
|
{
|
||||||
|
// clear the target GPS location
|
||||||
|
_roi_target_set = false;
|
||||||
|
|
||||||
|
// reset the mode if in GPS tracking mode
|
||||||
|
if (_mode == MAV_MOUNT_MODE_GPS_POINT) {
|
||||||
|
MAV_MOUNT_MODE default_mode = (MAV_MOUNT_MODE)_params.default_mode.get();
|
||||||
|
set_mode(default_mode);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// set_sys_target - sets system that mount should attempt to point towards
|
// set_sys_target - sets system that mount should attempt to point towards
|
||||||
void AP_Mount_Backend::set_target_sysid(uint8_t sysid)
|
void AP_Mount_Backend::set_target_sysid(uint8_t sysid)
|
||||||
{
|
{
|
||||||
|
@ -74,6 +74,8 @@ public:
|
|||||||
|
|
||||||
// set_roi_target - sets target location that mount should attempt to point towards
|
// set_roi_target - sets target location that mount should attempt to point towards
|
||||||
void set_roi_target(const Location &target_loc);
|
void set_roi_target(const Location &target_loc);
|
||||||
|
// clear_roi_target - clears target location that mount should attempt to point towards
|
||||||
|
void clear_roi_target();
|
||||||
|
|
||||||
// set_sys_target - sets system that mount should attempt to point towards
|
// set_sys_target - sets system that mount should attempt to point towards
|
||||||
void set_target_sysid(uint8_t sysid);
|
void set_target_sysid(uint8_t sysid);
|
||||||
|
Loading…
Reference in New Issue
Block a user