mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 11:59:17 +08:00
vmount: add param to use RC input for angular rate
Until now RC input was translated to angles only. I added the param MNT_RC_IN_MODE which allows the RC input to be used for angular rate.
This commit is contained in:
@@ -145,9 +145,10 @@ param set-default MPC_Z_VEL_P 0.27
|
|||||||
|
|
||||||
# gimbal configuration
|
# gimbal configuration
|
||||||
param set-default MNT_MODE_IN 1
|
param set-default MNT_MODE_IN 1
|
||||||
param set-default MNT_MODE_OUT 2
|
param set-default MNT_MODE_OUT 1
|
||||||
param set-default MNT_MAN_PITCH 1
|
param set-default MNT_MAN_PITCH 1
|
||||||
|
param set-default MNT_RC_IN_MODE 1
|
||||||
|
param set-default MNT_RATE_PITCH 30
|
||||||
|
|
||||||
# RC
|
# RC
|
||||||
param set-default RC_CHAN_CNT 12
|
param set-default RC_CHAN_CNT 12
|
||||||
|
|||||||
@@ -61,6 +61,9 @@
|
|||||||
#define FLASH_BASED_PARAMS
|
#define FLASH_BASED_PARAMS
|
||||||
#define RAM_BASED_MISSIONS
|
#define RAM_BASED_MISSIONS
|
||||||
|
|
||||||
|
// Hacks for MAVLink RC button input
|
||||||
|
#define ATL_MANTIS_RC_INPUT_HACKS
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* ADC channels
|
* ADC channels
|
||||||
*
|
*
|
||||||
|
|||||||
@@ -66,6 +66,9 @@ int OutputMavlinkV1::update(const ControlData *control_data)
|
|||||||
//got new command
|
//got new command
|
||||||
_set_angle_setpoints(control_data);
|
_set_angle_setpoints(control_data);
|
||||||
|
|
||||||
|
#if !defined(ALT_MANTIS_GIMBAL_HACKS)
|
||||||
|
// Don't send this command to ATL Mantis as it just spams the vehicle_command queue and the
|
||||||
|
// Mantis ignores it anyway.
|
||||||
vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONFIGURE;
|
vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONFIGURE;
|
||||||
vehicle_command.timestamp = hrt_absolute_time();
|
vehicle_command.timestamp = hrt_absolute_time();
|
||||||
|
|
||||||
@@ -89,6 +92,7 @@ int OutputMavlinkV1::update(const ControlData *control_data)
|
|||||||
vehicle_command.param4 = _stabilize[2] ? 1.0f : 0.0f;
|
vehicle_command.param4 = _stabilize[2] ? 1.0f : 0.0f;
|
||||||
|
|
||||||
_vehicle_command_pub.publish(vehicle_command);
|
_vehicle_command_pub.publish(vehicle_command);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
_handle_position_update();
|
_handle_position_update();
|
||||||
|
|||||||
@@ -184,6 +184,7 @@ extern "C" __EXPORT int tune_control_main(int argc, char *argv[])
|
|||||||
|
|
||||||
PX4_DEBUG("Publishing standard tune %d", tune_control.tune_id);
|
PX4_DEBUG("Publishing standard tune %d", tune_control.tune_id);
|
||||||
publish_tune_control(tune_control);
|
publish_tune_control(tune_control);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
PX4_WARN("Missing argument");
|
PX4_WARN("Missing argument");
|
||||||
usage();
|
usage();
|
||||||
|
|||||||
Reference in New Issue
Block a user