Servo Pin Initialization Problems

This forum is dedicated to all issues and questions related to your individual setups and configurations
Post Reply
ZFreakyFlier
Posts: 4
Joined: Wed Feb 03, 2016 2:12 pm

Servo Pin Initialization Problems

Post by ZFreakyFlier »

I got a twin airplane that's been flying real good, however due to issues with modifying the code, I had to get the ailerons by through a Y cable, but now I want flaperons and the Y cable ain't gonna cut it anymore. After stumbling around the code for a good two months, I've found several quirks that's making this very frustrating.

To start, due to the design architecture of my flight controller, I had to have the escs occupy two different slots in order for the servos to be powered, I did this through modification of the def.h and output.ccp files. in def.h number motor was changed from 1 to 2, and output.ccp had servo[7] bound to motor[0] and [1]

Code: Select all

#elif defined(AIRPLANE)
  #if defined (USE_THROTTLESERVO)
    #define NUMBER_MOTOR   0
    #define PRI_SERVO_TO   8
  #else
    #define NUMBER_MOTOR   2
    #define PRI_SERVO_FROM 1
    #define PRI_SERVO_TO   8 

Code: Select all

  /*****************************               AIRPLANE                **************************************/
    // servo[7] is programmed with safty features to avoid motorstarts when ardu reset..
    // All other servos go to center at reset..  Half throttle can be dangerus
    // Only use servo[7] as motorcontrol if motor is used in the setup            */
    if (!f.ARMED) {
      servo[7] = MINCOMMAND; // Kill throttle when disarmed
     
    } else {
      servo[7] = constrain(rcCommand[THROTTLE], conf.minthrottle, MAXTHROTTLE);
   
    }
    motor[0] = servo[7];
    motor[1] = servo[7];

This gets pwm pins 3 and 5 to produce the signals for the escs, I'll probably add differential thrust later.

Now, the servos. Things start getting confusing pretty quickly, so, I had to shift all the default assignments around and dig in the def.h file so the new servos would be activated based on the aircraft type. After initial tests I've quickly found there's discrepancies in the pin assignments. In def.h there's a list of servo pins that get initialized that appears to make sense to other references and appears to be the first time the servos are initialized.

Code: Select all

  #define SERVO_1_PINMODE            pinMode(34,OUTPUT);pinMode(44,OUTPUT); // TILT_PITCH - WING left
  #define SERVO_1_PIN_HIGH           PORTC |= 1<<3;PORTL |= 1<<5;
  #define SERVO_1_PIN_LOW            PORTC &= ~(1<<3);PORTL &= ~(1<<5);
  #define SERVO_2_PINMODE            pinMode(35,OUTPUT);pinMode(45,OUTPUT); // TILT_ROLL  - WING right
  #define SERVO_2_PIN_HIGH           PORTC |= 1<<2;PORTL |= 1<<4;
  #define SERVO_2_PIN_LOW            PORTC &= ~(1<<2);PORTL &= ~(1<<4);
  #define SERVO_3_PINMODE            pinMode(33,OUTPUT); pinMode(46,OUTPUT); // CAM TRIG  - alt TILT_PITCH
  #define SERVO_3_PIN_HIGH           PORTC |= 1<<4;PORTL |= 1<<3;
  #define SERVO_3_PIN_LOW            PORTC &= ~(1<<4);PORTL &= ~(1<<3);
  #define SERVO_4_PINMODE            pinMode (37, OUTPUT);pinMode(7,OUTPUT); // new       - alt TILT_ROLL
  #define SERVO_4_PIN_HIGH           PORTC |= 1<<0; PORTH |= 1<<4;
  #define SERVO_4_PIN_LOW            PORTC &= ~(1<<0);PORTH &= ~(1<<4);

  #define SERVO_5_PINMODE            pinMode(6,OUTPUT);                      // BI LEFT
  #define SERVO_5_PIN_HIGH           PORTH |= 1<<3;
  #define SERVO_5_PIN_LOW            PORTH &= ~(1<<3);
  #define SERVO_6_PINMODE            pinMode(2,OUTPUT);                      // TRI REAR - BI RIGHT
  #define SERVO_6_PIN_HIGH           PORTE |= 1<<4;
  #define SERVO_6_PIN_LOW            PORTE &= ~(1<<4);
  #define SERVO_7_PINMODE            pinMode(5,OUTPUT);                      // new
  #define SERVO_7_PIN_HIGH           PORTE |= 1<<3;
  #define SERVO_7_PIN_LOW            PORTE &= ~(1<<3);
  #define SERVO_8_PINMODE            pinMode(3,OUTPUT);                      // new
  #define SERVO_8_PIN_HIGH           PORTE |= 1<<5;
  #define SERVO_8_PIN_LOW            PORTE &= ~(1<<5);

