Skip to content

Commit 2bc1fb7

Browse files
committed
Merge branch 'release/0.2.1'
2 parents c027c16 + 7f9fee7 commit 2bc1fb7

File tree

6 files changed

+163
-147
lines changed

6 files changed

+163
-147
lines changed

README.md

Lines changed: 14 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1,22 +1,27 @@
1+
[![Gitter](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/legoinochat?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge)
2+
13
# Legoino
24
Arduino Library for controlling Powered UP and Boost controllers
35

46
*Disclaimer*: LEGO® is a trademark of the LEGO Group of companies which does not sponsor, authorize or endorse this project.
57

6-
Simple Train example
8+
Simple Train example (just click the image to see the video)
79

810
[![Legoino TrainHub example](http://img.youtube.com/vi/o1hgZQz3go4/0.jpg)](http://www.youtube.com/watch?v=o1hgZQz3go4 "Legoino TrainHub example")
911

10-
Simple Boost movement example
12+
Simple Boost movement example (just click the image to see the video)
1113

1214
[![Legoino BoostHub simple movements example](http://img.youtube.com/vi/VgWObhyUmi0/0.jpg)](http://www.youtube.com/watch?v=VgWObhyUmi0 "Legoino BoostHub simple movements example")
1315

1416
Up to now the Library is only teseted for a Powered Up Train controllers and Boost controllers. You can connect to your HUB, set the LED color, set the Hub name, control the motors (speed, port, movements) and shut down the HUB via a Arduino command. Up to now the notifications of the hub and the reading of the sensors are not supported. But this feature will come in the next release.
1517

18+
# Examples
19+
You can find 3 Examples called "BasicHub.ino", "BoostHub.ino" and "TrainHub.ino" in the "examples" folder. You can select the examples in your Arduino IDE via the Menu "File->Examples".
20+
1621
# Setup and Usage
17-
Just install the Libray via the Arduino Library Manager.
22+
Just install the Library via the Arduino Library Manager.
1823

19-
The usage is dependent on your hub type. Some basic commands are shared for the hubs and are covered in the Lpf2Hub library. Some other commands ar hub specific (e.g. Boost movement). The hub dependent usage is described below.
24+
The usage is dependent on your hub type. Some basic commands are shared for the hubs and are covered in the Lpf2Hub library. Some other commands ar hub specific (e.g. Boost movement).
2025

2126
## Boost Hub
2227
Add the follwoing include in your *.ino sketch
@@ -45,7 +50,7 @@ In the main ```loop``` just add the following connection flow
4550
}
4651
```
4752
48-
Now you are ready to control your actuators or your Hub
53+
Now you are ready to control your actuators on your Hub
4954
5055
### Hub control
5156
You can define the display name of the Hub (e.g. displayed in the PoweredUp Apps) with the following command.
@@ -165,7 +170,7 @@ In the main ```loop``` just add the following connection flow
165170
}
166171
}
167172
```
168-
Now you are ready to control your actuators or your Hub
173+
Now you are ready to control your actuators on your Hub
169174
170175
### Hub control
171176
You can define the display name of the Hub (e.g. displayed in the PoweredUp Apps) with the following command.
@@ -208,23 +213,20 @@ myTrainHub.stopMotor(A); // Stop motor on Port A
208213
myTrainHub.stopMotor(); // Stop all motors (Port A and Port B)
209214
```
210215

211-
# Examples
212-
You can find 3 Examples called "BasicHub.ino", "BoostHub.ino" and "TrainHub.ino" in the "examples" folder. You can select the examples in your Arduino IDE via the Menu "File->Examples".
213-
214216
# Arduino Hardware
215217
The library is implemented for the ESP32 Boards and does use the ESP32_BLE_Arduino Library.
216218

217219
# Credits
218220
Hands up to Lego, that they have recently open-sourced the Specification
219221
https://github.com/LEGO/lego-ble-wireless-protocol-docs
220222

221-
Thanks to JorgePe and all contributors for the reverse engenieering part
223+
Thanks to [@JorgePe](https://github.com/JorgePe) and all contributors for the reverse engenieering part
222224
https://github.com/JorgePe/BOOSTreveng
223225

224-
Thanks to jakorten for his SWIFT iOS App
226+
Thanks to [@jakorten](https://github.com/jakorten) for his SWIFT iOS App
225227
https://github.com/jakorten/UpControl
226228

227-
Thanks Nathan Kellenicki for his brilliant structured node module
229+
Thanks [@nathankellenicki](https://github.com/nathankellenicki) for his brilliant structured node module
228230
https://github.com/nathankellenicki/node-poweredup
229231

230232
# Remarks

src/BoostHub.cpp

Lines changed: 34 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ void BoostHub::setMotorSpeed(Port port, int speed)
2727
* @param [in] time Time value in ms of the acceleration from 0-100% speed/Power
2828
* @param [in] profileNumber Number for which the acceleration profile is stored
2929
*/
30-
void BoostHub::setAccelerationProfile(Port port, int16_t time, int8_t profileNumber)
30+
void BoostHub::setAccelerationProfile(Port port, int16_t time, int8_t profileNumber)
3131
{
3232
byte *timeBytes = Int16ToByteArray(time);
3333
byte setMotorCommand[7] = {0x81, port, 0x10, 0x05, timeBytes[0], timeBytes[1], profileNumber};
@@ -40,7 +40,7 @@ void BoostHub::setAccelerationProfile(Port port, int16_t time, int8_t profileNum
4040
* @param [in] time Time value in ms of the deceleration from 100-0% speed/Power
4141
* @param [in] profileNumber Number for which the deceleration profile is stored
4242
*/
43-
void BoostHub::setDecelerationProfile(Port port, int16_t time, int8_t profileNumber)
43+
void BoostHub::setDecelerationProfile(Port port, int16_t time, int8_t profileNumber)
4444
{
4545
byte *timeBytes = Int16ToByteArray(time);
4646
byte setMotorCommand[7] = {0x81, port, 0x10, 0x06, timeBytes[0], timeBytes[1], profileNumber};
@@ -103,76 +103,90 @@ void BoostHub::stopMotor(Port port = AB)
103103
* @brief Move forward (Port AB) with the default speed and stop after the number of steps
104104
* @param [in] steps Number of steps (Boost grid)
105105
*/
106-
void BoostHub::moveForward(int steps) {
106+
void BoostHub::moveForward(int steps)
107+
{
107108
Port port = AB;
108109
Port portA = A;
109110
Port portB = B;
110111
setDecelerationProfile(portA, 1000, 0);
111112
setDecelerationProfile(portB, 1000, 0);
112-
setMotorSpeedForDegrees(port, 50, steps*360*2);
113+
setMotorSpeedForDegrees(port, 50, steps * 360 * 2);
113114
}
114115

115116
/**
116117
* @brief Move back (Port AB) with the default speed and stop after the number of steps
117118
* @param [in] steps Number of steps (Boost grid)
118119
*/
119-
void BoostHub::moveBack(int steps) {
120+
void BoostHub::moveBack(int steps)
121+
{
120122
Port port = AB;
121-
setMotorSpeedForDegrees(port, -50, steps*360*2);
123+
setMotorSpeedForDegrees(port, -50, steps * 360 * 2);
122124
}
123125

124126
/**
125127
* @brief rotate (Port AB) with the default speed and stop after the degrees
126128
* @param [in] degrees (negative: left, positive: right)
127129
*/
128-
void BoostHub::rotate(int degrees) {
129-
if (degrees > 0) {
130+
void BoostHub::rotate(int degrees)
131+
{
132+
if (degrees > 0)
133+
{
130134
// right
131-
setMotorSpeedsForDegrees(-50, 50, degrees*4.5);
132-
} else {
135+
setMotorSpeedsForDegrees(-50, 50, degrees * 4.5);
136+
}
137+
else
138+
{
133139
// left
134-
setMotorSpeedsForDegrees(50, -50, degrees*4.5);
140+
setMotorSpeedsForDegrees(50, -50, degrees * 4.5);
135141
}
136142
}
137143

138144
/**
139145
* @brief rotate left (Port AB) with the default speed and stop after degrees (default 90)
140146
* @param [in] degrees (default 90)
141147
*/
142-
void BoostHub::rotateLeft(int degrees = 90) {
148+
void BoostHub::rotateLeft(int degrees = 90)
149+
{
143150
rotate(-degrees);
144151
}
145152

146153
/**
147154
* @brief rotate right (Port AB) with the default speed and stop after degrees (default 90)
148155
* @param [in] degrees (default 90)
149156
*/
150-
void BoostHub::rotateRight(int degrees = 90) {
157+
void BoostHub::rotateRight(int degrees = 90)
158+
{
151159
rotate(degrees);
152160
}
153161

154162
/**
155163
* @brief move an arc (Port AB) with the default speed and stop after degrees
156164
* @param [in] degrees (negative: left, positive: right)
157165
*/
158-
void BoostHub::moveArc(int degrees) {
159-
if (degrees > 0) {
166+
void BoostHub::moveArc(int degrees)
167+
{
168+
if (degrees > 0)
169+
{
160170
// right
161-
setMotorSpeedsForDegrees(60, 20, degrees*12);
162-
} else {
171+
setMotorSpeedsForDegrees(60, 20, degrees * 12);
172+
}
173+
else
174+
{
163175
// left
164-
setMotorSpeedsForDegrees(20, 60, degrees*12);
176+
setMotorSpeedsForDegrees(20, 60, degrees * 12);
165177
}
166178
}
167179

168180
/**
169181
* @brief move an arc left (Port AB) with the default speed and stop after degrees (default 90)
170182
* @param [in] degrees (default 90)
171183
*/
172-
void BoostHub::moveArcLeft(int degrees = 90) {
184+
void BoostHub::moveArcLeft(int degrees = 90)
185+
{
173186
moveArc(-degrees);
174187
}
175188

176-
void BoostHub::moveArcRight(int degrees= 90) {
189+
void BoostHub::moveArcRight(int degrees = 90)
190+
{
177191
moveArc(degrees);
178192
}

src/BoostHub.h

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,7 @@
1616
class BoostHub : public Lpf2Hub
1717
{
1818
public:
19-
20-
//Port definitions specific to Boost Hubs
19+
//Port definitions specific to Boost Hubs
2120
enum Port
2221
{
2322
A = 0x37,

src/Lpf2Hub.cpp

Lines changed: 29 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,11 @@
1313
*/
1414
class Lpf2HubAdvertisedDeviceCallbacks : public BLEAdvertisedDeviceCallbacks
1515
{
16-
Lpf2Hub* _lpf2Hub;
17-
public:
18-
Lpf2HubAdvertisedDeviceCallbacks(Lpf2Hub* lpf2Hub) : BLEAdvertisedDeviceCallbacks() {
16+
Lpf2Hub *_lpf2Hub;
17+
18+
public:
19+
Lpf2HubAdvertisedDeviceCallbacks(Lpf2Hub *lpf2Hub) : BLEAdvertisedDeviceCallbacks()
20+
{
1921
_lpf2Hub = lpf2Hub;
2022
}
2123

@@ -36,18 +38,19 @@ class Lpf2HubAdvertisedDeviceCallbacks : public BLEAdvertisedDeviceCallbacks
3638
* @param [in] command byte array which contains the ble command
3739
* @param [in] size length of the command byte array
3840
*/
39-
void Lpf2Hub::WriteValue(byte command[], int size) {
40-
byte commandWithCommonHeader[size+2] = {size+2, 0x00};
41-
memcpy(commandWithCommonHeader+2, command, size);
41+
void Lpf2Hub::WriteValue(byte command[], int size)
42+
{
43+
byte commandWithCommonHeader[size + 2] = {size + 2, 0x00};
44+
memcpy(commandWithCommonHeader + 2, command, size);
4245
_pRemoteCharacteristic->writeValue(commandWithCommonHeader, sizeof(commandWithCommonHeader), false);
4346
}
4447

45-
4648
/**
4749
* @brief Map speed from -100..100 to the 8bit internal value
4850
* @param [in] speed -100..100
4951
*/
50-
byte Lpf2Hub::MapSpeed(int speed) {
52+
byte Lpf2Hub::MapSpeed(int speed)
53+
{
5154
byte rawSpeed;
5255
if (speed == 0)
5356
{
@@ -64,19 +67,21 @@ byte Lpf2Hub::MapSpeed(int speed) {
6467
return rawSpeed;
6568
}
6669

67-
byte* Lpf2Hub::Int16ToByteArray(int16_t x) {
70+
byte *Lpf2Hub::Int16ToByteArray(int16_t x)
71+
{
6872
static byte y[2];
69-
y[0] = (byte) (x & 0xff);
70-
y[1] = (byte) ((x >> 8) & 0xff);
73+
y[0] = (byte)(x & 0xff);
74+
y[1] = (byte)((x >> 8) & 0xff);
7175
return y;
7276
}
7377

74-
byte* Lpf2Hub::Int32ToByteArray(int32_t x) {
78+
byte *Lpf2Hub::Int32ToByteArray(int32_t x)
79+
{
7580
static byte y[4];
76-
y[0] = (byte) (x & 0xff);
77-
y[1] = (byte) ((x >> 8) & 0xff);
78-
y[2] = (byte) ((x >> 16) & 0xff);
79-
y[3] = (byte) ((x >> 24) & 0xff);
81+
y[0] = (byte)(x & 0xff);
82+
y[1] = (byte)((x >> 8) & 0xff);
83+
y[2] = (byte)((x >> 16) & 0xff);
84+
y[3] = (byte)((x >> 24) & 0xff);
8085
return y;
8186
}
8287

@@ -241,7 +246,6 @@ void Lpf2Hub::parsePortMessage(uint8_t *pData)
241246
{
242247
Serial.print(" is not connected");
243248
}
244-
245249
}
246250

247251
/**
@@ -352,17 +356,15 @@ void Lpf2Hub::notifyCallback(
352356
}
353357
}
354358

355-
356-
357359
Lpf2Hub::Lpf2Hub(){};
358360

359361
/**
360362
* @brief Init function set the UUIDs and scan for the Hub
361363
*/
362364
void Lpf2Hub::init()
363365
{
364-
_isConnected=false;
365-
_isConnecting=false;
366+
_isConnected = false;
367+
_isConnecting = false;
366368
_bleUuid = BLEUUID(LPF2_UUID);
367369
_charachteristicUuid = BLEUUID(LPF2_CHARACHTERISTIC);
368370
_hubType = BOOST_MOVE_HUB;
@@ -374,7 +376,6 @@ void Lpf2Hub::init()
374376

375377
pBLEScan->setActiveScan(true);
376378
pBLEScan->start(30);
377-
378379
}
379380

380381
/**
@@ -437,11 +438,10 @@ void Lpf2Hub::setHubName(char name[])
437438
int arraySize = offset + nameLength;
438439
byte setNameCommand[arraySize] = {0x01, 0x01, 0x01};
439440

440-
memcpy(setNameCommand+offset, name, nameLength);
441+
memcpy(setNameCommand + offset, name, nameLength);
441442
WriteValue(setNameCommand, arraySize);
442443
}
443444

444-
445445
void Lpf2Hub::activateHubUpdates()
446446
{
447447
// Activate reports
@@ -462,10 +462,10 @@ void Lpf2Hub::activateHubUpdates()
462462

463463
byte setFWCommand[3] = {0x01, 0x03, 0x02};
464464
WriteValue(setFWCommand, 3);
465-
465+
466466
byte setHWCommand[3] = {0x01, 0x04, 0x02};
467467
WriteValue(setHWCommand, 3);
468-
468+
469469
byte setBatteryType[3] = {0x01, 0x07, 0x02};
470470
WriteValue(setBatteryType, 3);
471471
}
@@ -485,15 +485,15 @@ bool Lpf2Hub::connectHub()
485485
BLERemoteService *pRemoteService = pClient->getService(_bleUuid);
486486
if (pRemoteService == nullptr)
487487
{
488-
Serial.println("get pClient failed");
488+
Serial.println("get pClient failed");
489489
return false;
490490
}
491-
Serial.println("get pRemoteService");
491+
Serial.println("get pRemoteService");
492492

493493
_pRemoteCharacteristic = pRemoteService->getCharacteristic(_charachteristicUuid);
494494
if (_pRemoteCharacteristic == nullptr)
495495
{
496-
Serial.println("get pRemoteService failed");
496+
Serial.println("get pRemoteService failed");
497497

498498
return false;
499499
}

0 commit comments

Comments
 (0)