-
Posts
1775 -
Joined
-
Last visited
-
Days Won
1
Content Type
Profiles
Forums
Events
Everything posted by Hansolo
-
IFF C-6280 running with DCS-BIOS Thanks DM. Well got the RS485 issue solved. Turned out to be a batch of bad chips. Made a test setup and they got really hot. Once I found a healthy chip the Mega ran without any issue as a Slave unit. Still haven’t figured out how to get the TACAN channels as Integer as I have been busy on other tasks. IFF C-6280 A long time ago I managed to get myself an original IFF C-6280A. Using the code Ian made for GSS Rain for the channel selection and it worked beautifully. Thanks a lot, saved me a bunch of headaches. The rotaries I re-used by comparison code I made for the TACAN. This time there are no issues with using the exported rotaries positions as each position is unique. I did find two small things. 1. The actual light for the Reply and Test aren’t exported. Only the push to test status is. Looking at the DCS-BIOS code it may just need following added; defineIndicatorLight("IFF_REPLY", 798, "IFF", "REPLY") defineIndicatorLight("IFF_REPLY", 799, "IFF", "TEST") I have writtin Ian to see if it’s possible to do locally or it will have to be done the main DCS-BIOS in order to work. As can be seen on the YT the lights only come on when the lamps are being pushed, not when the actual test is used. 2. The ‘Mode 4 Audio-Out-Light' on the A-10C IFF seems to move less than it should. When toggling the original panel SOCAT does report 0-1-2 for the positions however in-game the toggle doesn’t move sufficient. It’s like the command is insuffient, 1:24. When toggling directly in pit it all works and the Reply light also comes on. My current code; /* The following #define tells DCS-BIOS that this is a RS-485 slave device. It also sets the address of this slave device. The slave address should be between 1 and 126 and must be unique among all devices on the same bus. */ #define DCSBIOS_RS485_SLAVE 20 /* The Arduino pin that is connected to the /RE and DE pins on the RS-485 transceiver. */ #define TXENABLE_PIN 2 #include "DcsBios.h" #include <timer.h> Timer tm; int Master_mode_ingame; // hold value from DCS int Code_dial_ingame; // hold value from DCS namespace DcsBios { class SwitchMultiPosBCD : PollingInput { private: const char* msg_; const byte* pins_; char numberOfPins_; char lastState_; char readState() { unsigned char i; unsigned char state = 0; for (i=0; i<numberOfPins_; i++) { unsigned char j = numberOfPins_ - i - 1; state |= ((digitalRead(pins_[i]) ^ 1) << j); // before state |= (digitalRead(pins_[i]) << j); } return state; } void pollInput() { char state = readState(); if (state != lastState_) { char buf[7]; utoa(state, buf, 10); if (tryToSendDcsBiosMessage(msg_, buf)) lastState_ = state; } } public: SwitchMultiPosBCD(const char* msg, const byte* pins, char numberOfPins) : lastState_(0) { msg_ = msg; pins_ = pins; numberOfPins_ = numberOfPins; unsigned char i; for (i=0; i<numberOfPins; i++) { pinMode(pins[i], INPUT_PULLUP); } lastState_ = readState(); } }; } //Mode-1 Wheel 1 const byte iffMode1Wheel1Pins[3] = {44, 45, 46}; DcsBios::SwitchMultiPosBCD iffMode1Wheel1("IFF_MODE1_WHEEL1", iffMode1Wheel1Pins, 3); //Mode-1 Wheel 2 const byte iffMode1Wheel2Pins[2] = {42, 43}; DcsBios::SwitchMultiPosBCD iffMode1Wheel2("IFF_MODE1_WHEEL2", iffMode1Wheel2Pins, 2); //Mode-3A Wheel 1 const byte iffMode3aWheel1Pins[3] = {14, 15, 16}; DcsBios::SwitchMultiPosBCD iffMode3aWheel1("IFF_MODE3A_WHEEL1", iffMode3aWheel1Pins, 3); //Mode-3A Wheel 2 const byte iffMode3aWheel2Pins[3] = {9, 10, 11}; DcsBios::SwitchMultiPosBCD iffMode3aWheel2("IFF_MODE3A_WHEEL2", iffMode3aWheel2Pins, 3); //Mode-3A Wheel 3 const byte iffMode3aWheel3Pins[3] = {6, 7, 8}; DcsBios::SwitchMultiPosBCD iffMode3aWheel3("IFF_MODE3A_WHEEL3", iffMode3aWheel3Pins, 3); //Mode-3A Wheel 4 const byte iffMode3aWheel4Pins[3] = {3, 4, 5}; DcsBios::SwitchMultiPosBCD iffMode3aWheel4("IFF_MODE3A_WHEEL4", iffMode3aWheel4Pins, 3); //RAD Mic/Ident DcsBios::Switch3Pos iffMicIdent("IFF_MIC_IDENT", 47, 48); //RAD Test/Mon DcsBios::Switch3Pos iffRadtest("IFF_RADTEST", 49, 50); //Test M-1 const byte iffTestM1Pins[3] = {A6, A7, A8}; DcsBios::SwitchMultiPos iffTestM1("IFF_TEST_M1", iffTestM1Pins, 3); //Test M-2 const byte iffTestM2Pins[3] = {A9, A10, A11}; DcsBios::SwitchMultiPos iffTestM2("IFF_TEST_M2", iffTestM2Pins, 3); //Test M-3 const byte iffTestM3Pins[3] = {A12, A13, A14}; DcsBios::SwitchMultiPos iffTestM3("IFF_TEST_M3", iffTestM3Pins, 3); //Test M-4 const byte iffTestM4Pins[3] = {51, 52, 53}; DcsBios::SwitchMultiPos iffTestM4("IFF_TEST_M4", iffTestM4Pins, 3); //IFF On/Out const byte iffOnOutPins[2] = {A0, A1}; DcsBios::SwitchMultiPos iffOnOut("IFF_ON_OUT", iffOnOutPins, 2); //IFF Out: LIGHT - OFF - AUDIO DcsBios::Switch3Pos iffOutAudioLight("IFF_OUT_AUDIO_LIGHT", A4, A5); //IFF Master: OFF - STBY - LOW - NORM - EMER void onIffMasterChange(unsigned int newValue_Master) { Master_mode_ingame = newValue_Master; } DcsBios::IntegerBuffer iffMasterBuffer(0x111e, 0xe000, 13, onIffMasterChange); //IFF Code: ZERO - B - A - (HOLD) void onIffCodeChange(unsigned int newValue_Code) { Code_dial_ingame = newValue_Code; } DcsBios::IntegerBuffer iffCodeBuffer(0x111a, 0xc000, 14, onIffCodeChange); //Not correct //REPLY DcsBios::LED iffReplyTest(0x1128, 0x8000, 13); //TEST DcsBios::LED iffTestTest(0x112a, 0x0040, 12); void setup() { DcsBios::setup(); //Master mode inputs DDRA = B00000000; // set PINA (digital 29-22) as inputs PORTA = B11111111; // Sets (digital 29-22) with internal pull up //Code dial inputs DDRC = B00000000; // set PINA (digital 30-37) as inputs PORTC = B11111111; // Sets (digital 30-37) with internal pull up tm.startTimer(200, setIFF); } int inputMaster_mode() { int valueMaster_mode; if (PINA == B00001111) { valueMaster_mode = 4; //EMER } if (PINA == B00011111) { valueMaster_mode = 3; //NORM } if (PINA == B01011111) { valueMaster_mode = 2; //LOW } if (PINA == B00111111) { valueMaster_mode = 1; //STBY } if (PINA == B11111111) { valueMaster_mode = 0; //OFF } return valueMaster_mode; } int inputCode_dial() { int valueCode_dial; if (PINC == B11111111) { valueCode_dial = 0; //ZERO } if (PINC == B01111111) { valueCode_dial = 1; //B } if (PINC == B10111111) { valueCode_dial = 2; //A } if (PINC == B11011111) { valueCode_dial = 3; //HOLD } return valueCode_dial; } void loop() { DcsBios::loop(); tm.runTimers(); } void setIFF(int timer){ if (Master_mode_ingame < inputMaster_mode()) { sendDcsBiosMessage("IFF_MASTER", "INC"); } if (Master_mode_ingame > inputMaster_mode()) { sendDcsBiosMessage("IFF_MASTER", "DEC"); } if (Code_dial_ingame < inputCode_dial()) { sendDcsBiosMessage("IFF_CODE", "INC"); } if (Code_dial_ingame > inputCode_dial()) { sendDcsBiosMessage("IFF_CODE", "DEC"); } } A few shots; Front Back with electronics Why?? Many would probably say why go through all this trouble to get the IFF working since it’s not modelled in DCS. True but UniverseRadio/LotAtc just released an additional layer which will enable IFF system. If I recall correctly Aries Radio System implemented it as well long time back. Cheers Solo
-
Thank you very much Eddie and 476th vFG for sharing this valuable document. Much appreciated Cheers Solo
-
A low-cost way to attach a small TFT display module over USB
Hansolo replied to FSFIan's topic in Home Cockpits
Very nice Ian. Thanks for sharing :thumbup: Cheers Hans -
Very nice of you and your team, jrsteensen :thumbup: Looking forward to seeing the result And subscribed Cheers Hans
-
Very nicely done Sir :thumbup: It does sound like the sensor is quite similar to the one in the A-10 throttle; https://forums.eagle.ru/showpost.php?p=2540923&postcount=59 You are not using any amplification of the sensor signal? Cheers Hans
-
Viewing Mark Point and Way points simultaneously on TAD
Hansolo replied to LaLa's topic in DCS: A-10C Warthog
If you set you Aux. Avionics Panel to MARK then you can view all the mark point. If you want to copy them into a waypoint this should be possible by setting the TAD as SOI, Slew cursor over the MARK point, hook it. Now ? should appear OSB18. Pressing OSB18 ? will copy the hooked item into a waypoint. Cheers Hans -
You may find something useful from my good friend Reznik's build; https://forums.eagle.ru/showthread.php?p=3098601 Cheers Hans
-
It doesn't necessary have to be that you are out of ammo and he is not. The threat situation may also require that the aircraft delivering the ordnance needs to conduct agressive manouvres after release. In this case wingman can lase from a little safer distance. On note is that in order for buddy lasing to work both aircrafts have to be within 8nm of the target. Not sure what the distance is in real life but for DCS its app. 8nm. Cheers Hans
- 1 reply
-
- 1
-
-
Nicely done Sir:thumbup: What did you use for the push-pull switches? looks like circuit breakers. Looking forward to see more where that's coming from. Cheers Hans
-
Do you have the DCS-BIOS folder including all the files in 1.5.8 saved games folder\DCS\Scripts? Cheers Hans
-
DCS-BIOS - How to send a freuency value directly to a UHF radio?
Hansolo replied to yoreh's topic in Home Cockpits
Sweet yoreh. I am glad you got first part of it working :thumbup: Top job Sir. Cheers Hans -
Very nice pit you got there Sir. You should be ready for end of spring :-) Cheers Hans
-
First successful Maverick launch. Did I do it right?
Hansolo replied to Vampyr's topic in DCS: A-10C Warthog
If you want to RIFLE off more AGM in one pass don't use the TGP. Here is an example from one of our flights where FROSTY 6-2 RIFLE's off 4xAGM in one pass, 1h25m10s into the recording. NOTE! Here the TGP is not used. Just use the wagon wheel in the HUD to slew to the vicinity of the targets and then gain a lock from AGM seeker. What can't seen in the clip is that AGM is on right MFCD on a second monitor. Cheers Hans -
Patriot how many Arduino's do you use for your engine cluster? If you use just one then that may be the problem. I seem to recall Warhog talking about the fact that a Nano/Uno isn't fast enough to run all 12 gauges. p.s. very nice engine cluster you have made by the way :-) Cheers Hans
-
From my understanding DCS-BIOS only updates on changes. Thus if your real panel is in ON but DCS starts in OFF nothing happens. You have to cycle it OFF then ON to get it to ON. And it doesn't matter whether uyou use an ONB-ON or an ON-OFF. Functionality is the same. Difference is that with the ON-ON DCS-BIOS doesn't have to 'calculate' the OFF position. It knows it from the feed back. Sorry for the misunderstanding Cheers Hans
-
Hi Sven, Looking good. To answer your question about the MS24659-23D. You can use it as an ON-OFF with DCS-BIOS (simple); DcsBios::Switch2Pos alcpHarssas("ALCP_HARSSAS", PIN); Or as an ON-ON with DCS-BIOS (advanced mode); const byte alcpHarssasPins[2] = {PIN_0, PIN_1}; DcsBios::SwitchMultiPos alcpHarssas("ALCP_HARSSAS", alcpHarssasPins, 2); Cheers Hans
-
Nice find at currently good price:thumbup:
-
DCS-BIOS - How to send a freuency value directly to a UHF radio?
Hansolo replied to yoreh's topic in Home Cockpits
Yoreh this may be of assistance to you https://forums.eagle.ru/showpost.php?p=3336218&postcount=180 Here I try to get a TACAN up and running in the A10C with DCS-BIOS. The TACAN in the A10C also can only use Increase and Decrease. The code can probably be done more neatly but it sound like a similar situation you want to handle Cheers Hans -
Real TACAN implementation with DCS-BIOS Extremely slow progress now. We got our second child end of October so time is sparse for the time being. Nonetheless there is a little progress which I’d like to share. I have been working on getting a real TACAN implemented into the pit. (without lightplate) The issue with TACAN in DCS is that it, unlike ILS, the TACAN can’t be set for specific channel. DCS and therefore also DCS-BIOS can only handle ‘step up’ or ‘step down’. My idea was to have DCS-BIOS compare set value on real TACAN panel with value from DCS. If DCS was lower than TACAN panel value then DCS-BIOS to send ‘step up’ to DCS, if DCS value was higher than TACAN panel value then DCS-BIOS to send 'step down’ to DCS. If DCS value is equal to TACAN panel value then don’t step. First hurdle to get past was a simple way of interpreting the positions from the hardware. I made a map of the rotary switch: I couldn’t figure out the coding system. It isn’t binary and doesn’t appear to be grey code either. A good friend of mine pointed me toward Port Registers. It lets you read or write to a segment of pins. That way I could write the map down thereby telling the Arduino that positions the channel was in. I discarded to use of the Nano board as I needed more pins as I had two rotary switches. Secondly the Nano only has one segment with 8 pins BUT is uses pins 0 and 1 which are TX/RX. Using the Arduino Mega gave me more options as it also has more Port Registers of 8 pins. As can seen from above I threw away rotary switch pins 4 and 5 on the rotary switch and then ended up with 8 pins what could define the exact position of the rotary. From the above map if only rotary switch pin 0 and 11 were active then the channel is 8. Now to implement the Port registers. In Void Setup I added following: //TACAN_1 inputs DDRA = B00000000; // set PINA (digital 29-22) as inputs PORTA = B11111111; // Sets (digital 29-22) with internal pull up //TACAN_10 inputs DDRC = B00000000; // set PINA (digital 30-37) as inputs PORTC = B11111111; // Sets (digital 30-37) with internal pull up } Above setup tells the Mega to set pins 29-22 as well as pins 30-37 as INPUT and use internal PULL UP. I also added following to Void Setup; int inputTacan_right() { int valueTacan_right; if (PINA == B11110010) { valueTacan_right = 0; } if (PINA == B11110101) { valueTacan_right = 1; } if (PINA == B11101011) { valueTacan_right = 2; } if (PINA == B11101111) { valueTacan_right = 3; } if (PINA == B11101110) { valueTacan_right = 4; } if (PINA == B11011101) { valueTacan_right = 5; } if (PINA == B11011011) { valueTacan_right = 6; } if (PINA == B11011111) { valueTacan_right = 7; } if (PINA == B10111110) { valueTacan_right = 8; } if (PINA == B00111101) { valueTacan_right = 9; } return valueTacan_right; } Int inputTacan_right () which will be used later in the comparison between DCS and real TACAN rotary switch position. The value for inputTacan_right() is by checking the port register A (pins 29-22) and see which of the combinations fit. E.g. if the pins are read as 11011111 then the position is 7. Same is done for left channel, please see full code later. I also needed the channels from DCS so added this to the beginning of the sketch; int Tacan_right_ingame; // hold value from DCS //TACAN Right Channel void onTacan1Change(unsigned int newValue) { Tacan_right_ingame = newValue; } DcsBios::IntegerBuffer tacan1Buffer(0x1158, 0xf000, 12, onTacan1Change); It basically set Tacan_right_ingame to the right channel value received from DCS via DCS-BIOS In the Loop I added; if (Tacan_right_ingame < inputTacan_right()) { sendDcsBiosMessage("TACAN_1", "INC"); } if (Tacan_right_ingame > inputTacan_right()) { sendDcsBiosMessage("TACAN_1", "DEC"); } This is the comparison between DCS values and the set values on the rotaries. The whole sketch was set to use USB communications as it was a trial version. Well it kinda worked. Problems encountered was that it was that communication was flooded with INC INC INC INC. And it had a tendency over running past the rotary value and them back again until it settled. I tried to include a delay into the loop but that just made it worse. Now it seemed like the values were remembered during the delay. Thus it kept increasing long after DCS and rotaries were aligned. Ok back to the drawing board. I had an idea of what I was looking for. I just wanted the sketch to compare DCS and TACAN panel a few times a second. Finally I would something useful: This in the beginning of the sketch: #include <timer.h> Timer tm; This in Void setup() tm.startTimer(200, setTacan); It calls the function setTacan every 200miliseconds. So even if the loop is being called many more time due to the speed of the processor then it's only about 5 times a second the TACAN rotary switch position is being compared with DCS. When I wite 'about' then if I understand correctly the timer isn't that accurate as it does not take into account the time it takes to run the loop itself. For all intended purposes it shouldn't matter here. The timer function is included in the Void loop() but the comparison between DCS and Tacan rotaries is done in Void setTacan() This is currently the full sketch; /* Tell DCS-BIOS to use a serial connection and use the default Arduino Serial library. This will work on the vast majority of Arduino-compatible boards, but you can get corrupted data if you have too many or too slow outputs (e.g. when you have multiple character displays), because the receive buffer can fill up if the sketch spends too much time updating them. If you can, use the IRQ Serial connection instead. */ #define DCSBIOS_DEFAULT_SERIAL #include "DcsBios.h" #include <timer.h> Timer tm; int Tacan_right_ingame; // hold value from DCS int Tacan_left_ingame; // hold value from DCS /* paste code snippets from the reference documentation here */ //TACAN test button DcsBios::Switch2Pos tacanTestBtn("TACAN_TEST_BTN", 3); //TACAN Channel X/Y Toggle const byte tacanXyPins[2] = {4, 5}; DcsBios::SwitchMultiPos tacanXy("TACAN_XY", tacanXyPins, 2); //TACAN Mode Dial const byte tacanModePins[5] = {6, 7, 8, 9, 10}; DcsBios::SwitchMultiPos tacanMode("TACAN_MODE", tacanModePins, 5); //TACAN Signal Volume DcsBios::Potentiometer tacanVol("TACAN_VOL", A0); //TACAN Right Channel void onTacan1Change(unsigned int newValue) { Tacan_right_ingame = newValue; } DcsBios::IntegerBuffer tacan1Buffer(0x1158, 0xf000, 12, onTacan1Change); //TACAN Left Channel void onTacan10Change(unsigned int newValue_Tacan_left) { Tacan_left_ingame = newValue_Tacan_left; } DcsBios::IntegerBuffer tacan10Buffer(0x1158, 0x0f00, 8, onTacan10Change); void setup() { DcsBios::setup(); //TACAN_1 inputs DDRA = B00000000; // set PINA (digital 29-22) as inputs PORTA = B11111111; // Sets (digital 29-22) with internal pull up //TACAN_10 inputs DDRC = B00000000; // set PINA (digital 30-37) as inputs PORTC = B11111111; // Sets (digital 30-37) with internal pull up tm.startTimer(200, setTacan); } int inputTacan_right() { int valueTacan_right; if (PINA == B11110010) { valueTacan_right = 0; } if (PINA == B11110101) { valueTacan_right = 1; } if (PINA == B11101011) { valueTacan_right = 2; } if (PINA == B11101111) { valueTacan_right = 3; } if (PINA == B11101110) { valueTacan_right = 4; } if (PINA == B11011101) { valueTacan_right = 5; } if (PINA == B11011011) { valueTacan_right = 6; } if (PINA == B11011111) { valueTacan_right = 7; } if (PINA == B10111110) { valueTacan_right = 8; } if (PINA == B00111101) { valueTacan_right = 9; } return valueTacan_right; } int inputTacan_left() { int valueTacan_left; if (PINC == B11110010) { valueTacan_left = 0; } if (PINC == B11110101) { valueTacan_left = 1; } if (PINC == B11101011) { valueTacan_left = 2; } if (PINC == B11101111) { valueTacan_left = 3; } if (PINC == B11101110) { valueTacan_left = 4; } if (PINC == B11011101) { valueTacan_left = 5; } if (PINC == B11011011) { valueTacan_left = 6; } if (PINC == B11011111) { valueTacan_left = 7; } if (PINC == B10111110) { valueTacan_left = 8; } if (PINC == B00111101) { valueTacan_left = 9; } if (PINC == B00111011) { valueTacan_left = 10; } if (PINC == B01111111) { valueTacan_left = 11; } if (PINC == B11111110) { valueTacan_left = 12; } return valueTacan_left; } void loop() { DcsBios::loop(); tm.runTimers(); } void setTacan(int timer){ if (Tacan_right_ingame < inputTacan_right()) { sendDcsBiosMessage("TACAN_1", "INC"); } if (Tacan_right_ingame > inputTacan_right()) { sendDcsBiosMessage("TACAN_1", "DEC"); } if (Tacan_left_ingame < inputTacan_left()) { sendDcsBiosMessage("TACAN_10", "INC"); } if (Tacan_left_ingame > inputTacan_left()) { sendDcsBiosMessage("TACAN_10", "DEC"); } } 1st unsolved issue; Now it doesn’t work complete as it should. It only works for channels 00 to 99. The position from DCS is actually the position of the rotary knob not the channel itself. This is not an issue for the right channel but for the left the knob will be in the same position on channel 0 and 10, 1 and 11 plus 2 and 12. Ian has given me help to retrieve the channel itself from the char value instead but I haven’t gotten it to work. Most probably I noted down the solution incorrectly; void onTacanChannelChange(char* newValue) { // if (newValue[0] == '48') newValue[0] = '0'; // leftSelectorPos = (newValue[0] - '48')* 10 + (newValue[1] - '48'); int Tacan_left_ingame = atoi(newValue[1]); //leftSelectorPos; } DcsBios::StringBuffer<4> tacanChannelBuffer(0x1162, onTacanChannelChange); 2. unsolved issue; For some odd reason I can’t get the Mega to work with RS485 using MAX487 as I have been using on all the other Nano boards. I did find one of the MAX487’s not working but that’s not the issue. I tried to use same communications board. When running it on a Nano it works, but when connecting it to the Mega is doesn’t. It should be working so it must be an error on my side but haven’t located it yet. A little wiring; Quick YT, sorry for poor recording Anyway just a small sitrep at the end of 2017. Pace have gone down but I hope to be able to get some momentum end of first quarter 2018 Happy New Year Cheers Hans
-
It's an old post but mostlikely still valid; https://forums.eagle.ru/showpost.php?p=1724366&postcount=103 Cheers Solo
-
You can force the magnetic held switch out of position but as already mentioned they come off when de-enegized; Cheers Hans
-
Looks like really good shape Calum. Congratulations on your purchase :thumbup: Cheers Hans
-
Odd. I am still running Helios and Phidget for the Caution panel. Well at least until I get a working Caution panel for DCS-BIOS ;) Anyway the update to the ejection seat does look good as always RK :thumbup: Cheers Hans
-
Eh IMHO no. Entering wind into the CDU wouldn't really matter too much for guided munition, since it's well guided. For dumb bombs maybe, but I never used it. The CDU will already record the wind date while flying. Main reason fro me not using it is the fact that Eddie from 476th has on numerous occasions stated that it's simply not necessary. IIRCC one of his points are that we as simmers tends to believe that dumb bombs will give us same accuracy as guided bombs if we enter wind into the CDU. If were that accurate then guided munition wouldn't be used at all I guess. The second reason again IIRCC is that our (mine too) lineup on target and delivery is simply not good enough. Can I proof it. No I am not that good, but reading through all the stuff Eddie posted over the years I have no reason to doubt him. Cheers Hans
-
I suggest you add your code you are using, otherwise we are guessing blindly. DCS-BIOS are using default pull-up of the inputs so no pull-down resistor is needed. Cheers Hans