Saturday, May 18, 2013

23. Switch-out from Auto-Pilot Mode : Another function for #UAV

In our previous programming segment (16. Auto Take-Off and Auto-Landing programming of the #UAV and 6. How are we going to build a more stable Loiter program? - The Idea.) we had made Auto-Pilot program and also an Auto-take off and Auto-landing program for our U.A.V.

Then we thought more. What if due to some reason we want our U.A.V to move out of the Auto-Pilot mode towards the next desired waypoint (like sometimes we may want a quick auto-landing or surveillance of some other area)?. Hence we came up with another addition to the whole program we had made so far.

We decided to use one of the 2 output channels left (rest 5 out total 7 are used for Aileron, Throttle, rudder, Elevator and Mode) of the UDB Devboard to receive a signal from our transmitter so that whenever we change the position of the switch from its initial position (at start-up) i.e. from up to down or down to up, our  DevBoard will switch out of the Auto-Pilot mode.

So in order form a logic, we first tried a simple C program in which if we press any letter different from the one we have put in the memory (through scanf function), then it will display a certain message and if we press the same letter as in the memory then another certain message will appear:


#include <stdio.h>
#include <conio.h>

int main()

{
char in, oc;
in = 'j';
printf("Testing code");
while(1)
{
          printf("input pls");
          oc=getch(); // so that we do not have to press enter every-time we enter something on screen
          //scanf("%c", &oc);
          //printf("yes wrkin");
          if (oc!=in)
             {
                     printf("Matched");
                    if ( (oc == 'j')||(oc == 'h'))
                       {
                                printf("moved to next waypoint");
                                in = oc;
                       }
             }
}
   getch();
   return 0;
}

To implement this idea we went into the servoMix.c file of our program and edited the following:

static int mychannelvalue =0;
static char startflag =0; // will be used to check position of switch at sart-up only once
void startupfuntion(void); //to store the current position of the switch
void checkmode (void); // to check the position of the switch, if changed then switch-out of Auto-Pilot mode
static int currentvalue =0;

// Helicopter airframe
// Mix half of roll_control and half of pitch_control into aileron channels
// Mix full pitch_control into elevator
// Ignore waggle for now
#if ( AIRFRAME_TYPE == AIRFRAME_HELI )
temp = pwManual[AILERON_INPUT_CHANNEL] +
REVERSE_IF_NEEDED(AILERON_CHANNEL_REVERSED, roll_control/2 +

pitch_control/2) ;
udb_pwOut[AILERON_OUTPUT_CHANNEL] = udb_servo_pulsesat( temp ) ;

temp = pwManual[ELEVATOR_INPUT_CHANNEL] +

REVERSE_IF_NEEDED(ELEVATOR_CHANNEL_REVERSED, pitch_control) ;
udb_pwOut[ELEVATOR_OUTPUT_CHANNEL] = udb_servo_pulsesat( temp ) ;

temp = pwManual[AILERON_SECONDARY_OUTPUT_CHANNEL] +
REVERSE_IF_NEEDED(AILERON_SECONDARY_CHANNEL_REVERSED,

-roll_control/2 + pitch_control/2) ;
udb_pwOut[AILERON_SECONDARY_OUTPUT_CHANNEL] = temp ;

temp = pwManual[RUDDER_INPUT_CHANNEL] /*+

REVERSE_IF_NEEDED(RUDDER_CHANNEL_REVERSED, yaw_control)*/ ;
udb_pwOut[RUDDER_OUTPUT_CHANNEL] = udb_servo_pulsesat( temp ) ;

if ( pwManual[THROTTLE_INPUT_CHANNEL] == 0 )
{
udb_pwOut[THROTTLE_OUTPUT_CHANNEL] = 0 ;
}
else
{
temp = pwManual[THROTTLE_INPUT_CHANNEL] +

REVERSE_IF_NEEDED(THROTTLE_CHANNEL_REVERSED, throttle_control) ;
udb_pwOut[THROTTLE_OUTPUT_CHANNEL] = udb_servo_pulsesat( temp ) ;
}
#endif
mychannelvalue = udb_servo_pulsesat( pwManual[PASSTHROUGH_A_INPUT_CHANNEL] )

;

startupfuntion();
checkmode();
// next_waypoint();      

udb_pwOut[PASSTHROUGH_A_OUTPUT_CHANNEL] = udb_servo_pulsesat(

pwManual[PASSTHROUGH_A_INPUT_CHANNEL] ) ;
udb_pwOut[PASSTHROUGH_B_OUTPUT_CHANNEL] = udb_servo_pulsesat(

pwManual[PASSTHROUGH_B_INPUT_CHANNEL] ) ;
udb_pwOut[PASSTHROUGH_C_OUTPUT_CHANNEL] = udb_servo_pulsesat(

pwManual[PASSTHROUGH_C_INPUT_CHANNEL] ) ;
udb_pwOut[PASSTHROUGH_D_OUTPUT_CHANNEL] = udb_servo_pulsesat(

pwManual[PASSTHROUGH_D_INPUT_CHANNEL] ) ;
}

