Wednesday, March 16, 2016

Hacking Torqueedo Outboard Motors


Welcome

If you are the proud owner of a Torqeedo outboard motor and are unsatisfied with the standard Torqeedo  remote throttle, you've come to the right place!

In this post I'm going to cover using a micro controller to interface with the Torqeedo hardware by mimicking the digital signature of the magnetic encoder in the remote throttle used to read the handle position...  I'll be skipping a few of the trivial steps, but I'll cover in detail most of the software and share some code.

white

Why Mimic the Encoder? 

Lack of better options.  Alternatives we've tried:
  1. Use a servo to manually rotate the throttle, or a magnet placed where the throttle would normally sit.
  2. Splice into the data line between controller and handle, try to reverse engineer Torqeedo's messages, use those messages to directly communicate with the motor without remote throttle.
While the first method worked, it did not provide the fidelity or response times we needed.  The second method proved fruitless.  Mimicking the encoder is sort of a happy medium between the two, you can communicate digitally, but you're doing so with a protocol pulled off a data sheet.

white

What Encoder?

Start by taking apart your remote throttle.  Unplug it and remove the dead man switch for good measure.  Then you'll want to open it like a clam shell:


I've already spliced the encoder lines on mine, so the cable is really long.  Your's probably won't be, so it won't want to open all the way.  You can pop off both the white and red plugs on the right side to give yourself some wiggle room.  Next take a torque wrench and remove the screw that holds in the encoder.

white

AS5045

Now let's take a look at that encoder.  This is the part we're going to be mimicking, so it's crucial that anyone following this guide verbatim has the exact same chip as us.  A cell phone camera might do a better job reading those small letters than you and your naked eye (I don't know who decided to use dark dark gray font on a black background).

I've pulled out two AS5045's from both our Torqeedo outboard motors.  Make sure your chips are the same.  I don't know anything about Torqeedo's product line, or whether or not the same product is guaranteed to have the same chip, but if you have an AS5045, you should be golden.

You can download the data sheet for the AS5045 here.  It's a fairly generic "12 bit rotary position sensor."  It's configured to communicate with the main remote throttle control logic via serial interface.

white

AS5045 to Remote Throttle Communication

There is a 6 pin gray and red ribbon cable that connects the AS5045 with the main control logic.  The cable connects the following AS5045 Pins:
  • Power
  • Ground
  • Digital Out
  • Digital In
  • Clock
  • Chip Select
