This code is a good simple baseline for anyone wanting to control three thrusters with ESC's over RS485 with a single 24awg twisted pair using a ps2 controller.
It's a simplified version of techmonkey's code. Thanks Hamish.
And thanks to Bill Porter for the libraries.
I cut out Hamish's sensor data as I do that with a seperate minimosd video overlay board.
and I only send data to the rov using the arduino's so comms are one way.
I also only have one vertical thruster so I cut out the code one for his two verticals.
And my vertical ESC is a one way one for a quadcopter so has down thrust only.
I'll need to re-code when I get a bi-directional ESC.
top side-(controller)
Code: Select all
/*
Simplified version for MiniRay by Bigbadbob, Jan 2020.
Based on ROVPS2Control_Masterv8.ino
by Hamish Trolove
http://www.techmonkeybusiness.com
This sketch takes control commands from a PS2 handset and transmits the
commands using Bill Porter's EasyTransfer Library over a 9600 baud serial
link (100m tether).
This sketch is designed for an Arduino Nano with only one Serial Port.
Pin assignments are:
3.3V output to PS2 red Pin
gnd connection for PS2 Black Pin
Pin D10 to PS2 yellow pin (chip select)
Pin D11 to PS2 orange pin (Mosi)
Pin D12 to PS2 brown pin (Miso)
Pin D13 to PS2 blue pin (clock)
Communications
Serial Connection: Topside D1 (TX) to ROV D0 (RX)
Serial Connection: Topside D0 (RX) to ROV D1 (TX)
Connect the GND on both
Or use RS485 converter boards.
The coding pulls on the PSX library developed by Bill Porter.
See http://www.billporter.info for the latest from Bill Porter and to
download the library.
The controls for the ROV are;
Left Stick - Y-axis, fwd=down
Right Stick - X-axis = Yaw, Y-axis = forward/back
*/
#include <PS2X_lib.h> // Bill Porter's PS2 Library
#include <EasyTransfer.h> // Bill Porter's Easy Transfer Library
PS2X ps2x; //The PS2 Controller Class
EasyTransfer ETin, ETout; //Create the two Easy transfer Objects for two way communication
int ForwardVal = 0; //Value read off the PS2 Right Stick up/down.
int YawLeftVal = 0; //Value read off the PS2 Right Stick left/right
int UpVal = 0; //Value read off the PS2 Left Stick up/down
struct SEND_DATA_STRUCTURE{
int Vraw; //Variables to carry the actual raw data for the ESCs
int HLraw;
int HRraw;
};
SEND_DATA_STRUCTURE txdata;
void setup()
{
ps2x.config_gamepad(13,11,10,12, false, false);
//setup pins and settings: GamePad(clock, command, attention, data, Pressures?, Rumble?)
//We have disabled the pressure sensitivity and rumble in this instance and
//we know the controller type so we have not bothered with the error checks
delay(4500); //The 4.5 second delay to allow thruster calibration in slave and prevent a comms clash.
Serial.begin(9600); //Begin Serial to talk to the Slave Arduino
ETout.begin(details(txdata), &Serial);//Get the Easy Transfer Library happening through the Serial
}
void loop()
{
ps2x.read_gamepad(); //This needs to be called at least once a second to get data from the controller.
// now read the stick values
ForwardVal = ps2x.Analog(PSS_RY);
YawLeftVal = ps2x.Analog(PSS_RX);
UpVal = ps2x.Analog(PSS_LY);
//and do the yaw maths
txdata.HLraw = -(128-ForwardVal)+(128-YawLeftVal); //This will be up to a value of 256
txdata.HRraw = -(128-ForwardVal)-(128-YawLeftVal); //This will be up to a value of 256
txdata.Vraw = UpVal; //This will be up to a value of 256. no Roll maths needed as I only have one vertical thruster.
//Scale the values to be suitable for ESCs
// These values will be able to be written directly to the ESCs
txdata.Vraw=map(txdata.Vraw,128,0,0,179); //128 from ps2 = 90 to ESC //vert is down only remember.
txdata.HLraw=map(txdata.HLraw,-256,256,0,179);
txdata.HRraw=map(txdata.HRraw,-256,256,0,179);
ETout.sendData();// send the ESC commands.
delay(100);
}
And here's the ROV code-
Code: Select all
/*
Slave receiver for MiniRay ROV by Bigbadbob, jan 2020
based on code by Hamish Trolove
http://www.techmonkeybusiness.com
This sketch takes commands sent to it from the Master unit with
the PS2 Controller attached and converts it to motor ESC commands,
The data is sent fromthe controller (Master) to the ROV(Slave) using Bill Porter's EasyTransfer
Library over a 9600 baud serial link (100m tether).
Data sent from the Master are raw settings for the ESC control.
This sketch is designed for an Arduino Nano with only one Serial Port.
The pin assignments are;
D9 = ESC Horizontal Right (stbd)
D10 = ESC Horizontal Left (port)
D11 = ESC Vertical
Communications
Serial Connection: Topside D1 (TX) to ROV D0 (RX)
Serial Connection: Topside D0 (RX) to ROV D1 (TX)
Connect the GND on both
or connect via ttL serial to RS485 converter
Please note that the ESCs will all have been programmed by this
point in the project.
*/
#include <Servo.h>
#include <EasyTransfer.h> // Bill Porter's Easy Transfer Library
EasyTransfer ETin, ETout; //Create the Easy transfer Object for
// two way communication
Servo ESCV; // Create Servo Object ESC Vertical
Servo ESCHL; // Create Servo Object ESC Horizontal Left
Servo ESCHR; // Create Servo Object ESC Horizontal Right
struct RECEIVE_DATA_STRUCTURE{
int Vraw; //Variables to carry the actual raw data for the ESCs
int HLraw;
int HRraw;
};
//give a name to the group of data
RECEIVE_DATA_STRUCTURE rxdata;
void setup()
{
ESCV.attach(11,600,2250); //attach the ESCV to pin 11
ESCHL.attach(10,600,2250); //attach the ESCHL to pin 10
ESCHR.attach(9,600,2250); //attach the ESCHR to pin 9
//Due to problems with the ESC recognising the maximum
//position at the default settings, the figures after
//the pin number are the microsecond signals for the
//minimum and maximum that the ESC will recognise.
// 600 and 2250 work.
//calibrate ESC's
//0=min,90=neutral,180=max
ESCV.write(180); //set vertical throttle to max for calibration.
ESCHL.write(180); //Set the LEFT throttle to the max position.
ESCHR.write(180); //Set the RIGHT throttle to the max position.
delay(2000);
ESCV.write(0); //set the vertical throttle to the min position
ESCHL.write(0); //Set the left throttle to the min position.
ESCHR.write(0); //Set the RIGHT throttle to the min position
delay(2000);
Serial.begin(9600); //Begin Serial to talk to the Master Arduino
ETin.begin(details(rxdata), &Serial); //Get the Easy Transfer Library happening through the Serial
}
void loop()
{
ETin.receiveData();
ESCV.write(rxdata.Vraw); //Set the ESCVR signal to the defined throttle position.
ESCHL.write(rxdata.HLraw); //Set the ESCHL signal to the defined throttle position.
ESCHR.write(rxdata.HRraw); //Set the ESCHR signal to the defined throttle position.
}
This code now tested and working on the bench. happy days.