Skip to content

Commit 3c40221

Browse files
fix according to master branch
Signed-off-by: yamahatayukiya <[email protected]>
1 parent 08fc29b commit 3c40221

20 files changed

+2472
-84
lines changed

.github/workflows/arduino_ci.yaml

+52
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
---
2+
name: Arduino_CI
3+
4+
on:
5+
push:
6+
branches: [ master, ros2 ]
7+
8+
jobs:
9+
arduino_ci:
10+
needs: [ cpplint, uncrustify ]
11+
runs-on: ubuntu-20.04
12+
steps:
13+
- uses: actions/checkout@v3
14+
- uses: arduino/compile-sketches@v1
15+
with:
16+
sketch-paths: |
17+
- .
18+
fqbn: "esp32:esp32:esp32"
19+
platforms: |
20+
- source-url: https://dl.espressif.com/dl/package_esp32_index.json
21+
name: esp32:esp32
22+
libraries: |
23+
- name: Rosserial Arduino Library
24+
version: 0.9.1
25+
- name: Adafruit BNO055
26+
- name: Adafruit BME280 Library
27+
- name: Adafruit MPR121
28+
- name: arduino-timer
29+
- name: ESP32 AnalogWrite
30+
31+
cpplint:
32+
runs-on: ubuntu-latest
33+
steps:
34+
- name: Setup cpplint
35+
run: |
36+
sudo apt install python3-pip
37+
pip install cpplint
38+
- uses: actions/checkout@v3
39+
- name: Run cpplint
40+
run: |
41+
cpplint --recursive .
42+
43+
uncrustify:
44+
runs-on: ubuntu-latest
45+
steps:
46+
- name: Setup uncrustify
47+
run: |
48+
sudo apt-get install -y uncrustify
49+
- uses: actions/checkout@v3
50+
- name: Run uncrustify
51+
run: |
52+
ls *.ino *.h *.cpp | uncrustify -c code_style.cfg --check -F -

BarometerReader.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
* THE SOFTWARE.
2121
*******************************************************************************/
2222

23-
#include "BarometerReader.hpp"
23+
#include "BarometerReader.hpp" // NOLINT
2424

2525
BarometerReader::BarometerReader(cabot::Handle & ch)
2626
: SensorReader(ch) {}

ButtonsReader.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
* THE SOFTWARE.
2121
*******************************************************************************/
2222

23-
#include "ButtonsReader.hpp"
23+
#include "ButtonsReader.hpp" // NOLINT
2424

2525
ButtonsReader::ButtonsReader(cabot::Handle & ch, uart_com & cm)
2626
: SensorReader(ch), cm(cm) {}

CPPLINT.cfg

+9
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
set noparent
2+
extensions=c,cpp,h,hpp,ino
3+
linelength=120
4+
filter=-build/c++11
5+
filter=-runtime/references
6+
filter=-whitespace/braces
7+
filter=-whitespace/indent
8+
filter=-whitespace/parens
9+
filter=-whitespace/semicolon

CaBotHandle.cpp

+10-10
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
* THE SOFTWARE.
2121
*******************************************************************************/
2222

23-
#include "CaBotHandle.hpp"
23+
#include "CaBotHandle.hpp" // NOLINT
2424

2525
// #define DEBUG 1
2626

@@ -103,15 +103,15 @@ void Handle::spinOnce()
103103
need_to_update = true;
104104
} else {
105105
snprintf(
106-
buff, sizeof(buff), "large time jump %lu.%09lu -> %lu.%09lu",
106+
buff, sizeof(buff), "large time jump %u.%09u -> %u.%09u",
107107
prev.sec, prev.nsec, current.sec, current.nsec);
108108
logwarn(buff);
109109
}
110110

111111
// #ifdef DEBUG
112112
snprintf(
113113
buff, sizeof(buff),
114-
"sync,%lu,%lu.%03lu,%lu.%03lu,%lu.%03lu,%ld,%ld,%ld,%ld", ms,
114+
"sync,%u,%u.%03u,%u.%03u,%u.%03u,%d,%d,%d,%d", ms,
115115
newTime.sec, newTime.nsec / 1000000, prev.sec, prev.nsec / 1000000,
116116
current.sec, current.nsec / 1000000, jump, turn_around_time,
117117
back_time, temp);
@@ -145,11 +145,11 @@ void Handle::subscribe(uint8_t cmd, void (* callback)(const uint8_t))
145145

146146
void Handle::logdebug(char * text) {sendCommand(0x02, text, strlen(text));}
147147

148-
void Handle::loginfo(char * text) {sendCommand(0x03, text, strlen(text));}
148+
void Handle::loginfo(const char * text) {sendCommand(0x03, text, strlen(text));}
149149

150-
void Handle::logwarn(char * text) {sendCommand(0x04, text, strlen(text));}
150+
void Handle::logwarn(const char * text) {sendCommand(0x04, text, strlen(text));}
151151

