Skip to content

Commit

Permalink
first version of DC Motor Lib
Browse files Browse the repository at this point in the history
  • Loading branch information
chpoulter committed Aug 21, 2021
0 parents commit f4291a1
Show file tree
Hide file tree
Showing 7 changed files with 1,070 additions and 0 deletions.
5 changes: 5 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/build
firmware.hex
.cproject
.project
/.settings
674 changes: 674 additions & 0 deletions LICENSE

Large diffs are not rendered by default.

70 changes: 70 additions & 0 deletions Makefile
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
ORACCRSC := /daten/Projekte/Calliope/OpenRoberta/ora-cc-rsc/RobotMbed/libs2017
BUILD := build

MICROBITPATH := $(ORACCRSC)/microbit
MICROBITDALPATH := $(ORACCRSC)/microbit-dal
MBEDCLASSICPATH := $(ORACCRSC)/mbed-classic
BLEPATH := $(ORACCRSC)/ble
BLE_BOOTLOADER_RESERVED_HEX := $(ORACCRSC)/BLE_BOOTLOADER_RESERVED.hex
S110NRF51822_HEX := $(ORACCRSC)/s110_nrf51822_8.0.0_softdevice.hex
NRF51822 := $(ORACCRSC)/NRF51822.ld

CPPLAGS := -fno-exceptions -fno-unwind-tables -ffunction-sections -fdata-sections -Wdeprecated -Wno-unused-variable -Wall -Wextra -fno-rtti -fno-threadsafe-statics -mtune=cortex-m0 -mthumb -D__thumb2__ -std=c++11 -fwrapv -Os -g -gdwarf-3 -DNDEBUG -DTOOLCHAIN_GCC -DTOOLCHAIN_GCC_ARM -DMBED_OPERATORS -DNRF51 -DTARGET_NORDIC -DTARGET_M0 -D__MBED__=1 -DMCU_NORDIC_16K -DTARGET_NRF51_CALLIOPE -DTARGET_MCU_NORDIC_16K -DTARGET_MCU_NRF51_16K_S110 -DTARGET_NRF_LFCLK_RC -DTARGET_MCU_NORDIC_16K -D__CORTEX_M0 -DARM_MATH_CM0 -MMD
LDFLAGS := -fno-exceptions -fno-unwind-tables -Wl,--no-wchar-size-warning -Wl,--gc-sections -Wl,--sort-common -Wl,--sort-section=alignment -Wl,-wrap,main -mcpu=cortex-m0 -mthumb --specs=nano.specs

INCLIB := -I $(MICROBITDALPATH)/inc/drivers \
-I $(MICROBITDALPATH)/inc/core \
-I $(MICROBITDALPATH)/inc/platform \
-I $(MBEDCLASSICPATH)/api \
-I $(MBEDCLASSICPATH)/targets/hal/TARGET_NORDIC/TARGET_MCU_NRF51822/TARGET_NRF51_CALLIOPE \
-I $(MBEDCLASSICPATH)/targets/hal/TARGET_NORDIC/TARGET_MCU_NRF51822 \
-I $(MBEDCLASSICPATH)/targets/cmsis/TARGET_NORDIC/TARGET_MCU_NRF51822 \
-I $(MBEDCLASSICPATH)/targets/cmsis \
-I $(MBEDCLASSICPATH)/hal

INCDEMO := $(INCLIB) \
-I $(MICROBITPATH)/inc \
-I $(BLEPATH) \
-I $(MICROBITDALPATH)/inc/types \
-I $(MICROBITDALPATH)/inc/bluetooth

LDLIBS := -lnosys -lstdc++ -lsupc++ -lm -lc -lgcc -lstdc++ -lsupc++ -lm -lc -lgcc
CALLIOPELIBS := $(ORACCRSC)/microbit.a \
$(ORACCRSC)/ble.a \
$(ORACCRSC)/microbit-dal.a \
$(ORACCRSC)/ble-nrf51822.a \
$(ORACCRSC)/nrf51-sdk.a \
$(ORACCRSC)/mbed-classic.a