Following where pinmode is called again, goes to the output.cpp file where depending on the variables in def.h, servos would appear to get initialized based on the number needed.

Code: Select all

/**************************************************************************************/
/************                Initialize the PWM Servos               ******************/
/**************************************************************************************/
void initializeServo() {
  #if !defined(HW_PWM_SERVOS)
  // do pins init
    #if (PRI_SERVO_FROM == 1) || (SEC_SERVO_FROM == 1)
      SERVO_1_PINMODE;
    #endif
    #if (PRI_SERVO_FROM <= 2 && PRI_SERVO_TO >= 2) || (SEC_SERVO_FROM <= 2 && SEC_SERVO_TO >= 2)
      SERVO_2_PINMODE;
    #endif
    #if (PRI_SERVO_FROM <= 3 && PRI_SERVO_TO >= 3) || (SEC_SERVO_FROM <= 3 && SEC_SERVO_TO >= 3)
      SERVO_3_PINMODE;
    #endif
    #if (PRI_SERVO_FROM <= 4 && PRI_SERVO_TO >= 4) || (SEC_SERVO_FROM <= 4 && SEC_SERVO_TO >= 4)
      SERVO_4_PINMODE;
    #endif
    #if (PRI_SERVO_FROM <= 5 && PRI_SERVO_TO >= 5) || (SEC_SERVO_FROM <= 5 && SEC_SERVO_TO >= 5)
      SERVO_5_PINMODE;
    #endif
    #if (PRI_SERVO_FROM <= 6 && PRI_SERVO_TO >= 6) || (SEC_SERVO_FROM <= 6 && SEC_SERVO_TO >= 6)
      SERVO_6_PINMODE;
    #endif
    #if (PRI_SERVO_FROM <= 7 && PRI_SERVO_TO >= 7) || (SEC_SERVO_FROM <= 7 && SEC_SERVO_TO >= 7)
      SERVO_7_PINMODE;
    #endif
    #if (PRI_SERVO_FROM <= 8 && PRI_SERVO_TO >= 8) || (SEC_SERVO_FROM <= 8 && SEC_SERVO_TO >= 8)
      SERVO_8_PINMODE;
    #endif
  #endif

Further down the line there's more sections where pwm and timer parameters are defined, but none of them are influenced by the aircraft type. So to continue, immediately after that the mix tables come up, where I changed the servo assignment for the control surfaces.

Code: Select all

      // Assisted modes (gyro only or gyro+acc according to AUX configuration in Gui
      servo[3] = axisPID[ROLL] + flapperons[0];   //   Wing 1
      servo[6] = axisPID[ROLL] + flapperons[1];   //   Wing 2
      servo[5] = axisPID[YAW];                    //   Rudder
      servo[4] = axisPID[PITCH];                  //   Elevator

servo[3] outputs to pwm 7 and 37,
servo[6] is nowhere to be found,
servo[5] outputs to pwm 6
and servo[4] outputs to pwm 2
Frustration being a good motivator, I scoured the other pins 34,35,36,44,45,46 and they all produce a signal but none of them are effected by changing the working servo assignments. 37 however is an oddball cause it coppies servo[3] on pin 7, which would make sense if it did that for servo[4]. Now, somewhere in the code these values are being flipped around, I'm at the end of my rope trying to solve this mystery to get the other pins to work, I need help, and suggestions would be appreciated, plz :(

Post Reply