Embedded, low-level firmware for STM32 microcontroller inside ROSbot. Developed using Mbed Os.
______ _____ _____ _ _ __
| ___ \| _ |/ ___|| | | | / _|
| |_/ /| | | |\ `--. | |__ ___ | |_ | |_ __ __
| / | | | | `--. \| '_ \ / _ \ | __| | _|\ \ /\ / /
| |\ \ \ \_/ //\__/ /| |_) || (_) || |_ | | \ V V /
\_| \_| \___/ \____/ |_.__/ \___/ \__| |_| \_/\_/
Firmware version: 0.16.2
You need to install following tools:
- Microsoft C/C++ extension (
ms-vscode.cpptools) - PlatformIO IDE (
platformio.platformio-ide)
https://docs.platformio.org/en/latest/frameworks/mbed.html#ignoring-particular-components
In directory ~/.platformio/packages/framework-mbed/features create file called .mbedignore with the following content:
cellular/*
cryptocell/*
deprecated_warnings/*
lorawan/*
lwipstack/*
nanostack/*
netsocket/*
nfc/*
unsupported/*
By default the ROSbot firmware supports ROS Noetic. To build it for previous ROS distributions remove below flag from platformio.ini:
-D ROS_NOETIC_MSGS=1
Use PlatformIO: Build task.
Use PlatformIO: Upload task.
TODO: add core2-flasher to repository (download right version by detecting system type), use advance scripting: https://docs.platformio.org/en/latest/projectconf/advanced_scripting.html
To create intel hex file use arm-none-eabi-objcopy:
$ arm-none-eabi-objcopy -O ihex firmware.elf firmware.hex You will find firmware.elf in ./pio/core2.
To flash firmware using core2-flasher run:
core2-flasher firmware.hex
https://github.com/husarion/stm32loader
This tool allows you to upload firmware using RPi connector.
If you have the bootloader the first two sectors are write protected. Before uploading new firmware you must unlock them (this will erase the bootloader):
$ sudo stm32loader -c <your_sbc> -u -WTo upload new firmware run:
$ sudo stm32loader -c <your_sbc> -e -v -w firmware.binwhere <your_sbc> :
tinkerfor Asus Tinker Boardupboardfor Upboardrpifor Raspberry Pi
You will find firmware.bin in ./pio/core2.
To use this firmware you have to disable communication with Husarion Cloud. On your SBC run:
$ sudo systemctl disable husarnet-configurator
$ sudo rebootTo start rosserial communication run:
$ rosrun rosserial_node serial_node.py.py _port:=<SBC_port_name> _baud:=<port_baudrate><SBC_port_name>:
/dev/ttyS1for Asus Tinker Board,/dev/serial0for Raspberry Pi/dev/ttyS4for UpBoard
<port_baudrate>:
525000for UpBoard525000for Asus Tinker Board525000for Raspberry Pi
The baudrate should be adjusted for SBC you use. The default value for this firmware is 525000.
The following rosserial.launch file can be used to start roscore and rosserial_python communication:
<launch>
<arg name="serial_port" default="/dev/ttyUSB0"/>
<arg name="serial_baudrate" default="525000"/>
<node pkg="rosserial_python" type="serial_node.py" name="serial_node" output="screen">
<param name="port" value="$(arg serial_port)"/>
<param name="baud" value="$(arg serial_baudrate)"/>
</node>
</launch>Usage for Asus Tinker Board:
$ roslaunch rosserial.launch serial_port:=/dev/ttyS1 serial_baudrate:=525000ROSbot subscribes to:
-
/cmd_velwith message typegeometry_msgs/Twist -
/cmd_serwith message typestd_msgs/UInt32- control configured servo output. SeeCSERservice command to learn how to configure servo outputs. Message format:MSB [ duty_cycle_us | output_id] LSB 28bits 4bitsServos are numbered from 1 to 6, where 1 means hServo 1 output etc. To set SERVO 1 duty cycle to 1000us (0x3E8) run:
$ rostopic pub /cmd_ser std_msgs/UInt32 "data: 0x3E81" --once
ROSbot publishes to:
/velocitywith message typegeometry_msgs/Twist/batterywith message typesensor_msgs/BatteryState/posewith message typegeometry_msgs/Pose/range/flwith message typesensor_msgs/Range/range/frwith message typesensor_msgs/Range/range/rlwith message typesensor_msgs/Range/range/rrwith message typesensor_msgs/Range/joint_stateswith message typesensor_msgs/JointState/mpu9250with custom message typerosbot_ekf/Imu/buttonswith message typestd_msgs/UInt8
ROSbot provides service server:
/configwith custom message typerosbot_ekf/Configuration
$ rossrv show rosbot_ekf/Configuration
string command
string data
---
uint8 SUCCESS=0
uint8 FAILURE=1
uint8 COMMAND_NOT_FOUND=2
string data
uint8 resultAt the moment following commands are available:
-
CSER- CONFIGURE SERVOChange a configuration of servo outputs. Can be repeated as many times as required to change several configuration parameter at once. The parameter name should be separated from the value with a full column
:character. Available parameters:S- select servo output, required withPandWoptions [1:6]V- select voltage mode:0- about 5V1- about 6V2- about 7.4V3- about 8.6V
E- enable servo output [1,0]P- set period in usW- set duty cycle in us
To set servo voltages to 5V and enable
SERVO 1output with period 20ms and width 1ms run:$ rosservice call /config "command: 'CSER' >data: 'V:0 S:1 E:1 P:20000 W:1000 '"
-
CPID- CONFIGURE PIDChange the motor's pid configuration. This command is similar to CSER command. You can change multiple parameters at the same time. Available parameters:
kp- proportional gain (default: 0.8)ki- integral gain (default: 0.2)kd- derivative gain (default: 0.015)out_max- upper limit of the pid output, represents pwm duty cycle (default: 0.80, max: 0.80)out_min- lower limit of the pid output, represents pwm duty cycle when motor spins in opposite direction (default: -0.80, min: -0.80)a_max- acceleration limit (default: 1.5e-4 m/s2)speed_max- max motor speed (default: 1.0 m/s, max: 1.25 m/s)
To limit pid outputs to 75% run:
$ rosservice call /config "command: 'CPID' >data: 'out_max:0.75 out_min:-0.75'"
-
GPID- GET PID CONFIGURATIONTo get current PID configuration run:
$ rosservice call /config "command: 'GPID' data: ''"
Response:
data: "kp:0.800 ki:0.200 kd:0.015 out_max:1.000 out_min:-1.000 a_max:1. 500e-04 speed_max:\ \ 1.500" result: 0
-
SLED- SET LED:To set LED2 on run:
$ rosservice call /config "command: 'SLED' >data: '2 1'"
-
EIMU- ENABLE/DISABLE IMU:To enable IMU MPU9250 run:
$ rosservice call /config "command: 'EIMU' >data: '1'"
data: '1'- enabledata: '0'- disable
-
RIMU- RESET IMU (for Kalman related odometry)To reset IMU MPU9250 run:
$ rosservice call /config "command: 'RIMU' >data: ''"
-
EJSM- ENABLE/DISABLE JOINT STATES MESSAGESTo enable JointStates messages run:
$ rosservice call /config "command: `EJSM` >data: '1'"
data: '1'- enabledata: '0'- disable
-
RODOM- RESET ODOMETRYTo reset odometry run:
$ rosservice call /config "command: `RODOM` >data: ''"
-
CALI- ODOMETRY CALIBRATION (update coefficients)To update
diameter_modificatorandtyre_deflationrun:$ rosservice call /config "command: `CALI` >data: 'X Y'"
X-diameter_modificatorvalueY-tyre_deflationvalue
-
EMOT- ENABLE/DISABLE MOTORSTo disable motors run:
$ rosservice call /config "command 'EMOT' >data '0'
0- disconnect motors1- connect motors
-
SANI- SET WS2812B LEDS ANIMATIONTo enable the ws2812b interface open the
mbed_app.jsonfile and change the line:"enable-ws2812b-signalization": 0
to
"enable-ws2812b-signalization": 1
To set fading blue animation run:
$ rosservice call /config "command: `SANI` >data: 'F #0000aa'"
Available commands:
O- OFFS <hex color code>- SOLID COLORF <hex color code>- FADE IN FADE OUT ANIMATIONB <hex color code>- BLINK FRONT/REAR ANIMATIONR- RAINBOW ANIMATION
-
SKIN- SET ROSBOT KINEMATICS DIFFERENTIAL/MECANUMBy default robot always start with differential drive kinematics available to change by command
$ rosservice call /config "command 'SKIN' >data 'DIFF'
To set mecanum kinematics run
$ rosservice call /config "command 'SKIN' >data 'MEC'
MEC- mecanum kinematicsDIFF- differential drive kinematics
TODO: change rosbot_ekf lib
In order to use the service you have to download the package rosbot_ekf that can be found HERE. For installation details check the README.
The package incorporate a ready to use Extended Kalman Filter that combines both the imu and encoders measurements to better approximate the ROSbot position and orientation. The package also contains custom messages that are required by the new firmware.
To launch the rosserial communication and Kalman filter run:
$ roslaunch rosbot_ekf all.launchFor PRO version add parameter:
$ roslaunch rosbot_ekf all.launch rosbot_pro:=trueThe project uses SemVer for versioning. For the versions available, see the tags on this repository.
See CHANGELOG.md.
Documentation:
- https://github.com/platformio/platform-ststm32/tree/develop/examples/mbed-legacy-examples/mbed-rtos
- https://github.com/platformio/platform-ststm32/blob/develop/boards/olimex_e407.json
- https://github.com/platformio/platform-ststm32/blob/develop/boards/black_f407zg.json
- https://github.com/ARMmbed/mbed-os/tree/mbed-os-5.15.6/targets/TARGET_STM/TARGET_STM32F4/TARGET_STM32F407xG
- https://docs.platformio.org/en/latest/frameworks/mbed.html
- https://docs.platformio.org/en/latest/platforms/creating_board.html
Required changes in pio files:
File ".platformio/packages/framework-mbed/platformio/package_deps/py3/past/types/oldstr.py", line 5:
> from collections.abc import Iterable
< from collections import IterableFile ".platformio/packages/framework-mbed/platformio/package_deps/py3/past/builtins/misc.py", line 4:
> from collections.abc import Mapping
< from collections import Mapping