Tractor PPM controller

This commit is contained in:
produktr 2018-04-06 15:20:57 +02:00
commit 403d6f4aff

136
Tractor_ppm.ino Normal file
View File

@ -0,0 +1,136 @@
/* [channel out pins]
* | action | pin | port | Binary | Byte | Range | TIMER | OCR
* |------------|-------|-----------|-----------|-------|-----------|-----------|---
* | forward pwm| 3 | PORTD | B00001000 | 8 | 1000-2000 | TIMER2B | OCR2B
* | reverse pwm| 5 | PORTD | B00100000 | 32 | 1000-2000 | TIMER0B | OCR0B
* | left pwm | 6 | PORTD | B01000000 | 64 | 1550-2000 | TIMER0A | OCR0A
* | right pwm | 9 | PORTB | B00000010 | 2 | 1000-1450 | TIMER1A | OCR1A
* | camera pwm | 10 | PORTB | B00000100 | 4 | 1000-2000 | TIMER1B | OCR1B
* | hitch | 12 | PORTB | B00010000 | 16 | 1500-2000 | - | -
* | lights | 11 | PORTB | B00001000 | 8 | 1500-2000 | TIMER2A | OCR2A
*
* I think (unchecked) the servo library is going to mess with the timer1 duty cycle when attached
*/
#include <PPMReader.h>
//#include <Servo.h>
// ppm receive settings
#define PPM_PIN 2
#define PPM_CHANNELS 6
// ppm channel numbers
#define STEERING 1
#define THROTTLE 3
#define CAMERA 4
#define HITCH 5
#define DIRECTION 6
#define LIGHTS 7
// output pin numbers
#define P_THR_F 3 // on problems move to 13
#define P_THR_R 5
#define P_STE_L 6
#define P_STE_R 9 // was 11
#define P_CAMER 10
#define P_HITCH 12
#define P_LIGHT 11 // was 13
// bytes
#define B_THR_F 8
#define B_THR_R 32
#define B_STE_L 64
#define B_STE_R 2
#define B_CAMER 4
#define B_HITCH 16
#define B_LIGHT 8
// camera servo out
//Servo servoCamera;
// Attach PPM input
PPMReader ppm(PPM_PIN, PPM_CHANNELS);
void setup(){
Serial.begin(9600);
Serial.println("Tractor");
// SET OUTPUTS
// PORTD 0-7
DDRD = DDRD | B01101000;
// PORTB 8-13
DDRB = DDRB | B00011110;
// servoCamera.attach(P_CAMER);
// WRITE TO PWM PINS (ONCE)
analogWrite(P_THR_F, 0);
analogWrite(P_THR_R, 0);
analogWrite(P_STE_L, 0);
analogWrite(P_STE_R, 0);
analogWrite(P_CAMER, 0);
analogWrite(P_LIGHT, 0);
}
void loop(){
/* SET VALUES */
static uint16_t unThrottleIn;
static uint16_t unSteeringIn;
static uint16_t unHitchIn;
static uint16_t unDirectionIn;
static uint16_t unCameraIn;
unThrottleIn = ppm.latestValidChannelValue(THROTTLE, 1000);
unSteeringIn = ppm.latestValidChannelValue(STEERING, 1500);
unCameraIn = ppm.latestValidChannelValue(CAMERA, 1500);
unHitchIn = ppm.latestValidChannelValue(HITCH, 2000);
unDirectionIn = ppm.latestValidChannelValue(DIRECTION, 2000);
unLightsIn = ppm.latestValidChannelValue(LIGHTS, 1500);
/* THROTTLE */
if(unThrottleIn < 1020){
// no throttle
OCR0B = 0;
OCR2B = 0;
}else{
if(unDirectionIn < 1750){
// forward
OCR0B = 0;
OCR2B = map(unThrottleIn, 1000, 2000, 0, 255);
}else{
// reverse
OCR2B = 0;
OCR0B = map(unThrottleIn, 1000, 2000, 0, 255);
}
}
/* STEERING */
if(unSteeringIn < 1450){
// go right
OCR0A = 0;
OCR1A = map(unSteeringIn, 1000, 1450, 255, 0);
}else if(unSteeringIn > 1550){
// go left
OCR1A = 0;
OCR0A = map(unSteeringIn, 1550, 2000, 0, 255);
}else{
// no steer (1450..1550)
OCR0A = 0;
OCR1A = 0;
}
/* TRAILER HITCH */
if(unHitchIn < 1750){
// hitch active
PORTB |= B_HITCH;
}else{
// hitch unactive
PORTB &= ~B_HITCH;
}
/* LIGHTS */
OCR2A = map(unSteeringIn, (1000, 2000, 0, 255);
/* CAMERA */
// servoCamera.writeMicroseconds(unCameraIn);
}