Skip to content

Linobase Firmware

lawrence edited this page Sep 15, 2019 · 5 revisions

Linobase is the component in charge to control/sense

  • Motor
  • IMU
  • TODO: Eventually GPS? (I guess there is a second i2c free with pin 17 and 16

Before uploading the codes, identify and define your robot’s specification in the config file.

On your robot’s computer, open and edit the lino_base_config.h:

roscd plutobot/teensy/firmware/lib/config

nano lino_base_config.h

Make sure to define variable DEBUG as 1 for debugging later.

// #define DEBUG 1

There's only one firmware for all the supported robot base so you have to define which one you're building.

We use a 2WD differential robot

//uncomment the base you're building #define LINO_BASE DIFFERENTIAL_DRIVE // 2WD and Tracked robot w/ 2 motors

ALL THE OTHER MUST BE COMMENTED

Define your Motor Driver, we use a ESC

//uncomment the motor driver you're using

#define USE_ESC

ALL THE OTHER MUST BE COMMENTED

Define your IMU:

//uncomment the IMU we're using

#define USE_MPU9250_IMU

Define your robot's specification, we use only an ackermann 2wd:

//define your robot' specs here

#define MAX_RPM 330 // motor's maximum RPM, here limit your max RPM. Stay on safe (with 15 cm diameter 180 RPM are around 5 km/h

`#define COUNTS_PER_REV 6*5 // wheel encoder's no of ticks per rev, ACTUALLY THERE IS MOUNTED A RATIO 1:5,ONE MOTOR ROATION IS 6 TICKS

// wheel encoder's no of ticks per rev (e.g motors for one rotation should be 6, then multiplied for the number of the gear ratio e.g 1:5 is 30 counts per rev)`

#define WHEEL_DIAMETER 0.15 // wheel's diameter in meters

#define PWM_BITS 8 // PWM Resolution of the microcontroller

#define LR_WHEELS_DISTANCE 0.235 // distance between left and right wheels

#define PWM_MAX 100 //Set lower PWM for better control (read as: avoid lost of control)

#define PWM_MIN -115 //-PWM_MAX

#define PWM_POSITIVE_MIN_THRESHOLD 45 // The minimum threshold for pwm in brushless control. An offset for the 0 to PWM MAX

#define PWM_NEGATIVE_MIN_THRESHOLD -55 // The minimum threshold for pwm in brushless control. An offset for the 0 to PWM MIN

PWM is used to control brushless motors. They can mapped to a proper PWM range with PWM_MAX PWM_MIN PWM_POSITIVE_MIN_THRESHOLD PWM_NEGATIVE_MIN_THRESHOLD. Ot can be found empirically with test application ESC_Ramp.ino

If you are unsure what is the encoder’s PPR (COUNTS_PER_REV) – you can check the encoder’s total count from minimal.launch’s terminal (see 2.3.1). Get the recent count and rotate the wheel 360 degrees:

PPR = abs(RECENT_COUNT – INITIAL_COUNT)

If you have the encoder and motor’s specification:

PPR = MOTOR_GEAR_RATIO * ENCODER_RES

The first time you upload your codes using platformio, it will prompt if you want to install the framework (ie. ‘teensy’) you are using. Press ‘y’ to proceed with the installation. Once the framework is installed, plug in the Teensy board to the robot’s computer and upload the codes:

roscd plutobot/teensy/firmware

platformio run --target upload

If and ONLY IF you are using MPU6050 IMU, remember to set use_mag param on imu_madgwick_filter to false since it has no magnetometer. Open imu.launch:

roscd plutobot/launch/include/imu

nano imu.launch

Set the second parameter to false:

<param name="fixed_frame" value="base_footprint" />

<param name="use_mag" value="true" />

<param name="publish_tf" value="false" />

<param name="use_magnetic_field_msg" value="true" /> 

<param name="world_frame" value="enu" />

<param name="orientation_stddev" value="0.05" />

Test by running

roslaunch plutobot minimal.launch

if you see this, the linobase is not connected see '/dev/linobase' not exists

[INFO] [1555698249.913223]: Connecting to /dev/linobase at 57600 baud

[ERROR] [1555698249.919567]: Error opening serial: [Errno 2] could not open port /dev/linobase: [Errno 2] No such file or directory: '/dev/linobase'

ROS Environment

To achieve full autonomy, navigation stack requires to know which type of BOT is.

This configuration is done MANUALLY during installation. You can run:

echo $LINOBASE

LINOBASE=2wd

on your robot's computer to check the configured LINOBASE for your build. It should be 2wd Change accordingly with your setup

If not check the .bashrc