mirror of
https://github.com/okalachev/flix.git
synced 2025-07-27 17:49:33 +00:00
Make MAVLink control scale a parameter
This commit is contained in:
parent
26bb4d2b3f
commit
7effd92043
@ -13,6 +13,8 @@
|
|||||||
#define MAVLINK_CONTROL_SCALE 0.7f
|
#define MAVLINK_CONTROL_SCALE 0.7f
|
||||||
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
||||||
|
|
||||||
|
float mavlinkControlScale = 0.7;
|
||||||
|
|
||||||
extern double controlsTime;
|
extern double controlsTime;
|
||||||
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||||
|
|
||||||
@ -92,9 +94,9 @@ void handleMavlink(const void *_msg) {
|
|||||||
mavlink_manual_control_t manualControl;
|
mavlink_manual_control_t manualControl;
|
||||||
mavlink_msg_manual_control_decode(msg, &manualControl);
|
mavlink_msg_manual_control_decode(msg, &manualControl);
|
||||||
controls[throttleChannel] = manualControl.z / 1000.0f;
|
controls[throttleChannel] = manualControl.z / 1000.0f;
|
||||||
controls[pitchChannel] = manualControl.x / 1000.0f * MAVLINK_CONTROL_SCALE;
|
controls[pitchChannel] = manualControl.x / 1000.0f * mavlinkControlScale;
|
||||||
controls[rollChannel] = manualControl.y / 1000.0f * MAVLINK_CONTROL_SCALE;
|
controls[rollChannel] = manualControl.y / 1000.0f * mavlinkControlScale;
|
||||||
controls[yawChannel] = manualControl.r / 1000.0f * MAVLINK_CONTROL_SCALE;
|
controls[yawChannel] = manualControl.r / 1000.0f * mavlinkControlScale;
|
||||||
controls[modeChannel] = 1; // STAB mode
|
controls[modeChannel] = 1; // STAB mode
|
||||||
controls[armedChannel] = 1; // armed
|
controls[armedChannel] = 1; // armed
|
||||||
controlsTime = t;
|
controlsTime = t;
|
||||||
|
@ -7,6 +7,7 @@
|
|||||||
|
|
||||||
extern float channelNeutral[16];
|
extern float channelNeutral[16];
|
||||||
extern float channelMax[16];
|
extern float channelMax[16];
|
||||||
|
extern float mavlinkControlScale;
|
||||||
|
|
||||||
Preferences storage;
|
Preferences storage;
|
||||||
|
|
||||||
@ -66,7 +67,9 @@ Parameter parameters[] = {
|
|||||||
{"RC_MAX_4", &channelMax[4]},
|
{"RC_MAX_4", &channelMax[4]},
|
||||||
{"RC_MAX_5", &channelMax[5]},
|
{"RC_MAX_5", &channelMax[5]},
|
||||||
{"RC_MAX_6", &channelMax[6]},
|
{"RC_MAX_6", &channelMax[6]},
|
||||||
{"RC_MAX_7", &channelMax[7]}
|
{"RC_MAX_7", &channelMax[7]},
|
||||||
|
// MAVLink
|
||||||
|
{"MAV_CTRL_SCALE", &mavlinkControlScale},
|
||||||
};
|
};
|
||||||
|
|
||||||
void setupParameters() {
|
void setupParameters() {
|
||||||
|
Loading…
x
Reference in New Issue
Block a user