Skip to content

Commit

Permalink
Fix base_controller build (#90)
Browse files Browse the repository at this point in the history
* 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]>
  • Loading branch information
santerioksanen and santeriok committed Apr 2, 2024
1 parent 0aca693 commit 8d4e432
Show file tree
Hide file tree
Showing 4 changed files with 73 additions and 2 deletions.
32 changes: 32 additions & 0 deletions .github/workflows/build_base_controller.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
name: Build base controller
on:
push:
branches:
- "**"
pull_request:
types: [opened, synchronize, reopened]

jobs:
build_teensy_40:
runs-on: ubuntu-latest
strategy:
fail-fast: true

steps:
- uses: actions/checkout@v3
- uses: actions/cache@v3
with:
path: |
~/.cache/pip
~/.platformio/.cache
key: ${{ runner.os }}-pio
- uses: actions/setup-python@v4
with:
python-version: '3.9'
- name: Install PlatformIO Core
run: pip install --upgrade platformio

- name: Build PlatformIO Project
run: |
cd diffbot_base/scripts/base_controller
pio run
Original file line number Diff line number Diff line change
Expand Up @@ -342,7 +342,7 @@ namespace diffbot {
// Measured left and right joint states (angular position (rad) and angular velocity (rad/s))
diffbot::JointState joint_state_left_, joint_state_right_;

unsigned long encoder_resolution_;
int encoder_resolution_;

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

Expand Down
12 changes: 11 additions & 1 deletion diffbot_base/scripts/base_controller/platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,22 @@
; https://docs.platformio.org/page/projectconf.html

[platformio]
default_envs = teensy31
default_envs = teensy40

[env:teensy31]
platform = teensy
board = teensy31
framework = arduino
lib_deps =
frankjoshua/Rosserial Arduino Library@^0.9.1
./lib
adafruit/Adafruit Motor Shield V2 Library@^1.0.11
Wire

[env:teensy40]
platform = teensy
board = teensy40
framework = arduino
lib_deps =
frankjoshua/Rosserial Arduino Library@^0.9.1
./lib
Expand Down
29 changes: 29 additions & 0 deletions raspi-setup.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
#!/bin/bash
# update & upgrade #
sudo apt update
sudo apt upgrade

sudo apt -y install i2c-tools curl

# Add i2c support to /boot/firmware/config.txt
# dtparam=i2c0=on
sudo sed -i '/dtparam=i2c0=on/s/^#//g' /boot/firmware/config.txt

# ROS Noetic setup
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
sudo apt -y update
sudo apt -y install ros-noetic-ros-base

sudo apt -y install python3-rosdep python3-rosinstall python3-rosinstall-generator python3-vcstool \
python3-rosdep python3-catkin-tools build-essential

sudo rosdep init
rosdep update
echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc
source ~/.bashrc

cd ~/catkin_ws
rosdep install --from-paths src --ignore-src -r -y

catkin build

0 comments on commit 8d4e432

Please sign in to comment.