Thread Rating:
  • 0 Vote(s) - 0 Average
  • 1
  • 2
  • 3
  • 4
  • 5
Pololu Motor Controller Daisy Chains
#1
I posted a PDF to help understand how to daisy chain the Pololu Simple Motor Controller (SMC).

And code to go with it: http://rebeldroids.net/gallery/displayim...1&pid=1432 

The H015 needs 4 motor controllers.  Each need assigned a # (in my case 13-16).  To make them move the Tx of the Arduino merely connects to the Rx of all of the controllers.  When they hear their number, they'll listen for what to do.

Querying for the R/C receiver input positions is more complicated though.  The Arduino has to ask the controller to read the R/C input, and then send that back to the Arduino.  If there were only one SMC, we'd just hook up the Tx on the SMC to the RX of the Arduino.  

However, with multiple SMC's we have to pass the Tx outputs through so that the last SMC Tx output goes to the next "TXin", until the final Tx output goes to the Arduino Rx.

[Image: Motor_Wiring_Diagram.png]

Here I'm assuming the motors are 12V motors.  Grounds pretty much all need to be connected, if the Arduino and SMC's don't share ground, then the Tx/Rx signals will be mixed up.  If the R/X RX and SMCs don't share a ground, then those won't work either.

For power, I'm assuming that the Arduino is powered externally, and that there's a 12V (or other appropriate) input to the SMCs.  The R/C receiver needs power, however it should only be powered from ONE of the SMCs.  Ensure that SMC is wired (solder or jumper) from the "BEC" pin to "5V" pin on that SMC's R/C jumper block.

I hooked up the "A" side of the SMC to the + on my motor.  If they run backwards, either flip them or change the software.  It's easier if all the motors are connected in the same polarity.

We need 3 signals from the R/C Receiver to the Arduino.  The SMC's can read the R/C inputs, but each SMC only has 2 R/C channel inputs, so you'll have to use 2 of them.  The other two don't have to have the Tx lines connected because we'll never ask them any questions.  The Tx line of the "last" SMC connects to the TXin line of the "first" SMC, and that TX line connects to the Rx of the Arduino.  (You can connect all 4 if you want).  You could also use the PWM inputs on the Arduino to listen to the R/C, I just did it this way.
Reply
#2
Did you have to use the Pololu software to change the input type from serial/USB to RC on each of the SMCs? Also, the diagram you provide states, "Arduino and SMC must share signal ground", what does that mean? Do the SMC's need to be ground to the Arduino or can they all be ground to the battery?

Please let me know
Reply
#3
(10-12-2018, 12:34 PM)r_saggio Wrote: Did you have to use the Pololu software to change the input type from serial/USB to RC on each of the SMCs?  Also, the diagram you provide states, "Arduino and SMC must share signal ground", what does that mean? Do the SMC's need to be ground to the Arduino or can they all be ground to the battery?

Please let me know

Yes, the Pololu software has to be used to configure the SMCs -- it's also worth setting the limits at that time.

Short answer to grounds:  All the grounds can be connected to the battery - terminal.

All I meant by sharing "signal ground" is that the signal wire (Rx/Tx) is in reference to some common voltage (ground in this case).  If they have different grounds (maybe you used a big 12V battery for the motor controllers and a 5V battery for the arduino), then those grounds have to be connected (common).  Otherwise the tx/rx signals will appear to "float" to one or the other side and basically not work.

The Arduino's Vcc could also go to the +12V (depending on which arduino you're using and if it has a built-in regulator).  Alternatively, the Simple Motor Controllers have a regulator and you can steal a little of their 5V to power the Arduino (but if you do that, then ONLY CONNECT ONE SMC 12V to the Arduino - you don't want their regulators to fight eachother!  Also don't do that if your Arduino is getting power from somewhere else!)  