void cameraServoMix( void )
{
int32_t temp ;
int16_t pwManual[NUM_INPUTS+1] ;

// If radio is off, use udb_pwTrim values instead of the udb_pwIn values
for (temp = 0; temp <= NUM_INPUTS; temp++)
if (udb_flags._.radio_on)
pwManual[temp] = udb_pwIn[temp];
else
pwManual[temp] = udb_pwTrim[temp];

temp = ( pwManual[CAMERA_PITCH_INPUT_CHANNEL] - 3000 ) +

REVERSE_IF_NEEDED(CAMERA_PITCH_CHANNEL_REVERSED,
cam_pitch_servo_pwm_delta ) ;
temp = cam_pitchServoLimit(temp) ;
udb_pwOut[CAMERA_PITCH_OUTPUT_CHANNEL] = udb_servo_pulsesat( temp + 3000 ) ;

temp = ( pwManual[CAMERA_YAW_INPUT_CHANNEL] - 3000 ) +

REVERSE_IF_NEEDED(CAMERA_YAW_CHANNEL_REVERSED,
cam_yaw_servo_pwm_delta ) ;
temp = cam_yawServoLimit(temp) ;
udb_pwOut[CAMERA_YAW_OUTPUT_CHANNEL] = udb_servo_pulsesat( temp + 3000 ) ;
}

void startupfuntion(void)
{
if (startflag == 0)
{
startflag =1;
currentvalue = mychannelvalue;
}
}

void checkmode(void)
{
int diff;
diff = mychannelvalue-currentvalue;
 if(diff>100 || diff<-100)
{
             if (flags._.GPS_steering == 1 && flags._.pitch_feedback == 1 && udb_flags._.radio_on == 1) //to check if in Auto-Pilot mode, else will never go for the function, make sure only Auto-Pilot switch-out
            {
 next_waypoint();
                           currentvalue = mychannelvalue;
}
}
}

22. Tip2 for #UAV

Always debug (i.e. check for values in a particular part of the program) your program in a PIC controller testing kit with MPLab 8.9, because UDB4 Devboard does not provide the facility to debug, i.e it can't be debugged with PICKit 2. This will help you as you will discover in the next post on this blog. (Wink! Wink!)
  1. You may double click on the left hand side of the line where you want to debug. A letter 'B' in red circle will appear at that point. Change the mode of the MPLab setup to Debug (originally its Release). 
  2. After the changes above you may build your program.
  3. Connect the PICKit 2 with the testing board and program it.
  4. Next go to View - Locals. A window will appear which will show you values at the breakpoints set by you every time you Run the debugging.



Wednesday, May 15, 2013

21. Tip1 for #UAV

Tip: After making all the changes to the hardware of the fuselage according to your requirements, do check the Center of Gravity of the whole plane.

Monday, May 13, 2013

