int main() { udp = initUDP(); start(); int status = 0; while (status == 0) { status = setCallback(&packet_handler); } return 0; }
int main (void) { int fd = initMW(); ThinkGearStreamParser ctx; initParser(&ctx); #ifdef OUTPUT_UDP initUDP(); #endif int res, i, n; unsigned char bytes[BUFSIZE]; while (1) { n = read (fd, bytes, BUFSIZE); // read up to BUFSIZE bytes from the device if (n > 0) { #ifdef __DEBUG fprintf (stderr, "%i bytes read\n", n); #endif for (i = 0; i < n; i++) { res = THINKGEAR_parseByte(&ctx, bytes[i]); if (res < 0) { fprintf (stderr, "error parsing byte: %i\n", res); initParser(&ctx); continue; } control(); // output robot control char } } else if (n < 0) { fprintf (stderr, "error %d reading %s: %s\n", errno, MINDWAVEPORT, strerror (errno)); return (1); } usleep ((n * 100) + 1000); // sleep approx 100 uS per char transmit + 1kuS } return (0); }
void extern init(lx_light_container_t *lightCollection) { initUDP(&broadcast_udp_socket, 1); initUDP(&unicast_udp_socket, 0); discover(lightCollection); getInfo(lightCollection); }
int main(int argc, char **argv) { //Register signal and signal handler signal(SIGINT, signal_callback_handler); //Init UDP with callbacks and pointer to run status initUDP( &UDP_Command_Handler, &UDP_Control_Handler, &Running ); print("Eddie starting...\r\n"); initIdentity(); double EncoderPos[2] = {0}; initEncoders( 183, 46, 45, 44 ); print("Encoders activated.\r\n"); imuinit(); print("IMU Started.\r\n"); float kalmanAngle; InitKalman(); #ifndef DISABLE_MOTORS print( "Starting motor driver (and resetting wireless) please be patient..\r\n" ); if ( motor_driver_enable() < 1 ) { print("Startup Failed; Error starting motor driver.\r\n"); motor_driver_disable(); return -1; } print("Motor Driver Started.\r\n"); #endif print("Eddie is starting the UDP network thread..\r\n"); pthread_create( &udplistenerThread, NULL, &udplistener_Thread, NULL ); print( "Eddie is Starting PID controllers\r\n" ); /*Set default PID values and init pitchPID controllers*/ pidP_P_GAIN = PIDP_P_GAIN; pidP_I_GAIN = PIDP_I_GAIN; pidP_D_GAIN = PIDP_D_GAIN; pidP_I_LIMIT = PIDP_I_LIMIT; pidP_EMA_SAMPLES = PIDP_EMA_SAMPLES; PIDinit( &pitchPID[0], &pidP_P_GAIN, &pidP_I_GAIN, &pidP_D_GAIN, &pidP_I_LIMIT, &pidP_EMA_SAMPLES ); PIDinit( &pitchPID[1], &pidP_P_GAIN, &pidP_I_GAIN, &pidP_D_GAIN, &pidP_I_LIMIT, &pidP_EMA_SAMPLES ); /*Set default values and init speedPID controllers*/ pidS_P_GAIN = PIDS_P_GAIN; pidS_I_GAIN = PIDS_I_GAIN; pidS_D_GAIN = PIDS_D_GAIN; pidS_I_LIMIT = PIDS_I_LIMIT; pidS_EMA_SAMPLES = PIDS_EMA_SAMPLES; PIDinit( &speedPID[0], &pidS_P_GAIN, &pidS_I_GAIN, &pidS_D_GAIN, &pidS_I_LIMIT, &pidS_EMA_SAMPLES ); PIDinit( &speedPID[1], &pidS_P_GAIN, &pidS_I_GAIN, &pidS_D_GAIN, &pidS_I_LIMIT, &pidS_EMA_SAMPLES ); //Get estimate of starting angle and specify complementary filter and kalman filter start angles getOrientation(); kalmanAngle = filteredPitch = i2cPitch; setkalmanangle( filteredPitch ); filteredRoll = i2cRoll; print( "Eddie startup complete. Hold me upright to begin\r\n" ); double gy_scale = 0.01; last_PID_ms = last_gy_ms = current_milliseconds(); while(Running) { GetEncoders( EncoderPos ); if( fabs(GetEncoder()) > 2000 && !inRunAwayState ) { print( "Help! I'm running and not moving.\r\n"); ResetEncoders(); inRunAwayState=1; } /*Read IMU and calculate rough angle estimates*/ getOrientation(); /*Calculate time since last IMU reading and determine gyro scale (dt)*/ gy_scale = ( current_milliseconds() - last_gy_ms ) / 1000.0f; last_gy_ms = current_milliseconds(); /*Complementary filters to smooth rough pitch and roll estimates*/ filteredPitch = 0.995 * ( filteredPitch + ( gy * gy_scale ) ) + ( 0.005 * i2cPitch ); filteredRoll = 0.98 * ( filteredRoll + ( gx * gy_scale ) ) + ( 0.02 * i2cRoll ); /*Kalman filter for most accurate pitch estimates*/ kalmanAngle = -getkalmanangle(filteredPitch, gy, gy_scale /*dt*/); /* Monitor angles to determine if Eddie has fallen too far... or if Eddie has been returned upright*/ if ( ( inRunAwayState || ( fabs( kalmanAngle ) > 50 || fabs( filteredRoll ) > 45 ) ) && !inFalloverState ) { #ifndef DISABLE_MOTORS motor_driver_standby(1); #endif inFalloverState = 1; print( "Help! I've fallen over and I can't get up =)\r\n"); } else if ( fabs( kalmanAngle ) < 10 && inFalloverState && fabs( filteredRoll ) < 20 ) { if ( ++inSteadyState == 100 ) { inRunAwayState = 0; inSteadyState = 0; #ifndef DISABLE_MOTORS motor_driver_standby(0); #endif inFalloverState = 0; print( "Thank you!\r\n" ); } } else { inSteadyState = 0; } if ( !inFalloverState ) { /* Drive operations */ smoothedDriveTrim = ( 0.99 * smoothedDriveTrim ) + ( 0.01 * driveTrim ); if( smoothedDriveTrim != 0 ) { EncoderAddPos(smoothedDriveTrim); //Alter encoder position to generate movement } /* Turn operations */ if( turnTrim != 0 ) { EncoderAddPos2( turnTrim, -turnTrim ); //Alter encoder positions to turn } double timenow = current_milliseconds(); speedPIDoutput[0] = PIDUpdate( 0, EncoderPos[0], timenow - last_PID_ms, &speedPID[0] );//Wheel Speed PIDs speedPIDoutput[1] = PIDUpdate( 0, EncoderPos[1], timenow - last_PID_ms, &speedPID[1] );//Wheel Speed PIDs pitchPIDoutput[0] = PIDUpdate( speedPIDoutput[0], kalmanAngle, timenow - last_PID_ms, &pitchPID[0] );//Pitch Angle PIDs pitchPIDoutput[1] = PIDUpdate( speedPIDoutput[1], kalmanAngle, timenow - last_PID_ms, &pitchPID[1] );//Pitch Angle PIDs last_PID_ms = timenow; //Limit PID output to +/-100 to match 100% motor throttle if ( pitchPIDoutput[0] > 100.0 ) pitchPIDoutput[0] = 100.0; if ( pitchPIDoutput[1] > 100.0 ) pitchPIDoutput[1] = 100.0; if ( pitchPIDoutput[0] < -100.0 ) pitchPIDoutput[0] = -100.0; if ( pitchPIDoutput[1] < -100.0 ) pitchPIDoutput[1] = -100.0; } else //We are inFalloverState { ResetEncoders(); pitchPID[0].accumulatedError = 0; pitchPID[1].accumulatedError = 0; speedPID[0].accumulatedError = 0; speedPID[1].accumulatedError = 0; driveTrim = 0; turnTrim = 0; } #ifndef DISABLE_MOTORS set_motor_speed_right( pitchPIDoutput[0] ); set_motor_speed_left( pitchPIDoutput[1] ); #endif if ( (!inFalloverState || outputto == UDP) && StreamData ) { print( "PIDout: %0.2f,%0.2f\tcompPitch: %6.2f kalPitch: %6.2f\tPe: %0.3f\tIe: %0.3f\tDe: %0.3f\tPe: %0.3f\tIe: %0.3f\tDe: %0.3f\r\n", speedPIDoutput[0], pitchPIDoutput[0], filteredPitch, kalmanAngle, pitchPID[0].error, pitchPID[0].accumulatedError, pitchPID[0].differentialError, speedPID[0].error, speedPID[0].accumulatedError, speedPID[0].differentialError ); } } //--while(Running) print( "Eddie is cleaning up...\r\n" ); CloseEncoder(); pthread_join(udplistenerThread, NULL); print( "UDP Thread Joined..\r\n" ); #ifndef DISABLE_MOTORS motor_driver_disable(); print( "Motor Driver Disabled..\r\n" ); #endif print( "Eddie cleanup complete. Good Bye!\r\n" ); return 0; }