Skip to content

Commit 8d4e432

Browse files
santerioksanensanteriok
and
santeriok
authored
Fix base_controller build (#90)
* unsigned long -> int * Add teensy40 * Add script for raspi setup * Make raspi setup executable * Run with bash * Raspi setup script * Add github action to build base controller for teensy4 * Change folder * typo --------- Co-authored-by: santeriok <[email protected]>
1 parent 0aca693 commit 8d4e432

File tree

4 files changed

+73
-2
lines changed

4 files changed

+73
-2
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
name: Build base controller
2+
on:
3+
push:
4+
branches:
5+
- "**"
6+
pull_request:
7+
types: [opened, synchronize, reopened]
8+
9+
jobs:
10+
build_teensy_40:
11+
runs-on: ubuntu-latest
12+
strategy:
13+
fail-fast: true
14+
15+
steps:
16+
- uses: actions/checkout@v3
17+
- uses: actions/cache@v3
18+
with:
19+
path: |
20+
~/.cache/pip
21+
~/.platformio/.cache
22+
key: ${{ runner.os }}-pio
23+
- uses: actions/setup-python@v4
24+
with:
25+
python-version: '3.9'
26+
- name: Install PlatformIO Core
27+
run: pip install --upgrade platformio
28+
29+
- name: Build PlatformIO Project
30+
run: |
31+
cd diffbot_base/scripts/base_controller
32+
pio run

diffbot_base/scripts/base_controller/lib/base_controller/base_controller.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -342,7 +342,7 @@ namespace diffbot {
342342
// Measured left and right joint states (angular position (rad) and angular velocity (rad/s))
343343
diffbot::JointState joint_state_left_, joint_state_right_;
344344

345-
unsigned long encoder_resolution_;
345+
int encoder_resolution_;
346346

347347
ros::Subscriber<std_msgs::Empty, BaseController<TMotorController, TMotorDriver>> sub_reset_encoders_;
348348

diffbot_base/scripts/base_controller/platformio.ini

+11-1
Original file line numberDiff line numberDiff line change
@@ -9,12 +9,22 @@
99
; https://docs.platformio.org/page/projectconf.html
1010

1111
[platformio]
12-
default_envs = teensy31
12+
default_envs = teensy40
1313

1414
[env:teensy31]
1515
platform = teensy
1616
board = teensy31
1717
framework = arduino
18+
lib_deps =
19+
frankjoshua/Rosserial Arduino Library@^0.9.1
20+
./lib
21+
adafruit/Adafruit Motor Shield V2 Library@^1.0.11
22+
Wire
23+
24+
[env:teensy40]
25+
platform = teensy
26+
board = teensy40
27+
framework = arduino
1828
lib_deps =
1929
frankjoshua/Rosserial Arduino Library@^0.9.1
2030
./lib

raspi-setup.sh

+29
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
#!/bin/bash
2+
# update & upgrade #
3+
sudo apt update
4+
sudo apt upgrade
5+
6+
sudo apt -y install i2c-tools curl
7+
8+
# Add i2c support to /boot/firmware/config.txt
9+
# dtparam=i2c0=on
10+
sudo sed -i '/dtparam=i2c0=on/s/^#//g' /boot/firmware/config.txt
11+
12+
# ROS Noetic setup
13+
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
14+
curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
15+
sudo apt -y update
16+
sudo apt -y install ros-noetic-ros-base
17+
18+
sudo apt -y install python3-rosdep python3-rosinstall python3-rosinstall-generator python3-vcstool \
19+
python3-rosdep python3-catkin-tools build-essential
20+
21+
sudo rosdep init
22+
rosdep update
23+
echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc
24+
source ~/.bashrc
25+
26+
cd ~/catkin_ws
27+
rosdep install --from-paths src --ignore-src -r -y
28+
29+
catkin build

0 commit comments

Comments
 (0)