19. Coordinating hardware with our program

We went into the options.h file of Matrix-Pilot UDB4 and did the following changes:

(Where left columns is from the receiver and the right column on the devboard)

// Configure Input and Output Channels
//
// For classic UDB boards:
// Use a single PPM input connection from the RC receiver to the UDB on RC input channel 4.
// This frees up RC inputs 3, 2, and 1 to act as RC outputs 4, 5, and 6.
// If PPM_ALT_OUTPUT_PINS is set to 0, the 9 available RC outputs will be sent to the
// following pins, in this order: Out1, Out2, Out3, In3, In2, In1, RE0, RE2, RE4.
// With it set to 1, the RC outputs will be in this alternate configuration:
// Out1, Out2, Out3, RE0, RE2, RE4, In3, In2, In1.
//
// For UDB4 boards:
// Use a single PPM input connection from the RC receiver to the UDB on RC input channel 1.
// The 8 standard output channels remain unaffected.  2 additional output channels are available
// on pins RA4 and RA1.
//
// For all boards:
// If you're not sure, leave USE_PPM_INPUT set to 0.
// PPM_NUMBER_OF_CHANNELS is the number of channels sent on the PWM signal.  This is
// often different from the NUM_INPUTS value below, and should usually be left at 8.
//
#define USE_PPM_INPUT 0
#define PPM_NUMBER_OF_CHANNELS 8
#define PPM_SIGNAL_INVERTED 0
#define PPM_ALT_OUTPUT_PINS 0

// NUM_INPUTS:
// For classic boards: Set to 1-5 (or 1-8 when using PPM input)
//   1-4 enables only the first 1-4 of the 4 standard input channels
//   5 also enables E8 as the 5th input channel
// For UDB4 boards: Set to 1-8
#define NUM_INPUTS 6

// Channel numbers for each input.
// Use as is, or edit to match your setup.
//   - If you're set up to use Rudder Navigation (like MatrixNav), then you may want to swap
//     the aileron and rudder channels so that rudder is CHANNEL_1, and aileron is 5.
#define THROTTLE_INPUT_CHANNEL CHANNEL_1
#define AILERON_INPUT_CHANNEL CHANNEL_2
#define ELEVATOR_INPUT_CHANNEL CHANNEL_3
#define RUDDER_INPUT_CHANNEL CHANNEL_4
#define MODE_SWITCH_INPUT_CHANNEL CHANNEL_6
#define CAMERA_PITCH_INPUT_CHANNEL CHANNEL_UNUSED
#define CAMERA_YAW_INPUT_CHANNEL CHANNEL_UNUSED
#define CAMERA_MODE_INPUT_CHANNEL CHANNEL_UNUSED
#define OSD_MODE_SWITCH_INPUT_CHANNEL        CHANNEL_UNUSED
#define PASSTHROUGH_A_INPUT_CHANNEL CHANNEL_5
#define PASSTHROUGH_B_INPUT_CHANNEL CHANNEL_UNUSED
#define PASSTHROUGH_C_INPUT_CHANNEL CHANNEL_UNUSED
#define PASSTHROUGH_D_INPUT_CHANNEL CHANNEL_UNUSED

// NUM_OUTPUTS:
// For classic boards: Set to 3, 4, 5, or 6
//   3 enables only the standard 3 output channels
//   4 also enables E0 as the 4th output channel
//   5 also enables E2 as the 5th output channel
//   6 also enables E4 as the 6th output channel
//   NOTE: If USE_PPM_INPUT is enabled above, up to 9 outputs are available.)
// For UDB4 boards: Set to 3-8 (or up to 10 using pins RA4 and RA1.)
#define NUM_OUTPUTS 5

