Некоторые настройки Multiwii (будет дополняться)

SUM PPM on THROTTLE

 Сообщение от erohin                     
                 Вечер добрый, подскажите как в прошивке  MultiWii_2_1_b3 переназначить сумарный PPM с входа RX на THROTTLE, плата  контроллера crius ALL IN ONE PRO v1.0 на меге 2560
                             отвечу на свой вопрос, разобрался такая возможность появилась в MultiWii dev version r1143 (2012/09/27)
необходимо отредактировать в
RX.ino после
/**************************************************************************************/
/***************                PPM SUM RX Pin reading             ********************/
/**************************************************************************************/
// attachInterrupt fix for promicro
#if defined(PROMICRO) && defined(SERIAL_SUM_PPM)
  ISR(INT6_vect){rxInt();}
#endif

вписать

#if defined(PPM_ON_THROTTLE) && defined(MEGA) && defined(SERIAL_SUM_PPM)
  ISR(PCINT2_vect) { if(PINK & (1<<0)) rxInt(); }
#endif

затем в def.h в
/**************************  all the Mega types  ***********************************/
найти #define PPM_PIN_INTERRUPT        attachInterrupt(4, rxInt, RISING);  //PIN 19, also used for Spektrum satellite option
и заменить на
  #if defined(PPM_ON_THROTTLE)
    //configure THROTTLE PIN (A8 pin) as input witch pullup and enabled PCINT interrupt
    #define PPM_PIN_INTERRUPT        DDRK &= ~(1<<0); PORTK |=  (1<<0); PCMSK2 |= (1<<0); PCICR |= (1<<2);
  #else
    #define PPM_PIN_INTERRUPT        attachInterrupt(4, rxInt, RISING);  //PIN 19, also used for Spektrum satellite option
  #endif

и последнее в config.h после раскоменченного желаемого PPM дописать #define PPM_ON_THROTTLE

например так

/**************************************************************************************/
  /********                       special receiver types             ********************/
  /**************************************************************************************/
    /****************************    PPM Sum Reciver    ***********************************/
      /* The following lines apply only for specific receiver with only one PPM sum signal, on digital PIN 2
         Select the right line depending on your radio brand. Feel free to modify the order in your PPM order is different */
      //#define SERIAL_SUM_PPM         PITCH,YAW,THROTTLE,ROLL,AUX1,AUX2,AUX3,AUX4 //For Graupner/Spektrum
      //#define SERIAL_SUM_PPM         ROLL,PITCH,THROTTLE,YAW,AUX1,AUX2,AUX3,AUX4 //For Robe/Hitec/Futaba
      #define SERIAL_SUM_PPM         PITCH,ROLL,THROTTLE,YAW,AUX1,AUX2,AUX3,AUX4 //For some Hitec/Sanwa/Others
      #define PPM_ON_THROTTLE

проверил работает.
ну както так...


Управление камерой по одной оси

gorbln:

Столкнулся с такой фигнёй:
Если включить управление подвесом - то каналы AUX3 и AUX4 - автоматом мапятся на поворот камеры по питчу и роллу соответственно. (вообще, на AIOP есть специальные пины под это дело, но они походу не используются). У меня на AUX3 висит переключение режимов. Соответственно, при щелчке переключателем камера поворачивается хрен-те-куда.
Мне это не понравилось, сделал вот такое решение, может быть кому-то окажется полезно:
config.h

 /*  Camstab pitch control only by one channel, uncomment only one option. Roll control is disabled.
       E.g. CAM_STAB_AUX4_ONLY means that signal from AUX4 used to control pitch of the gimbal and AUX3 is ignored.
       === affects Output.ino - Cam stabilize Sevos section === */
 //  #define CAM_STAB_AUX3_ONLY
   #define CAM_STAB_AUX4_ONLY

output.ino
сначала надо удалить кусок

S_PITCH = TILT_PITCH_MIDDLE + rcData[AUX3]-1500;
   S_ROLL  = TILT_ROLL_MIDDLE  + rcData[AUX4]-1500;

и потом добавить

#if defined(CAM_STAB_AUX3_ONLY)
    S_PITCH = TILT_PITCH_MIDDLE + rcData[AUX3]-1500;
    S_ROLL  = TILT_ROLL_MIDDLE;
  #endif
  #if defined(CAM_STAB_AUX4_ONLY)
    S_PITCH = TILT_PITCH_MIDDLE + rcData[AUX4]-1500;
    S_ROLL  = TILT_ROLL_MIDDLE;
  #endif
  #if !defined(CAM_STAB_AUX3_ONLY) && !defined(CAM_STAB_AUX4_ONLY)
   S_PITCH = TILT_PITCH_MIDDLE + rcData[AUX3]-1500;
   S_ROLL  = TILT_ROLL_MIDDLE  + rcData[AUX4]-1500;
  #endif
  • 1459