Similarly the receiver has to get power from somewhere - probably one of the SMC's because it's already got a jumper going there - but you don't want to try to power it from ALL of the simple motor controllers, only connect it's 5V line on one SMC.  (ground probably needs to go to both? -- though that makes me wonder about ground loops, though that's probably not a problem in most implementations)  

Hope that helps.
Reply
#4
OK, I'm getting closer. Now the RC controller is making the motors move. Smile

I have a few questions on the SMC settings:

1. What limits are you talking about in the previous post?
2. I set the following:
SMC A - Input Mode = RC
SMC B - Input Mode = Serial/USB
SMC C - Input Mode = Serial/USB
SMC D - Input Mode = RC
Since SMC D gets both RC inputs, do I need to configure RC Channel 2?
3. Is there anything in the Advanced Settings I should set?

Sorry for so many questions. Once I have this all set, I plan on creating a detailed document for future builders.

Thanks in advance,
- Ross
Reply
#5
(10-12-2018, 08:36 PM)r_saggio Wrote: OK, I'm getting closer.  Now the RC controller is making the motors move.  Smile

I have a few questions on the SMC settings:

1. What limits are you talking about in the previous post?
2. I set the following:
   SMC A - Input  Mode = RC
   SMC B - Input Mode = Serial/USB
   SMC C - Input Mode = Serial/USB
   SMC D - Input Mode = RC
   Since SMC D gets both RC inputs, do I need to configure RC Channel 2?
3. Is there anything in the Advanced Settings I should set?

Sorry for so many questions.  Once I have this all set, I plan on creating a detailed document for future builders.

Thanks in advance,
- Ross

No problem Smile Glad you're making progress

All 4 need to be set to serial with my script, sorry, I think I was confused earlier.

They motor controllers won't do anything my themselves.  They'll still listen for RC signals, but won't do anything with them.  


The Arduino will ask through serial where the sticks are and then add the values together and then command the motor controllers through serial to move whichever way is appropriate.

So:
  • RC RX tells SMC A & D what the R/C stick positions are....
  • SMC A & D remember that information - but don't actually do anything with it.
  • The Arduino sends a signal through the Tx lines saying "SMC A", what's the RC position?
  • SMC A sends a reply through it's Tx line (to the Arduino's Rx line) saying whatever the value is.
  • Ditto for SMC D and the other two channels.
  • The Arduino adds them all together.
  • The Arduino commands each SMC to set it's motor to the appropriate speed through it's TX line
Note that in order for the Arduino to talk to each SMC, it has to address them by #.  The bottom of the chart says which # it expects each SMC to be.  (A is 13, B is 14, C is 15, D is 16).  You have to configure that from the computer when programming the SMCs or else they won't listen when the Arduino calls out their number.  

You can prop up the droid on blocks so the wheels can turn freely.  (That might help if one motor seems to turn but not others, you can figure out which ones are doing what.)

Also note that the wires from the SMC to each motor need to be oriented the same way (otherwise some motors will go backwards and others frontwards).  Easiest to make sure each one is going the right way is to put it on blocks and then use the left stick to rotate.  All wheels should be going the same direction and speed then.  (And if backwards, flip the A/B wires for the backwards motor(s)).

It's cool someone else is using this script & stuff, thanks for helping me shake out the kinks in the instructions!

[Image: Motor_Wiring_Diagram.png]
Reply
#6
Thanks for the info. I reset SMC A and D back to Serial/USB.  I had already set the device numbers for all the controllers per your diagram. I was able to get things to work on my bench and yes, that's an Arduino Nano you see. I also modified the code to control just the motors. I have a separate Arduino Nano for the the LEDs. I can add the LED free code to the Code file folder, if you want.

Again, thanks for all the support.

- Ross


Attached Files Thumbnail(s)
   
Reply
#7
Funny thing is I combined the two scripts Smile

Previously I'd been running the LEDs in the head off a separate nano and one of the USB battery packs for power Smile

Glad you got it working! Cool!
Reply
#8
Here's the detailed wire diagram I came up with.  I've added a DPDT switch and a charge port.  Also, I've powered the controller receiver directly from the DC-DC Step-Down Converter.  I did this because I didn't want any of the SMC's to have to share power.  I've also attached the Arduino code.  I've removed the LED and debug lines to make the code as light as possible.

(PS. I had the wrong file attached for the wire diagram. Sorry)


Attached Files
.pdf   Wiring_H015.pdf (Size: 225.37 KB / Downloads: 1)
.zip   Sentry_Drive_Program.zip (Size: 1.33 KB / Downloads: 2)
Reply
#9
Hmm, I guess my code download wasn't very discoverable, it's in the code section: http://rebeldroids.net/gallery/displayim...1&pid=1432
Reply
#10
I'll go ahead and paste the code, 'cause...  http://rebeldroids.net/gallery/displayim...1&pid=1432

