mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: Set relative pan to true for servo mounts
This commit is contained in:
parent
44902ef535
commit
0dbe2e072c
@ -213,13 +213,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] = {
|
|||||||
|
|
||||||
// 23 formerly _K_RATE
|
// 23 formerly _K_RATE
|
||||||
|
|
||||||
// @Param: _OPTIONS
|
// 24 is AVAILABLE
|
||||||
// @DisplayName: Options field
|
|
||||||
// @Description: User configurable options; 0 = Enable Relative Pan on Servo Mounts
|
|
||||||
// @Values: 0:RelativePan
|
|
||||||
// @Bitmask: 0:RelativePan
|
|
||||||
// @User: Standard
|
|
||||||
AP_GROUPINFO("_OPTIONS", 24, AP_Mount, state[0]._options, 0),
|
|
||||||
|
|
||||||
#if AP_MOUNT_MAX_INSTANCES > 1
|
#if AP_MOUNT_MAX_INSTANCES > 1
|
||||||
// @Param: 2_DEFLT_MODE
|
// @Param: 2_DEFLT_MODE
|
||||||
@ -401,14 +395,6 @@ const AP_Param::GroupInfo AP_Mount::var_info[] = {
|
|||||||
// @Values: 0:None, 1:Servo, 2:3DR Solo, 3:Alexmos Serial, 4:SToRM32 MAVLink, 5:SToRM32 Serial
|
// @Values: 0:None, 1:Servo, 2:3DR Solo, 3:Alexmos Serial, 4:SToRM32 MAVLink, 5:SToRM32 Serial
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("2_TYPE", 42, AP_Mount, state[1]._type, 0),
|
AP_GROUPINFO("2_TYPE", 42, AP_Mount, state[1]._type, 0),
|
||||||
|
|
||||||
// @Param: 2_OPTIONS
|
|
||||||
// @DisplayName: Options field for Mount 2
|
|
||||||
// @Description: User configurable options; 0 = Enable Relative Pan on Servo Mounts
|
|
||||||
// @Values: 0:RelativePan
|
|
||||||
// @Bitmask: 0:RelativePan
|
|
||||||
// @User: Standard
|
|
||||||
AP_GROUPINFO("2_OPTIONS", 43, AP_Mount, state[1]._options, 0),
|
|
||||||
#endif // AP_MOUNT_MAX_INSTANCES > 1
|
#endif // AP_MOUNT_MAX_INSTANCES > 1
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
@ -40,9 +40,6 @@
|
|||||||
// maximum number of mounts
|
// maximum number of mounts
|
||||||
#define AP_MOUNT_MAX_INSTANCES 1
|
#define AP_MOUNT_MAX_INSTANCES 1
|
||||||
|
|
||||||
// options (see _OPTIONS parameter)
|
|
||||||
#define AP_MOUNT_OPTION_RELATIVE_PAN (1<<0)
|
|
||||||
|
|
||||||
// declare backend classes
|
// declare backend classes
|
||||||
class AP_Mount_Backend;
|
class AP_Mount_Backend;
|
||||||
class AP_Mount_Servo;
|
class AP_Mount_Servo;
|
||||||
@ -193,8 +190,6 @@ protected:
|
|||||||
Location _target_sysid_location; // sysid target location
|
Location _target_sysid_location; // sysid target location
|
||||||
bool _target_sysid_location_set;
|
bool _target_sysid_location_set;
|
||||||
|
|
||||||
AP_Int8 _options; // Options field, bit 0 = use relative pan
|
|
||||||
|
|
||||||
} state[AP_MOUNT_MAX_INSTANCES];
|
} state[AP_MOUNT_MAX_INSTANCES];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -35,8 +35,6 @@ void AP_Mount_Servo::update()
|
|||||||
_last_check_servo_map_ms = now;
|
_last_check_servo_map_ms = now;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t relative_pan = _state._options & AP_MOUNT_OPTION_RELATIVE_PAN;
|
|
||||||
|
|
||||||
switch(get_mode()) {
|
switch(get_mode()) {
|
||||||
// move mount to a "retracted position" or to a position where a fourth servo can retract the entire mount into the fuselage
|
// move mount to a "retracted position" or to a position where a fourth servo can retract the entire mount into the fuselage
|
||||||
case MAV_MOUNT_MODE_RETRACT:
|
case MAV_MOUNT_MODE_RETRACT:
|
||||||
@ -72,7 +70,7 @@ void AP_Mount_Servo::update()
|
|||||||
// point mount to a GPS point given by the mission planner
|
// point mount to a GPS point given by the mission planner
|
||||||
case MAV_MOUNT_MODE_GPS_POINT:
|
case MAV_MOUNT_MODE_GPS_POINT:
|
||||||
{
|
{
|
||||||
if (calc_angle_to_roi_target(_angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, relative_pan)) {
|
if (calc_angle_to_roi_target(_angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, true)) {
|
||||||
stabilize();
|
stabilize();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@ -85,7 +83,7 @@ void AP_Mount_Servo::update()
|
|||||||
}
|
}
|
||||||
_state._roi_target = AP::ahrs().get_home();
|
_state._roi_target = AP::ahrs().get_home();
|
||||||
_state._roi_target_set = true;
|
_state._roi_target_set = true;
|
||||||
if (calc_angle_to_roi_target(_angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, relative_pan)) {
|
if (calc_angle_to_roi_target(_angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, true)) {
|
||||||
stabilize();
|
stabilize();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@ -94,7 +92,7 @@ void AP_Mount_Servo::update()
|
|||||||
if (calc_angle_to_sysid_target(_angle_ef_target_rad,
|
if (calc_angle_to_sysid_target(_angle_ef_target_rad,
|
||||||
_flags.tilt_control,
|
_flags.tilt_control,
|
||||||
_flags.pan_control,
|
_flags.pan_control,
|
||||||
relative_pan)) {
|
true)) {
|
||||||
stabilize();
|
stabilize();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user