152-
bool Handle::getParam(char * name, int * out, size_t num, int timeout_ms)
152+
bool Handle::getParam(const char * name, int * out, size_t num, int timeout_ms)
153153
{
154154
sendCommand(0x08, name, strlen(name));
155155
uint8_t cmd = 0x08;
@@ -341,7 +341,7 @@ size_t Handle::readCommand(uint8_t * expect, uint8_t ** ptr)
341341
size = (received & 0xFF) << size_count * 8;
342342
size_count += 1;
343343
if (size_count == DATA_MAX_SIZE_BYTE) {
344-
if (size < 0 || sizeof(buffer) < size) {
344+
if (sizeof(buffer) < size) {
345345
state = 0;
346346
return 0;
347347
} else if (size == 0) {
@@ -375,7 +375,7 @@ size_t Handle::readCommand(uint8_t * expect, uint8_t ** ptr)
375375
bool Handle::sendCommand(uint8_t type, uint8_t * data, size_t num)
376376
{
377377
static uint8_t buffer[256 + 6];
378-
if (num < 0 || 256 < num) {
378+
if (256 < num) {
379379
return false;
380380
}
381381

@@ -399,9 +399,9 @@ bool Handle::sendCommand(uint8_t type, uint8_t * data, size_t num)
399399
return true;
400400
}
401401

402-
bool Handle::sendCommand(uint8_t type, char * data, size_t num)
402+
bool cabot::Handle::sendCommand(uint8_t type, const char * data, size_t num)
403403
{
404-
return sendCommand(type, reinterpret_cast<uint8_t *>(data), num);
404+
return sendCommand(type, reinterpret_cast<uint8_t *>(const_cast<char *>(data)), num);
405405
}
406406

407407
uint8_t Handle::checksum(uint8_t * data, size_t num)

CaBotHandle.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -48,9 +48,9 @@ class Handle {
4848
void spinOnce();
4949
void subscribe(uint8_t, void (*)(const uint8_t));
5050
void logdebug(char *);
51-
void loginfo(char *);
52-
void logwarn(char *);
53-
bool getParam(char *, int *, size_t, int);
51+
void loginfo(const char *);
52+
void logwarn(const char *);
53+
bool getParam(const char *, int *, size_t, int);
5454
void publish(uint8_t, uint8_t *, size_t);
5555
void publish(uint8_t, int8_t *, size_t);
5656
void publish(uint8_t, char *, size_t);
@@ -66,7 +66,7 @@ class Handle {
6666
Time _now(Time, uint32_t, uint32_t);
6767
int32_t timeDiff(Time, Time);
6868
bool sendCommand(uint8_t, uint8_t *, size_t);
69-
bool sendCommand(uint8_t, char *, size_t);
69+
bool sendCommand(uint8_t, const char *, size_t);
7070
size_t readCommand(uint8_t *, uint8_t **);
7171
uint8_t checksum(uint8_t *, size_t);
7272
uint32_t parseUInt32(uint8_t * ptr);

Dockerfile

+2-1
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,10 @@
1-
FROM ghcr.io/jpconstantineau/docker_arduino_cli:latest
1+
FROM jpconstantineau/arduino-cli:0.33.0
22

33
RUN arduino-cli config init
44
COPY arduino-cli.yaml arduino-cli.yaml
55
RUN arduino-cli core update-index --config-file arduino-cli.yaml
66
RUN arduino-cli core install esp32:esp32 --additional-urls https://dl.espressif.com/dl/package_esp32_index.json
7+
RUN arduino-cli lib install "Rosserial Arduino Library"@0.9.1
78
RUN arduino-cli lib install "Adafruit BNO055"
89
RUN arduino-cli lib install "Adafruit BME280 Library"
910
RUN arduino-cli lib install "Adafruit MPR121"

Heartbeat.h

+5-3
Original file line numberDiff line numberDiff line change
@@ -30,14 +30,16 @@
3030
#include <analogWrite.h>
3131
#endif
3232

33-
class Heartbeat {
33+
class Heartbeat
34+
{
3435
int led_pin_;
3536
int delay_;
3637
int status_;
3738

3839
public:
3940
Heartbeat(int led_pin, int delay)
40-
: led_pin_(led_pin), delay_(delay), status_(0) {
41+
: led_pin_(led_pin), delay_(delay), status_(0)
42+
{
4143
}
4244

4345
void init()
@@ -49,7 +51,7 @@ class Heartbeat {
4951
void update()
5052
{
5153
status_ = status_ + 1;
52-
analogWrite(led_pin_, (int)(sin(6.28 * status_ * delay_ / 1000.0) * 127 + 127));
54+
analogWrite(led_pin_, static_cast<int>(sin(6.28 * status_ * delay_ / 1000.0) * 127 + 127));
5355
}
5456
};
5557

IMUReader.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
* THE SOFTWARE.
2121
*******************************************************************************/
2222

23-
#include "IMUReader.hpp"
23+
#include "IMUReader.hpp" // NOLINT
2424

2525
#define D2R 0.0174532925
2626

SensorReader.h

+7-4
Original file line numberDiff line numberDiff line change
@@ -26,19 +26,22 @@
2626
#include <Arduino.h>
2727
#ifdef ESP32
2828
#undef ESP32
29-
#include "CaBotHandle.hpp"
29+
#include "CaBotHandle.hpp" // NOLINT
3030
#define ESP32
3131
#else
32-
#include "CaBotHandle.hpp"
32+
#include "CaBotHandle.hpp" // NOLINT
3333
#endif
3434

35-
class SensorReader {
35+
class SensorReader
36+
{
3637
protected:
3738
cabot::Handle & ch_;
3839
bool initialized_;
3940

4041
public:
41-
explicit SensorReader(cabot::Handle & ch) : ch_(ch), initialized_(false) {
42+
explicit SensorReader(cabot::Handle & ch)
43+
: ch_(ch), initialized_(false)
44+
{
4245
}
4346
virtual void init() = 0;
4447
virtual void update() = 0;

TouchReader.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
* THE SOFTWARE.
2121
*******************************************************************************/
2222

23-
#include "TouchReader.hpp"
23+
#include "TouchReader.hpp" // NOLINT
2424

2525
TouchReader::TouchReader(cabot::Handle & ch, uart_com & cm)
2626
: SensorReader(ch), cm(cm) {}

VibratorController.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ VibratorController::VibratorController(cabot::Handle & ch, uart_com & cm)
4646
buf += ",";
4747
buf += String(inst->cm.motor_l);
4848

49-
inst->ch_.loginfo(const_cast<char*>(buf.c_str()));
49+
inst->ch_.loginfo(const_cast<char *>(buf.c_str()));
5050
inst->cm.set_mot_c(ff2percent(msg));
5151
});
5252
ch.subscribe(0x21, [](const uint8_t msg) { /* nop: not supported */});

WiFiReader.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
* THE SOFTWARE.
2121
*******************************************************************************/
2222

23-
#include "WiFiReader.hpp"
23+
#include "WiFiReader.hpp" // NOLINT
2424
#include <algorithm>
2525

2626
extern void restart();
@@ -67,11 +67,11 @@ void WiFiReader::init()
6767

6868
void WiFiReader::showScanStatus()
6969
{
70-
snprintf(buf, buf[256], "%c", "WiFi: ");
70+
snprintf(buf, sizeof(buf), "%s", "WiFi: ");
7171
for (int i = 0; i < n_channel; i++) {
72-
snprintf(buf + strlen(buf), buf[256], "%2d|", aps[i]);
72+
snprintf(buf + strlen(buf), sizeof(buf + strlen(buf)), "%2d|", aps[i]);
7373
}
74-
snprintf(buf + strlen(buf), buf[256], "%2d|", all_zero_count);
74+
snprintf(buf + strlen(buf), sizeof(buf + strlen(buf)), "%2d|", all_zero_count);
7575

7676
callback_(buf);
7777
}
@@ -108,7 +108,7 @@ void WiFiReader::handleScan()
108108
// start scan for the current channcel
109109
//
110110
// definition
111-
int n = WiFi.scanNetworks(true, false, false, scan_duration, channel + 1);
111+
WiFi.scanNetworks(true, false, false, scan_duration, channel + 1);
112112
scanningStart = millis();
113113
count[channel] = 0;
114114
isScanning = true;
@@ -126,7 +126,7 @@ void WiFiReader::handleScan()
126126
showScanStatus();
127127
if (verbose) {
128128
snprintf(
129-
buf, buf[256], "[ch:%2d][%3dAPs][skip:%2d/%2d]%3dms,%5dms",
129+
buf, sizeof(buf), "[ch:%2d][%3dAPs][skip:%2d/%2d]%3lums,%5lums",
130130
channel + 1, n, skip[channel], max_skip,
131131
millis() - scanningStart, millis() - lastseen[channel]);
132132
// ch_.loginfo(buf);
@@ -144,7 +144,7 @@ void WiFiReader::handleScan()
144144
String name = WiFi.SSID(i);
145145
name.replace(",", " ");
146146
snprintf(
147-
msg_buf[waiting], msg_buf[MAX_WAITING][100], "%s,%s,%d,%d,%d,%d",
147+
msg_buf[waiting], sizeof(msg_buf[waiting]), "%s,%s,%d,%d,%d,%d",
148148
WiFi.BSSIDstr(i).c_str(), name.c_str(), WiFi.channel(i),
149149
WiFi.RSSI(i), ch_.now().sec, ch_.now().nsec);
150150
waiting++;

build.sh

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ fi
4141

4242
function build() {
4343
echo "building for $board..."
44-
arduino-cli compile -b $board .
44+
arduino-cli compile -b $board --warnings all .
4545
}
4646

4747
function upload() {

0 commit comments

Comments
 (0)