all: directories lib demo

directories:
mkdir -p $(BUILD)

lib: DcMotor.a

demo: firmware.hex


firmware.hex: MotorTest.hex
srec_cat $(BLE_BOOTLOADER_RESERVED_HEX) -intel $(S110NRF51822_HEX) -intel $(BUILD)/$< -intel -o $@ -intel --line-length=44

MotorTest.hex: MotorTest
arm-none-eabi-objcopy -O ihex $(BUILD)/$< $(BUILD)/$@

MotorTest: MotorTest.o DcMotor.a
arm-none-eabi-g++ $(LDFLAGS) -T $(NRF51822) -Wl,-Map,$(BUILD)/MotorTest.map -Wl,--start-group $(foreach i,$^,$(BUILD)/$(i)) $(LDLIBS) $(CALLIOPELIBS) -Wl,-end-group -o $(BUILD)/$@

MotorTest.o: src/MotorTest.cpp
arm-none-eabi-g++ $(INCDEMO) $(CPPLAGS) -MT $(BUILD)/$@.cpp.o -MF $(BUILD)/$@.cpp.o.d -o $(BUILD)/$@ -c $<

DcMotor.a: DcMotor.o
ar rvs $(BUILD)/$@ $(BUILD)/$^

DcMotor.o: src/DcMotor.cpp
arm-none-eabi-g++ $(INCLIB) $(CPPLAGS) -MT $(BUILD)/$@.o -MF $(BUILD)/$@.o.d -c -o $(BUILD)/$@ $<

