forked from Archive/PX4-Autopilot
Gimbal: remove shutter and retraction handling
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
parent
18898f1876
commit
ac6c9c857a
|
@ -5,5 +5,3 @@ uint8 INDEX_YAW = 2
|
|||
|
||||
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled
|
||||
float32[3] control
|
||||
|
||||
float32 retract_gimbal
|
||||
|
|
|
@ -78,8 +78,6 @@ struct ControlData {
|
|||
|
||||
Type type = Type::Neutral;
|
||||
|
||||
bool gimbal_shutter_retract = false; // whether to lock the gimbal (only in RC output mode)
|
||||
|
||||
uint8_t sysid_primary_control = 0; // The MAVLink system ID selected to be in control, 0 for no one.
|
||||
uint8_t compid_primary_control = 0; // The MAVLink component ID selected to be in control, 0 for no one.
|
||||
// uint8_t sysid_secondary_control = 0; // The MAVLink system ID selected for additional input, not implemented yet.
|
||||
|
|
|
@ -449,8 +449,6 @@ void update_params(ParameterHandles ¶m_handles, Parameters ¶ms)
|
|||
param_get(param_handles.mnt_mode_out, ¶ms.mnt_mode_out);
|
||||
param_get(param_handles.mnt_mav_sysid_v1, ¶ms.mnt_mav_sysid_v1);
|
||||
param_get(param_handles.mnt_mav_compid_v1, ¶ms.mnt_mav_compid_v1);
|
||||
param_get(param_handles.mnt_ob_lock_mode, ¶ms.mnt_ob_lock_mode);
|
||||
param_get(param_handles.mnt_ob_norm_mode, ¶ms.mnt_ob_norm_mode);
|
||||
param_get(param_handles.mnt_man_pitch, ¶ms.mnt_man_pitch);
|
||||
param_get(param_handles.mnt_man_roll, ¶ms.mnt_man_roll);
|
||||
param_get(param_handles.mnt_man_yaw, ¶ms.mnt_man_yaw);
|
||||
|
@ -476,8 +474,6 @@ bool initialize_params(ParameterHandles ¶m_handles, Parameters ¶ms)
|
|||
param_handles.mnt_mode_out = param_find("MNT_MODE_OUT");
|
||||
param_handles.mnt_mav_sysid_v1 = param_find("MNT_MAV_SYSID");
|
||||
param_handles.mnt_mav_compid_v1 = param_find("MNT_MAV_COMPID");
|
||||
param_handles.mnt_ob_lock_mode = param_find("MNT_OB_LOCK_MODE");
|
||||
param_handles.mnt_ob_norm_mode = param_find("MNT_OB_NORM_MODE");
|
||||
param_handles.mnt_man_pitch = param_find("MNT_MAN_PITCH");
|
||||
param_handles.mnt_man_roll = param_find("MNT_MAN_ROLL");
|
||||
param_handles.mnt_man_yaw = param_find("MNT_MAN_YAW");
|
||||
|
@ -500,8 +496,6 @@ bool initialize_params(ParameterHandles ¶m_handles, Parameters ¶ms)
|
|||
param_handles.mnt_mode_out == PARAM_INVALID ||
|
||||
param_handles.mnt_mav_sysid_v1 == PARAM_INVALID ||
|
||||
param_handles.mnt_mav_compid_v1 == PARAM_INVALID ||
|
||||
param_handles.mnt_ob_lock_mode == PARAM_INVALID ||
|
||||
param_handles.mnt_ob_norm_mode == PARAM_INVALID ||
|
||||
param_handles.mnt_man_pitch == PARAM_INVALID ||
|
||||
param_handles.mnt_man_roll == PARAM_INVALID ||
|
||||
param_handles.mnt_man_yaw == PARAM_INVALID ||
|
||||
|
|
|
@ -88,30 +88,6 @@ PARAM_DEFINE_INT32(MNT_MAV_SYSID, 1);
|
|||
*/
|
||||
PARAM_DEFINE_INT32(MNT_MAV_COMPID, 154);
|
||||
|
||||
/**
|
||||
* Mixer value for selecting normal mode
|
||||
*
|
||||
* if required by the gimbal (only in AUX output mode)
|
||||
*
|
||||
* @min -1.0
|
||||
* @max 1.0
|
||||
* @decimal 3
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_OB_NORM_MODE, -1.0f);
|
||||
|
||||
/**
|
||||
* Mixer value for selecting a locking mode
|
||||
*
|
||||
* if required for the gimbal (only in AUX output mode)
|
||||
*
|
||||
* @min -1.0
|
||||
* @max 1.0
|
||||
* @decimal 3
|
||||
* @group Mount
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MNT_OB_LOCK_MODE, 0.0f);
|
||||
|
||||
/**
|
||||
* Auxiliary channel to control roll (in AUX input or manual mode).
|
||||
*
|
||||
|
|
|
@ -45,8 +45,6 @@ struct Parameters {
|
|||
int32_t mnt_mode_out;
|
||||
int32_t mnt_mav_sysid_v1;
|
||||
int32_t mnt_mav_compid_v1;
|
||||
float mnt_ob_lock_mode;
|
||||
float mnt_ob_norm_mode;
|
||||
int32_t mnt_man_pitch;
|
||||
int32_t mnt_man_roll;
|
||||
int32_t mnt_man_yaw;
|
||||
|
@ -71,8 +69,6 @@ struct ParameterHandles {
|
|||
param_t mnt_mode_out;
|
||||
param_t mnt_mav_sysid_v1;
|
||||
param_t mnt_mav_compid_v1;
|
||||
param_t mnt_ob_lock_mode;
|
||||
param_t mnt_ob_norm_mode;
|
||||
param_t mnt_man_pitch;
|
||||
param_t mnt_man_roll;
|
||||
param_t mnt_man_yaw;
|
||||
|
|
|
@ -257,7 +257,6 @@ InputMavlinkCmdMount::_process_command(ControlData &control_data, const vehicle_
|
|||
|
||||
switch ((int) vehicle_command.param7) {
|
||||
case vehicle_command_s::VEHICLE_MOUNT_MODE_RETRACT:
|
||||
control_data.gimbal_shutter_retract = true;
|
||||
|
||||
// fallthrough
|
||||
case vehicle_command_s::VEHICLE_MOUNT_MODE_NEUTRAL:
|
||||
|
@ -606,8 +605,6 @@ InputMavlinkGimbalV2::UpdateResult InputMavlinkGimbalV2::_process_set_attitude(C
|
|||
InputMavlinkGimbalV2::UpdateResult InputMavlinkGimbalV2::_process_vehicle_roi(ControlData &control_data,
|
||||
const vehicle_roi_s &vehicle_roi)
|
||||
{
|
||||
control_data.gimbal_shutter_retract = false;
|
||||
|
||||
if (vehicle_roi.mode == vehicle_roi_s::ROI_NONE) {
|
||||
|
||||
control_data.type = ControlData::Type::Neutral;
|
||||
|
@ -679,7 +676,6 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
|
|||
|
||||
switch ((int) vehicle_command.param7) {
|
||||
case vehicle_command_s::VEHICLE_MOUNT_MODE_RETRACT:
|
||||
control_data.gimbal_shutter_retract = true;
|
||||
|
||||
// fallthrough
|
||||
|
||||
|
|
|
@ -161,8 +161,6 @@ InputRC::UpdateResult InputRC::_read_control_data_from_subscription(ControlData
|
|||
_last_set_aux_values[i] = new_aux_values[i];
|
||||
}
|
||||
|
||||
control_data.gimbal_shutter_retract = false;
|
||||
|
||||
return UpdateResult::UpdatedActive;
|
||||
|
||||
} else {
|
||||
|
|
|
@ -66,8 +66,6 @@ InputTest::UpdateResult InputTest::update(unsigned int timeout_ms, ControlData &
|
|||
|
||||
q.copyTo(control_data.type_data.angle.q);
|
||||
|
||||
control_data.gimbal_shutter_retract = false;
|
||||
|
||||
control_data.type_data.angle.angular_velocity[0] = NAN;
|
||||
control_data.type_data.angle.angular_velocity[1] = NAN;
|
||||
control_data.type_data.angle.angular_velocity[2] = NAN;
|
||||
|
|
|
@ -51,7 +51,6 @@ OutputRC::OutputRC(const Parameters ¶meters)
|
|||
void OutputRC::update(const ControlData &control_data, bool new_setpoints)
|
||||
{
|
||||
if (new_setpoints) {
|
||||
_retract_gimbal = control_data.gimbal_shutter_retract;
|
||||
_set_angle_setpoints(control_data);
|
||||
}
|
||||
|
||||
|
@ -76,9 +75,6 @@ void OutputRC::update(const ControlData &control_data, bool new_setpoints)
|
|||
(_angle_outputs[2] + math::radians(_parameters.mnt_off_yaw)) *
|
||||
(1.0f / (math::radians(_parameters.mnt_range_yaw / 2.0f))),
|
||||
-1.f, 1.f);
|
||||
gimbal_controls.retract_gimbal = constrain(
|
||||
_retract_gimbal ? _parameters.mnt_ob_lock_mode : _parameters.mnt_ob_norm_mode,
|
||||
-1.f, 1.f);
|
||||
gimbal_controls.timestamp = hrt_absolute_time();
|
||||
_gimbal_controls_pub.publish(gimbal_controls);
|
||||
|
||||
|
|
|
@ -58,8 +58,6 @@ private:
|
|||
|
||||
uORB::Publication <gimbal_controls_s> _gimbal_controls_pub{ORB_ID(gimbal_controls)};
|
||||
uORB::Publication <gimbal_device_attitude_status_s> _attitude_status_pub{ORB_ID(gimbal_device_attitude_status)};
|
||||
|
||||
bool _retract_gimbal = true;
|
||||
};
|
||||
|
||||
} /* namespace gimbal */
|
||||
|
|
Loading…
Reference in New Issue