// Channel numbers for each output
// Use as is, or edit to match your setup.
//   - Only assign each channel to one output purpose
//   - If you don't want to use an output channel, set it to CHANNEL_UNUSED
//   - If you're set up to use Rudder Navigation (like MatrixNav), then you may want to swap
//     the aileron and runner channels so that rudder is CHANNEL_1, and aileron is 5.
//
// NOTE: If your board is powered from your ESC through the throttle cable, make sure to
// connect THROTTLE_OUTPUT_CHANNEL to one of the built-in Outputs (1, 2, or 3) to make
// sure your board gets power.
//
#define THROTTLE_OUTPUT_CHANNEL CHANNEL_1
#define AILERON_OUTPUT_CHANNEL CHANNEL_2
#define ELEVATOR_OUTPUT_CHANNEL CHANNEL_3
#define RUDDER_OUTPUT_CHANNEL CHANNEL_5
#define AILERON_SECONDARY_OUTPUT_CHANNEL        CHANNEL_UNUSED
#define CAMERA_PITCH_OUTPUT_CHANNEL CHANNEL_UNUSED
#define CAMERA_YAW_OUTPUT_CHANNEL CHANNEL_UNUSED
#define TRIGGER_OUTPUT_CHANNEL CHANNEL_UNUSED
#define PASSTHROUGH_A_OUTPUT_CHANNEL CHANNEL_4
#define PASSTHROUGH_B_OUTPUT_CHANNEL CHANNEL_UNUSED
#define PASSTHROUGH_C_OUTPUT_CHANNEL CHANNEL_UNUSED
#define PASSTHROUGH_D_OUTPUT_CHANNEL CHANNEL_UNUSED

Next we soldered four channel cables with our DevBoard and by attaching each cable with a servo motor  ( while attaching another to a power supply) we checked whether our transmitter was working as we programmed or not. The four channels (Throttle, Aileron, Rudder and Elevator) were working just fine.



Thursday, May 9, 2013

18. More additions to our UDB4 Dev Board

Below is our Dev Board with 3DR G.P.S. MTK V2.0: 

 

Here in the picture below we have added/soldered 7 female (can be seen on the left side of the board) burst pins so that our receiver can be directly connected to the board of our Auto-Pilot (nearly burned my fingers while soldering the burst pins on the board!!! lols!):


The following changes we are making in the head of the fuselage, in order to place our whole Auto-Pilot with G.P.S.Setup in here:








Monday, May 6, 2013

17. UDB4 DevBoard arrived - New Features n Additions

Our UDB4 Devboard arrived today. It has the following features:
  1. Compatible with 20-channel EM-406A SiRF III GPS
  2. Compatible with 50-channel GS407 Helical GPS
  3. DSPIC33FJ256 Controller (with onboard 3.3V and 5V glue logic)
  4. DSPIC runs at 120MHz with 8MHz resonator and PLL
  5. MMA7361 three axis accelerometer
  6. IDG500 dual axis gyro and ISZ500 single axis gyro
  7. External 256Kbit EEPROM
  8. Up to 8 Input, 8 output PWM points
  9. 6-wire debug header or ICSP header
  10. 4 separate colored status LEDs
  11. On board 3.3V and 5V regulators (150mA max)
  12. Spare USART connection for debugging, flight logging, wireless telemetry, etc.
  13. 30 spare analog and digital I/O pins for debugging and interfacing to sensors
We added a slot (covering UART RX2, TX2 and GND) to transmit our data for telemetry and another for programming the micro-controller through PIC-Kit 2. You can install the version of PIC-Kit 2 (2.61) and replace a file in it if you already have one and do not wish to use PIC_Kit 3. You may find the necessary software and other stuff for this purpose at the google devboard discussion forum - Software and Replacement File.


For providing power supply to the UDB4 DevBoard we will use our previously made supplier (9 Volt Adapter and 7805 voltage regulator along with 100 micro-farad capacitor). 
For UD4 DevBoard we will open MatrixPilot-udb4 program in MPLab IDE software. One of the majore differences here is that the serial output format is defined as: #define SERIAL_OUTPUT_FORMAT SERIAL_MAVLINK and the type of board is defined as: #define BOARD_TYPE UDB4_BOARD.