Skip to content

Commit a4c29bd

Browse files
authored
Merge pull request #25 from arduino-libraries/nano_motor_carrier
Support Nano motor carrier and update PID behaviour
2 parents 5187891 + c32747c commit a4c29bd

28 files changed

+3608
-1033
lines changed

examples/Flasher/Flasher.ino

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/*
2-
STANDALONE FIRMWARE UPDATE FOR MKR Motor Shiuld
2+
STANDALONE FIRMWARE UPDATE FOR Arduino Motor Carrier
33
44
To generate a new firmware, compile D11-Firmware with target MKRMotorShield, 4KB bootloader, LTO enabled, pinmap complete
55
and execute
@@ -8,9 +8,14 @@
88
*/
99

1010
#include "Wire.h"
11-
#include "fw.h"
1211
#include "ArduinoMotorCarrier.h"
1312

13+
#ifdef ARDUINO_SAMD_NANO_33_IOT
14+
#include "fw_nano.h"
15+
#else
16+
#include "fw_mkr.h"
17+
#endif
18+
1419
#define I2C_ADDRESS 0x09
1520

1621
void setDataRunning(int cmd, uint8_t target, int data) {
@@ -52,6 +57,9 @@ void setup() {
5257
Serial.println("Reset D11");
5358
setDataRunning(RESET, 0, 0);
5459
delay(10);
60+
} else {
61+
// TODO: on NanoMotorCarrier we have the change to forcefully reset the D11; do it now if it is unresponsive
62+
5563
}
5664

5765
// reset running D11

examples/Flasher/fw.h

Lines changed: 0 additions & 967 deletions
This file was deleted.

examples/Flasher/fw_mkr.h

Lines changed: 958 additions & 0 deletions
Large diffs are not rendered by default.

examples/Flasher/fw_nano.h

Lines changed: 958 additions & 0 deletions
Large diffs are not rendered by default.
Lines changed: 97 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,97 @@
1+
#include <ArduinoMotorCarrier.h>
2+
#define INTERRUPT_PIN 6
3+
4+
//Variable to store the battery voltage
5+
static int batteryVoltage;
6+
7+
//Variable to change the motor speed and direction
8+
static int duty = 0;
9+
10+
void setup()
11+
{
12+
//Serial port initialization
13+
Serial.begin(115200);
14+
//while (!Serial);
15+
16+
//Establishing the communication with the motor shield
17+
if (controller.begin())
18+
{
19+
Serial.print("MKR Motor Shield connected, firmware version ");
20+
Serial.println(controller.getFWVersion());
21+
}
22+
else
23+
{
24+
Serial.println("Couldn't connect! Is the red led blinking? You may need to update the firmware with FWUpdater sketch");
25+
while (1);
26+
}
27+
28+
// Reboot the motor controller; brings every value back to default
29+
Serial.println("reboot");
30+
controller.reboot();
31+
delay(500);
32+
33+
int dutyInit = 0; // at 50 it works as espected, at 60 shift sides and is too small duty to move, at 70 is very big duty.
34+
M1.setDuty(dutyInit);
35+
M2.setDuty(dutyInit);
36+
M3.setDuty(dutyInit);
37+
M4.setDuty(dutyInit);
38+
Serial.print("Duty init: ");
39+
Serial.println(dutyInit);
40+
// int duty2 = dutyInit * 16777215 / 100;
41+
// Serial.print("Conversion formula: ");
42+
// Serial.println(duty2);
43+
//while (1); //WHILE 1!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! REMOVE!!!!
44+
}
45+
46+
47+
void loop() {
48+
49+
//Take the battery status
50+
//float batteryVoltage = (float)battery.getConverted();
51+
52+
//Reset to the default values if the battery level is lower than 11V
53+
// if (batteryVoltage < 11)
54+
// {
55+
// Serial.println(" ");
56+
// Serial.println("WARNING: LOW BATTERY");
57+
// Serial.println("ALL SYSTEMS DOWN");
58+
// M1.setDuty(0);
59+
// M2.setDuty(0);
60+
// M3.setDuty(0);
61+
// M4.setDuty(0);
62+
// while (batteryVoltage < 11)
63+
// {
64+
// batteryVoltage = (float)battery.getConverted();
65+
// }
66+
// }
67+
// else
68+
// {
69+
70+
//Motor test
71+
for (duty = -100; duty < 100; duty += 1)
72+
{
73+
Serial.print("Motor Duty: ");
74+
Serial.println(duty);
75+
M1.setDuty(duty);
76+
M2.setDuty(duty);
77+
M3.setDuty(duty);
78+
M4.setDuty(duty);
79+
delay(10);
80+
}
81+
for (duty = 100; duty > -100; duty -= 1)
82+
{
83+
Serial.print("Motor Duty: ");
84+
Serial.println(duty);
85+
M1.setDuty(duty);
86+
M2.setDuty(duty);
87+
M3.setDuty(duty);
88+
M4.setDuty(duty);
89+
delay(10);
90+
}
91+
92+
//Keep active the communication MKR1000 & MKRMotorCarrier
93+
//Ping the samd11
94+
controller.ping();
95+
//wait
96+
delay(50);
97+
}
Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,63 @@
1+
#include <ArduinoMotorCarrier.h>
2+
#define INTERRUPT_PIN 6
3+
4+
//Variable to store the battery voltage
5+
static int batteryVoltage;
6+
7+
//Variable to change the motor speed and direction
8+
static int duty = 0;
9+
10+
void setup()
11+
{
12+
//Establishing the communication with the motor shield
13+
if (controller.begin())
14+
{
15+
Serial.print("MKR Motor Shield connected, firmware version ");
16+
Serial.println(controller.getFWVersion());
17+
}
18+
else
19+
{
20+
Serial.println("Couldn't connect! Is the red led blinking? You may need to update the firmware with FWUpdater sketch");
21+
while (1);
22+
}
23+
24+
//Serial port initialization
25+
Serial.begin(115200);
26+
while (!Serial);
27+
28+
// Reboot the motor controller; brings every value back to default
29+
Serial.println("reboot");
30+
controller.reboot();
31+
delay(500);
32+
33+
// Reset the encoder internal counter to zero (can be set to any initial value)
34+
Serial.println("reset counters");
35+
encoder1.resetCounter(0);
36+
encoder2.resetCounter(0);
37+
38+
M1.setDuty(30);
39+
M2.setDuty(30);
40+
M3.setDuty(30);
41+
M4.setDuty(30);
42+
}
43+
44+
45+
void loop() {
46+
47+
//Chose the encoder to use:encoder1(default) or encoder2
48+
Serial.print("Encoder1 Pos [counts]: ");
49+
Serial.print(encoder1.getRawCount());
50+
Serial.print(" Encoder1 vel [counts/sec]: ");
51+
Serial.println(encoder1.getCountPerSecond());
52+
Serial.print("Encoder2 Pos [counts]: ");
53+
Serial.print(encoder2.getRawCount());
54+
Serial.print(" Encoder2 vel [counts/sec]: ");
55+
Serial.println(encoder2.getCountPerSecond());
56+
Serial.println("");
57+
58+
//Keep active the communication MKR1000 & MKRMotorCarrier
59+
//Ping the samd11
60+
controller.ping();
61+
//wait
62+
delay(50);
63+
}

examples/Nano/IMU_Test/IMU_Test.ino

Lines changed: 89 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,89 @@
1+
/*
2+
***************************************************************************
3+
4+
Euler_Streaming.pde - part of sample SW for using BNO055 with Arduino
5+
6+
(C) All rights reserved by ROBERT BOSCH GMBH
7+
8+
Copyright (C) 2014 Bosch Sensortec GmbH
9+
10+
This program is free software: you can redistribute it and/or modify
11+
it under the terms of the GNU General Public License as published by
12+
the Free Software Foundation, either version 3 of the License, or
13+
(at your option) any later version.
14+
15+
This program is distributed in the hope that it will be useful,
16+
but WITHOUT ANY WARRANTY; without even the implied warranty of
17+
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18+
GNU General Public License for more details.
19+
20+
You should have received a copy of the GNU General Public License
21+
along with this program. If not, see <http://www.gnu.org/licenses/>.
22+
23+
**************************************************************************/
24+
/* Date: 2014/01/07
25+
Revision: 1.2
26+
27+
*/
28+
29+
#include "BNO055_support.h" //Contains the bridge code between the API and Arduino
30+
#include <Wire.h>
31+
32+
//The device address is set to BNO055_I2C_ADDR2 in this example. You can change this in the BNO055.h file in the code segment shown below.
33+
// /* bno055 I2C Address */
34+
// #define BNO055_I2C_ADDR1 0x28
35+
// #define BNO055_I2C_ADDR2 0x29
36+
// #define BNO055_I2C_ADDR BNO055_I2C_ADDR2
37+
38+
//Pin assignments as tested on the Arduino Due.
39+
//Vdd,Vddio : 3.3V
40+
//GND : GND
41+
//SDA/SCL : SDA/SCL
42+
//PSO/PS1 : GND/GND (I2C mode)
43+
44+
//This structure contains the details of the BNO055 device that is connected. (Updated after initialization)
45+
struct bno055_t myBNO;
46+
struct bno055_euler myEulerData; //Structure to hold the Euler data
47+
48+
unsigned long lastTime = 0;
49+
50+
void setup() //This code is executed once
51+
{
52+
//Initialize I2C communication
53+
Wire.begin();
54+
55+
//Initialization of the BNO055
56+
BNO_Init(&myBNO); //Assigning the structure to hold information about the device
57+
58+
//Configuration to NDoF mode
59+
bno055_set_operation_mode(OPERATION_MODE_NDOF);
60+
61+
delay(1);
62+
63+
//Initialize the Serial Port to view information on the Serial Monitor
64+
Serial.begin(115200);
65+
}
66+
67+
void loop() //This code is looped forever
68+
{
69+
if ((millis() - lastTime) >= 100) //To stream at 10Hz without using additional timers
70+
{
71+
lastTime = millis();
72+
73+
bno055_read_euler_hrp(&myEulerData); //Update Euler data into the structure
74+
75+
Serial.print("Time Stamp: "); //To read out the Time Stamp
76+
Serial.println(lastTime);
77+
78+
Serial.print("Heading(Yaw): "); //To read out the Heading (Yaw)
79+
Serial.println(float(myEulerData.h) / 16.00); //Convert to degrees
80+
81+
Serial.print("Roll: "); //To read out the Roll
82+
Serial.println(float(myEulerData.r) / 16.00); //Convert to degrees
83+
84+
Serial.print("Pitch: "); //To read out the Pitch
85+
Serial.println(float(myEulerData.p) / 16.00); //Convert to degrees
86+
87+
Serial.println(); //Extra line to differentiate between packets
88+
}
89+
}

0 commit comments

Comments
 (0)