# Controls ## Arming When armed, the aircraft is ready to fly and the motors will spin when throttle is applied. With multirotors, the motors will spin at a slow speed when armed (this feature may be disabled by setting MOTOR_STOP, but for safety reasons, that is not recommended). Arming and disarming is done using a switch, set up on the modes page. (NOTE: Stick arming was removed in iNav 2.2) ## Stick Positions The three stick positions are: |Position | Approx. Channel Input| |----------------|----------------------| |LOW | 1000 | |CENTER | 1500 | |HIGH | 2000 | The stick positions are combined to activate different functions: | Function | Throttle | Yaw | Pitch | Roll | | ----------------------------- | -------- | ------- | ------ | ------ | | Profile 1 | LOW | LOW | CENTER | LOW | | Profile 2 | LOW | LOW | HIGH | CENTER | | Profile 3 | LOW | LOW | CENTER | HIGH | | Battery profile 1 | HIGH | LOW | CENTER | LOW | | Battery profile 2 | HIGH | LOW | HIGH | CENTER | | Battery profile 3 | HIGH | LOW | CENTER | HIGH | | Calibrate Gyro | LOW | LOW | LOW | CENTER | | Calibrate Acc | HIGH | LOW | LOW | CENTER | | Calibrate Mag/Compass | HIGH | HIGH | LOW | CENTER | | Trim Acc Left | HIGH | CENTER | CENTER | LOW | | Trim Acc Right | HIGH | CENTER | CENTER | HIGH | | Trim Acc Forwards | HIGH | CENTER | HIGH | CENTER | | Trim Acc Backwards | HIGH | CENTER | LOW | CENTER | | Save current waypoint mission | LOW | CENTER | HIGH | LOW | | Load/unload current waypoint mission | LOW | CENTER | HIGH | HIGH | | Save setting | LOW | LOW | LOW | HIGH | | Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER |  ## Yaw control While arming/disarming with sticks, your yaw stick will be moving to extreme values. In order to prevent your craft from trying to yaw during arming/disarming while on the ground, your yaw input will not cause the craft to yaw when the throttle is LOW (i.e. below the `min_check` setting). For tricopters, you may want to retain the ability to yaw while on the ground, so that you can verify that your tail servo is working correctly before takeoff. You can do this by setting `tri_unarmed_servo` to `1` on the CLI (this is the default). If you are having issues with your tail rotor contacting the ground during arm/disarm, you can set this to `0` instead. Check this table to decide which setting will suit you:
Is yaw control of the tricopter allowed? | ||||
---|---|---|---|---|
Disarmed | Armed | |||
Throttle low | Throttle normal | Throttle low | Throttle normal | |
tri_unarmed_servo = 0 | No | No | No | Yes |
No | No | No | Yes | |
tri_unarmed_servo = 1 | Yes | Yes | Yes | Yes |
Yes | Yes | Yes | Yes |