We ignore Power and Digital In, and reroute Chip Select, Ground, Digital Out, and Clock to some breakout wires.  You'll need to cut the ribbon cable in half to grab these connections.  The wires are pretty small, and soldering them isn't easy, but the wire is braided so if you give yourself lots of room to work with you should be fine.  You can see what I've done on the right.  The color code is:
  • White - Ground
  • Gray - Chip Select
  • Purple - Clock
  • Blue - Digital out
  • Green  - Digital In (you don't need this wire)
  • Yellow - Power (you don't need this wire)
In the picture, ribbon cable red side is on the right.

white

Sanity Check

To verify the reverse engineered pinouts, I attached an oscilloscope to the encoder output while everything is connected as it originally was:



Here a you can see a gif of the SCL (green) and SDA (blue) lines for two different handle positions:

If you compare this to the SSI interface outlined in the AS5045 data sheet:



You'll see that this is exactly what we'd expect from the system.  This is good!  However,  SOMETIMES THE CLK LINE (owned by the remote throttle) DOES NOT CYCLE 17 TIMES.  On occasion,  the CLK will only fire 12 times,  and essentially ignore the last few bits of the encoder message.  What's not shown in the oscilloscope (due to lack of channels) is the CSN line, which we will use later to clear the remaining 4 bits from the write buffer on our micro controller when the CLK line exhibits this behavior.

white

Remove the Dead Mans Switch

Do this if you haven't all ready.  We'll have to calibrate the remote throttle before it's reasonably safe to turn the motor back on.  After you've cut the ribbon cable connecting the AS5045 to the remote throttle, try turning on the remote throttle.  You should see a E22 error message.  This represents a non responsive encoder.  This is good!  Keep going.

white

Mimicking AS5045 Digital Signature

For this part, I use an Arduino Due micro controller.  You're welcome to try other flavors, but many other products on the Arduino line were not fast enough to match the timing of the AS5045.  I don't use the built in Arduino SPI interface because it appears to only have a master mode, and not a slave mode (master implies control of the clock, which the AS5045 does not have).   

Beware that the Arduino Due is a 3.3V micro controller, so plugging anything 5V into it is catastrophic.  

Upload this code to your Arduino Due.  Note the pinout's listed at the top of the file:

 const int PIN_DAT = 49;  
 const int PIN_CLK = 51;  
 const int PIN_CSN = 53;  

There is a ground pin right next to 53, which makes it all easy access.  Again, you don't need to connect the lines that would attach to Power or DI on the AS5045 to anything.  Here is my setup:


Note the remote throttle is not giving me the E22 error message.  You'll have to restart the remote throttle with the arduino plugged in to clear any prior error messages.

You'll need to replug the cables into the remote throttle if you haven't already.

If your remote throttle does not give you the E22 message, you're all set to continue!  If you see an E21 error message, this is alright as we'll address this in the next section.

white

Calibrating Remote Throttle

The remote throttle maps the rotation values from the encoder to power output.  That relationship is unique for each remote throttle.  On one of our remote throttles, 0 was full reverse, 900 was neutral, and 1300 was full forward.  Torqeedo has a built in calibration process to set this number line.  We'll be setting 0 to full reverse, 1000 to neutral, and 2000 to full forward.  This is the value range the arduino will be sending to command the motor when we're all finished.

Read through these instructions, taken from the torqueedo manual:

Re-calibrate: Press "cal" button for 10 seconds

  • The display shows "cal up": Press tiller forward to full gas then press the "cal" button
  • The display shows "cal stp": Return tiller to central postion then press the "cal" button
  • The display shows "cal dn": Press tiller backward to full gas then press the "acal" butto
The "cal" button they are referring to is the "setup" button (leftmost button on the remote throttle).  Other than that, these are great instructions.  We'll be doing something similar, except that we'll be pressing each button when the arduino is sending the right message, not when the handle is in the appropriate place.

Now, you'll need to upload this code to your arduino.  This code will continuously send either the value 0, 1000, or 2000 to the remote throttle.  Which value is sent is indicated by the speed of the on board blinking led on the arduino.

  • 1 Blink per second: tiller forward (2000) is being sent
  • 20 Blinks per second: neutral (1000) is being sent

  • 2.5 Blinks per second: tiller backward (0) is being sent
The arduino should progress like the manual suggests: Full Forward to Neutral to Full Backward to Neutral and so on.  The arduino will progress to the next output every 15 seconds, which leaves more than enough time to complete each calibration step.

white

Testing

Upload this code.  Reattach your dead mans switch, and let her rip!  If everything went well, the program should comamnd sinusoidal output.  The active code looks like this:


void loop()
{  
  int current_time = millis();
  float seconds = current_time / 1000.0;
  motorValue = 1000 + 1000 * sin(seconds);
} 

You'll notice that the motor won't go as fast in reverse as it will forward.  I think this is a function of the internal logic on the remote throttle, and isn't something we can fix here.

white

Sending Relevant Commands



This is a video of my lab mate controlling two Cruise R 2.0's with a remote control.  You won't want to spin the motors fast for long, as it heats up and eventually destroys the internal bearings.

We had to use two arduino due's, one for each Cruise R 2.0.  We found that a single arduino due was only fast enough to mimic one AS5045.  Trying to simulate two AS5045's at the same time caused us to miss interrupts, and poison our connection with the remote throttle (all it takes is one bad reading for the remote throttle to get stuck on a E23 or E22).

For the same reason, you can't open a serial line to a computer with the Arduino Due.  The serial interrupts mess with the timing of the arduino due, causing us to miss clock cycles.

What you can do is: use a second micro controller to read values from a computer or other device, and then use analogRead() or pulseIn() on the due to transfer the signal from the other micro controller to the due.  Neither analogRead or pulseIn throw off our interrupt timing.

That's it.

Happy Boating!


24 comments:

  1. Hi, this is a great tutorial thanks. Would you mind posting your complete code from the video including how you are reading the spektrum rx.
    Thanks a lot!

    ReplyDelete
    Replies
    1. Feoras,

      I've updated the git repo with a new set of programs in /RemoteControl. One is for an arduino nano which we use to read the remote and synchronize our two Arduino Due's that talk to each remote throttle. I've also included a pinout here:

      https://github.com/SnowmanTackler/Torqeedo/blob/cae9d5597ac295b0dff126ba9bfee1843ab45f0b/RemoteControl/Schematic.png

      Delete
    2. Great!! Thanks. Here's what I did in the meantime https://vimeo.com/169820962.

      I have a look at the diagram. It makes sense but do you have a level converter somewhere in there to drop the rx 5v to the due 3.3v?

      Delete
    3. Very cool! As per power ~ we power the nano through a USB connection to an onboard computer, and then send that 5V from the nano to the Due's, and a generic 6 channel receiver. The due's have their own converter to bring the input voltage down to 3.3.

      Let me know if you get the mimic encoder setup working / have any more questions.

      Delete
  2. Hey, great job!! I'm looking for other kind of hacking on this controller.. I would like to acess data it provides (speed, voltage, power, etc) for logging purposes. Any ideas on this topic?

    ReplyDelete
    Replies
    1. You'll need Torqueedo's messaging format. I believe they will disclose it to you if you sign an NDA, or you could try to reverse engineer it. I don't really have more than that.

      Delete
  3. Hi! I'm curious if anyone has experience calibrating 8 years old Cruise 2.0L motor... I've got error 13 message and wrong motor response on tiller turns. Service center in Germany agrees that i have to change tiller electronic, but, in addition, I need some calibrating tool. They don't share what tool exactly...

    ReplyDelete
  4. The mercury outboards are very famous among outboards. The owners need to maintain and repair them proper with the help of Mercury Outboards Manuals.

    ReplyDelete
  5. Hello ,
    Amazing Tutorial!
    I am able to make the motor run through the Arduino Due. My only problem at the moment is I see you use pin_52 on the Arduino Nano, but I cannot find set pin on the Nano. I'm sure I'm missing something very simple. Can anyone Help ?

    ReplyDelete
    Replies
    1. Whoops! Sorry for not getting back to you sooner. There is no pin 52 on a nano, that code existed when we ran the remote control receiver from an arduino mega. Hope that helps, if you haven't figured out an alternative already!

      Delete
  6. Hey there - I'm trying to find some pin-out information on the old Torqeedo Travel 401 - do any of you know if/how I can run that motor of a 12V deep cycle battery w/o the proprietary battery adapter? Has anyone reengineered that battery adapter?

    ReplyDelete
  7. Thank a lot!!! I'm building an efoil with a Torqeedo and your tutorial is very helpful in order to have a remote throttle.

    ReplyDelete
  8. Finding the time and actual effort to create a superb article like this is great thing. I’ll learn many new stuff right here! Good luck for the next post buddy..
    Discount Outboard Motors for sale

    ReplyDelete
  9. so if I have a motor on each pontoon, I can steer with thrust?

    ReplyDelete
  10. I flip the kayak , the trottle was inside the water.
    After I get out , I let everything dry and then connect everything, but the trottle give me the E22 error. I follow the manual steps for calibration , but still give the E22 error. I'm thinking in humidity inside. Wath do you think?

    ReplyDelete
  11. My stupid question is how to open up the remote throttle lid. I don't see a screw holding it on, does it just snap off?

    ReplyDelete
  12. Do you happen to know the pin-out of the connector that connects to the controller on the actual outboard (5 pin)? I cannot find a wiring diagram anywhere...

    ReplyDelete
  13. Excellent technical post. Curious, I'm not as technical as you, I'd like to relocate the throttle handle and encoder into a long extendable tiller. I see there are 6 wires, is it possible to simply extend these wires and connect them to some pentiotometer or rotary encoder or do I need to do more? Thanks.

    ReplyDelete
  14. The end goal is to put my own encoder on the tiller and connect it to either a trigger or thumb wheel for throttle. Thanks for any advice.

    ReplyDelete
  15. my 3 tpeqeedo throttles are showing a no battery status sign and wont make the motor work...also show 0.0 v anyone knows anything about this ?

    ReplyDelete
  16. Hi, thank you for sharing excellent tips. I got a Torqeedo Cruise 2.0 with a „massive surgery“ and I would like to compare its status with an original one. Do you know where I can find a diagram of the circuits and maybe photos of the open head (where the electronics go)? Thank you!

    ReplyDelete
  17. Great Project! I got it working , but the motor is not smooth, RPMs fluctuate up and down.

    ReplyDelete
  18. Excellent job! Nice work describing each step.

    Do you happen to know the pin diagram for the throthle output /input signals cable?

    Thanks!

    ReplyDelete
  19. https://www.hackerone.com/for-hackers/how-to-start-hacking Join the world’s largest community of ethical hackers and start hacking today! Be challenged and earn rewarding bounties. Learn more!

    ReplyDelete