clean:
-rm firmware.hex $(BUILD)/*
-rmdir $(BUILD)

34 changes: 34 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# DC Motor Library and Demo

This repository contains a library to control the DC Motor Module with the Calliope Mini and an example program.

## Compiling the firmware

You will need the Calliope development files from OpenRoberta. Just clone '[OpenRoberta/ora-cc-rsc/](https://github.com/OpenRoberta/ora-cc-rsc)' and adjust path
variable in the Makefile.

## Contact

Christian Poulter <devel@poulter.de>
Homepage: https://www.poulter.de
BLOG: https://blog.poulter.de
Project: https://blog.poulter.de/projekte/motorsteuerung-calliope-mini-lego-motor.html

## License and warranty
```
Copyright (C) 2021 Christian Poulter <devel@poulter.de>
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <https://www.gnu.org/licenses/>
or the LICENCE file.
```
137 changes: 137 additions & 0 deletions src/DcMotor.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,137 @@
/*
* DC Motor Lib
*
* Copyright (C) 2021 Christian Poulter
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/

#include "DcMotor.h"

// Pins: PWM dir1 dir2
const uint8_t DcMotor::PINS[4][3] = {
{ 8, 10, 9},
{ 13, 11, 12},
{ 2, 4, 3},
{ 7, 5, 6},
};

DcMotor::DcMotor() : i2c(SDA, SCL) {}

void DcMotor::init() {
writeI2C(PCA9685_REGISTER_MODE1, 0x00);
writeI2C(PCA9685_REGISTER_MODE1, 0x10);
writeI2C(PCA9685_REGISTER_PRESCALE, PRESCALE_VALUE);
writeI2C(PCA9685_REGISTER_MODE1, 0x00);

wait_ms(5);

writeI2C(PCA9685_REGISTER_MODE1, 0xa1);

allOff();
}

void DcMotor::allOff() {
for (uint8_t i = 0; i < 16; i++) writeI2C(i, 0, 0, 0x10, 0);
}

void DcMotor::release() {
allOff();
writeI2C(PCA9685_REGISTER_MODE1, 0x08);
}

void DcMotor::set(Motor motor, int8_t speed) {
if (speed > 0) {
setSpeed(motor, speed * 41);
setDirection(motor, Direction::Forward);

} else if (speed < 0) {
setSpeed(motor, speed * -41);
setDirection(motor, Direction::Backward);

} else {
setSpeed(motor, 0);
setDirection(motor, Direction::Stop);
}
}

void DcMotor::set(Motor motor, Direction direction, uint16_t speed) {
setSpeed(motor, speed);
setDirection(motor, direction);
}

void DcMotor::setSpeed(Motor motor, uint16_t speed) {
uint8_t pin = PINS[static_cast<int>(motor)][0];

if (speed == 0)
writeI2C(pin, 0, 0, 0x10, 0); // full OFF

else if (speed > 4095)
writeI2C(pin, 0x10, 0, 0, 0); // full ON

else
writeI2C(pin, 0, 0, speed >> 8, speed & 0xFF); // pwm ON

}

void DcMotor::setDirection(Motor motor, Direction direction) {
uint8_t pin1 = PINS[static_cast<int>(motor)][1];
uint8_t pin2 = PINS[static_cast<int>(motor)][2];

switch(direction) {
case Direction::Forward:
setPin(pin2, false);
setPin(pin1, true);
break;

case Direction::Backward:
setPin(pin1, false);
setPin(pin2, true);
break;

case Direction::Stop:
setPin(pin1, false);
setPin(pin2, false);
break;
}
}

// internal sets
void DcMotor::setPin(uint8_t pin, bool value) {
if (value)
writeI2C(pin, 0x10, 0, 0, 0); // ON
else
writeI2C(pin, 0, 0, 0x10, 0); // OFF
}

// I2C read / write
void DcMotor::writeI2C(uint8_t reg, uint8_t value) {
char buffer[2];
buffer[0] = reg;
buffer[1] = value;

i2c.write(I2C_ADDRESS, buffer, 2);
}

void DcMotor::writeI2C(uint8_t basereg, uint8_t value1, uint8_t value2, uint8_t value3, uint8_t value4) {
char buffer[5];
buffer[0] = PCA9685_REGISTER_FIRST_LED + 4 * basereg;
buffer[1] = value2;
buffer[2] = value1;
buffer[3] = value4;
buffer[4] = value3;

i2c.write(I2C_ADDRESS, buffer, 5);
}
67 changes: 67 additions & 0 deletions src/DcMotor.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/*
* DC Motor Lib
*
* Copyright (C) 2021 Christian Poulter
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/

#ifndef DCMOTOR_H
#define DCMOTOR_H

#include "MicroBitI2C.h"

enum class Direction { Forward, Backward, Stop };
enum class Motor { M1 = 0, M2 = 1, M3 = 2, M4 = 3 };

class DcMotor {

public:
DcMotor();

void init();
void release();
void set(Motor motor, int8_t speed);
void set(Motor motor, Direction direction, uint16_t speed);
void setSpeed(Motor motor, uint16_t speed);
void setDirection(Motor motor, Direction direction);

private:
I2C i2c;

void allOff();
void setPin(uint8_t pin, bool value);
void writeI2C(uint8_t reg, uint8_t value);
void writeI2C(uint8_t startreg, uint8_t value1, uint8_t value2, uint8_t value3, uint8_t value4);

static const uint8_t PINS[4][3];

static const uint8_t I2C_ADDRESS = (0x60 << 1);

static const uint8_t PCA9685_REGISTER_PRESCALE = 0xFE;
static const uint8_t PCA9685_REGISTER_MODE1 = 0x0;
static const uint8_t PCA9685_REGISTER_FIRST_LED = 0x6;

static const uint8_t PRESCALE_VALUE = 1;

static const PinName SDA = I2C_SDA0;
static const PinName SCL = I2C_SCL0;

// Pre scale calculation: round(25MHz/(4096*freq)) - 1
// good values for freq could be 1.2-5.0 kHz

};

#endif
Loading

0 comments on commit f4291a1

Please sign in to comment.