aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-05-12 09:20:40 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-05-12 09:20:40 +0200
commitd9333a199354c0dfbe742cf396a90dc064cc5195 (patch)
tree960a665b96358815a46e6c7d4ace60b2ef2c0c75 /src
parent2569338919acda9b3bc64f4a02e2014f621980c4 (diff)
downloadpx4-firmware-d9333a199354c0dfbe742cf396a90dc064cc5195.tar.gz
px4-firmware-d9333a199354c0dfbe742cf396a90dc064cc5195.tar.bz2
px4-firmware-d9333a199354c0dfbe742cf396a90dc064cc5195.zip
manual control setpoint: rename variables
Diffstat (limited to 'src')
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h36
1 files changed, 23 insertions, 13 deletions
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index a23d89cd2..593e9453f 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -64,22 +64,32 @@ struct manual_control_setpoint_s {
/**
* Any of the channels may not be available and be set to NaN
* to indicate that it does not contain valid data.
+ * The variable names follow the definition of the
+ * MANUAL_CONTROL mavlink message.
+ * The default range is from -1 to 1 (mavlink message -1000 to 1000)
+ * The range for the z variable is defined from 0 to 1. (The z field of
+ * the MANUAL_CONTROL mavlink message is defined from -1000 to 1000)
*/
- float roll; /**< ailerons roll / roll rate input, -1..1 */
- float pitch; /**< elevator / pitch / pitch rate, -1..1 */
- float yaw; /**< rudder / yaw rate / yaw, -1..1 */
- float throttle; /**< throttle / collective thrust / altitude, 0..1 */
+ float x; /**< stick position in x direction -1..1
+ in general corresponds to forward/back motion or pitch of vehicle */
+ float y; /**< stick position in y direction -1..1
+ in general corresponds to right/left motion or roll of vehicle */
+ float z; /**< throttle stick position 0..1
+ in general corresponds to up/down motion or thrust of vehicle */
+ float r; /**< yaw stick/twist positon, -1..1
+ in general corresponds to rotation around the vertical
+ (downwards) axis of the vehicle */
float flaps; /**< flap position */
- float aux1; /**< default function: camera yaw / azimuth */
- float aux2; /**< default function: camera pitch / tilt */
- float aux3; /**< default function: camera trigger */
- float aux4; /**< default function: camera roll */
- float aux5; /**< default function: payload drop */
+ float aux1; /**< default function: camera yaw / azimuth */
+ float aux2; /**< default function: camera pitch / tilt */
+ float aux3; /**< default function: camera trigger */
+ float aux4; /**< default function: camera roll */
+ float aux5; /**< default function: payload drop */
- switch_pos_t mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
- switch_pos_t return_switch; /**< land 2 position switch (mandatory): land, no effect */
- switch_pos_t assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
- switch_pos_t loiter_switch; /**< mission 2 position switch (optional): mission, loiter */
+ switch_pos_t mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
+ switch_pos_t return_switch; /**< land 2 position switch (mandatory): land, no effect */
+ switch_pos_t assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
+ switch_pos_t loiter_switch; /**< mission 2 position switch (optional): mission, loiter */
}; /**< manual control inputs */
/**