Code:
//
// HO15 Brain Program
//
// On an Arduino Leonardo or ...
// Nano, etc would need Serial1 changed to Serial
//
#include "FastLED.h"
// Hardware serial is used to multiplex motor controllers as we have
// lots of motors on L115.  Most communication will be the "pololu
// protocol" so that we can select which controller to ask.
//
// Motors are on Serial1 (Arduino Leonardo)
// LEDs are on Pin 6
//
// If needed, we'll use software serial for other devices.
//
// First & Second motor controllers contain R/C inputs
//
// First motor controller is queried for battery voltage for failsafe
//
// RX will get power from controller 1
// Motors
#define FRONT_LEFT  13
#define FRONT_RIGHT 14
#define REAR_RIGHT  15
#define REAR_LEFT   16
#define MOTOR_FIRST FRONT_LEFT
#define MOTOR_LAST  REAR_LEFT
#define MOTOR_BAUD 38400
int motorSpeeds[4];
#define SPEED_FRONT_LEFT 0
#define SPEED_FRONT_RIGHT 1
#define SPEED_REAR_RIGHT 2
#define SPEED_REAR_LEFT 3
// R/CInputs
// Values will be scaled -3200 to 3200
// Rotate is Channel 1 of Controller 1
#define CHANNEL_ROTATE      6
#define CONTROLLER_ROTATE   FRONT_LEFT
// Forward/Backward is Channel 1 of Controller 2
#define CHANNEL_MOVE        6
#define CONTROLLER_MOVE     REAR_LEFT
// Sideways is Channel 2 of Controller 2
#define CHANNEL_SIDEWAYS    10
#define CONTROLLER_SIDEWAYS REAR_LEFT
int stickRotate = 0;
int stickMove = 0;
int stickSideways = 0;
// Alert for low volts (mV)
#define LOW_VOLT_CONTROLLER 1
int lowVoltCheck = 12800;  // 12750?
bool lowVoltAlert = false;
// Want to check volts periodically (not all the time so it doesn't slow us down)
unsigned long nextVoltCheck = 0;
// Check every 60 seconds
#define voltCheckPeriod = 60000
// LEDs are needed for L115's Neck
// #0 - Front Blue Center (first one on string)
// #1 - Left Center Red (blinks orange?)
// #2 - Rear Left Orange
// #3 - Right Rear Binks red
// #4 - Right Green
// Number of RGB LEDs
#define NUM_LEDS 5
// LED Pin was 3?
#define LEDPIN 6
// Define the array of leds
CRGB leds[NUM_LEDS];
#define LED_FRONT   0
#define LED_LEFT    1
#define LED_REAR    2
#define LED_RIGHT_A 3
#define LED_RIGHT_B 4
// Toggle spewing of debug spew
bool debug = true;
// MP3 Trigger code not in this version.
// the setup routine runs once when you press reset:
void setup()
{
  Serial1.begin(MOTOR_BAUD);  // Motor Controller
  // Not really needed, but tell motor controller(s) to autodetect baud rate
  Serial1.write(0xAA);
  if (debug)
  {
    Serial.begin(38400);
    Serial.write("hi there");
  }
  // Visual indicator for debugging
  pinMode(LED_BUILTIN, OUTPUT);  
   
  // Make sure all motors stopped, then configure for running
  stopMotors();
  setBrake();
  startMotors();
 
  if (debug)
  {
    // Quick test program
    // THIS MAKES THE MOTORS MOVE, COMMENT OUT TO NOT DO THIS!!!
    // testMotors();
  } 
 
  // LEDs
  // WS2811 have different color patterns than NEOPIXEL/WS2812B
//  FastLED.addLeds<NEOPIXEL, NEOPIXELPIN>(leds, NUM_LEDS);
  FastLED.addLeds<WS2811, LEDPIN>(leds, NUM_LEDS);
 
  if (debug)
  {
    // Do the LED test sequence
    for (int i = 0; i < 1; i++)
    {
      testLEDs();
    }
  }
  // Set them back to normal
  setNormalLEDs();
  FastLED.show();
}
// the loop routine runs over and over again forever:
void loop()
{
  // Do motors
  readPositions();
  calculateSpeeds();
  setMotorSpeeds();
 
  // Do LEDs
  updateLEDs();
}
void testLEDs()
{
  for (int i = 0; i < NUM_LEDS; i++)
  {
    leds[i].r = 255;
    FastLED.show();
    delay(250);
    leds[i].g = 255;
    leds[i].r = 0;
    FastLED.show();
    delay(250);
    leds[i].g = 0;
    leds[i].b = 255;
    FastLED.show();
    delay(250);
    leds[i].b = 0;
  }
}
// We're updating 4x/second
void updateLEDs()
{
  // Our things happen 4x/second
  int time = (millis() % 1000) / 250;
 
  // Right side counts down from 3 in binary
  // Right Red is 2's on time 0 & 1
  leds[LED_RIGHT_A].r = 0;
  leds[LED_RIGHT_A].g = 0;
  leds[LED_RIGHT_A].b = 0;   
  if (time < 2)
  {
    leds[LED_RIGHT_A].r = 255;   
  }
 
  // Right Green is 1's on time 0 & 2
  leds[LED_RIGHT_B].r = 0;
  leds[LED_RIGHT_B].g = 0;
  leds[LED_RIGHT_B].b = 0;   
  if (time == 0 || time == 2)
  {
    leds[LED_RIGHT_B].g = 255;
  }
   
  // Left & rear LED blinks red about 2hz, but slightly off of right side?
  time = (millis() % 510) / 255;
  leds[LED_REAR].r = 0;
  leds[LED_REAR].g = 0;
  leds[LED_REAR].b = 0;
  leds[LED_LEFT].r = 0;
  leds[LED_LEFT].g = 0;
  leds[LED_LEFT].b = 0;
  if (time == 0)
  {
    leds[LED_REAR].r = 255;
    leds[LED_LEFT].r = 255;
  } 
 
  // Front is Blue
  leds[LED_FRONT].r = 0;
  leds[LED_FRONT].g = 0;
  leds[LED_FRONT].b = 255;
  // Show our updates
  FastLED.show(); 
}
// Static for no good reason
void setNormalLEDs()
{
  // Front is Blue
  leds[LED_FRONT].r = 0;
  leds[LED_FRONT].g = 0;
  leds[LED_FRONT].b = 255;
 
  // Left is Red (blinks)
  leds[LED_LEFT].r = 255;
  leds[LED_LEFT].g = 0;
  leds[LED_LEFT].b = 0;
 
  // Rear is Red (one LED, leftish)
  leds[LED_REAR].r = 255;
  leds[LED_REAR].g = 0;
  leds[LED_REAR].b = 0;
  // Right (rear) is red (blinks)
  leds[LED_RIGHT_A].r = 255;
  leds[LED_RIGHT_A].g = 0;
  leds[LED_RIGHT_A].b = 0;
 
  // Right (more middle) is green (blinks)
  leds[LED_RIGHT_B].r = 0;
  leds[LED_RIGHT_B].g = 255;
  leds[LED_RIGHT_B].b = 0;
  FastLED.show();
}
void startMotors()
{
  // exit safe stop
  for (byte motor = MOTOR_FIRST; motor <= MOTOR_LAST; motor++)
  {
    Serial1.write(0xAA);
    Serial1.write(motor);
    Serial1.write(0x3);    // Start
  }     
}
void stopMotors()
{
  // Stop motors
  for (byte motor = MOTOR_FIRST; motor <= MOTOR_LAST; motor++)
  {
    Serial1.write(0xAA);
    Serial1.write(motor);
    Serial1.write(0x60);  // Stop motor
    motorSpeeds[motor-MOTOR_FIRST] = 0;
  }
}
void setBrake()
{
  for (byte motor = MOTOR_FIRST; motor <= MOTOR_LAST; motor++)
  {
    Serial1.write(0xAA);
    Serial1.write(motor);
    Serial1.write(0x12);  // Set brake
    Serial1.write(10);    // 0-32
  }
}
void setMotorSpeeds()
{
  for (byte motor = 0; motor <= 3; motor++)
  {
    int thisSpeed = motorSpeeds[motor];
    if (debug)
    {
      Serial.print("motor ");
      Serial.print(motor);
      Serial.print(":");
      Serial.println(thisSpeed);
    }
    Serial1.write(0xAA);
    Serial1.write(motor + MOTOR_FIRST);
    // Forward or backward command?
    if (thisSpeed < 0)
    {
      // Backwards
      Serial1.write(0x6);  // Motor Reverse
      thisSpeed = -thisSpeed;
    }
    else
    {
      // Forwards
      Serial1.write(0x5);  // Motor Forward
    }
    if (thisSpeed > 3200)
    {
      thisSpeed = 3200;
    }
    Serial1.write(thisSpeed&0x1f);
    Serial1.write(thisSpeed>>5);
  } 
}
void readPositions()
{
  // We shouldn't have anything available.
  while(Serial1.available())
  {
    if (debug) Serial.println("out-of-sync!!!");
    Serial1.read();
  }
 
  // Rotation
  Serial1.write(0xAA);
  Serial1.write(CONTROLLER_ROTATE);
  Serial1.write(0x21);            // Get Variable
  Serial1.write(CHANNEL_ROTATE);  // R/C 1 Scaled variable
  delay(1);
 
  Serial1.write(0xAA);
  Serial1.write(CONTROLLER_MOVE);
  Serial1.write(0x21);            // Get Variable
  Serial1.write(CHANNEL_MOVE);    // R/C 1 Scaled variable
  delay(1);
 
  Serial1.write(0xAA);
  Serial1.write(CONTROLLER_SIDEWAYS);
  Serial1.write(0x21);            // Get Variable
  Serial1.write(CHANNEL_SIDEWAYS);// R/C 1 Scaled variable
  delay(2);
 
  // Hopefully these all got queue'd up in order
  // Each value should be -3200 to 3200
  if (Serial1.available() < 2)
  {
    if (debug) Serial.println("delay1");
    delay(1);
  }
  stickRotate = Serial1.read() + Serial1.read()*256;
  if (Serial1.available() < 2)
  {
    if (debug) Serial.println("delay2");
    delay(1);
  }
 
  stickMove = Serial1.read() + Serial1.read()*256;
  if (Serial1.available() < 2)
  {
    if (debug) Serial.println("delay3");
    delay(1);
  }
  stickSideways = Serial1.read() + Serial1.read()*256;
 
  if (debug)
  {
    Serial.print("rotate: ");
    Serial.println(stickRotate);
    Serial.print("move: ");
    Serial.println(stickMove);
    Serial.print("sideways: ");
    Serial.println(stickSideways);       
    // Also blink the onboard LED in case computer isn't hooked up.
    // Change these two "stickRotate" checks to
    // "stickMove" or "stickSideways" to test other R/C inputs.
    if (stickRotate < -100)
    {
      digitalWrite(LED_BUILTIN, LOW);
    }
    if (stickRotate > 100)
    {
      digitalWrite(LED_BUILTIN, HIGH);
    }   
  }
}
void calculateSpeeds()
{
  // Everyone gets the rotate speed
  // left gets move
  // right gets -move
  // front gets sideways
  // rear gets - sideways
 
  motorSpeeds[SPEED_FRONT_LEFT] = stickRotate + stickMove + stickSideways;
  motorSpeeds[SPEED_FRONT_RIGHT] = stickRotate - stickMove + stickSideways;
  motorSpeeds[SPEED_REAR_RIGHT] = stickRotate - stickMove - stickSideways;
  motorSpeeds[SPEED_REAR_LEFT] = stickRotate + stickMove - stickSideways;
}
// Test the motors
void testMotors()
{
  for (int count = 0; count < 3; count++)
  {
    for (int i = 0; i < 3; i++)
    {
      // speed is -3200 to 3200, so fast enough to see it's doing something, not so fast as to go crazy
      motorSpeeds[i] = 600;
      setMotorSpeeds();
      delay(250);
      motorSpeeds[i] = 0;
      setMotorSpeeds();
    }
    for (int i = 0; i < 3; i++)
    {
      // speed is -3200 to 3200, so fast enough to see it's doing something, not so fast as to go crazy
      motorSpeeds[i] = -600; // Try the other direction
      setMotorSpeeds();
      delay(250);
      motorSpeeds[i] = 0;
      setMotorSpeeds();
    }   
  }
  // Make sure they're all off.
  stopMotors();
  startMotors();
}
Reply


Forum Jump:


Users browsing this thread: 1 Guest(s)