can-rover

The goal is to convert cheap RC car kits in to computer driven robots by
replacing the receiver with a separate module.
The project consists of three parts working as a whole:
Hardware
features:
- XT60 passthrough
- fuse protected battery input
- battery current & voltage measurement
- maximum rating: 20 V, 30 A
- a charge current of 10 A max can be measured
- 2x canbus+power connectors
- 8 buffered servo channels
- 8 selectable addresses
- 8 buffered inputs with pull-up to 5V
- e-stop controlled servo power
CAN header
Jumper for 120R termination.
May be used to power low power stuff. Connector rated at 3 A.
| pin | signal |
|---|---|
| 1 | GND |
| 2 | Battery |
| 3 | CAN_L |
| 4 | CAN_H |
Firmware
- can-utils:
sudo ip link set up can0 type can bitrate 500000 - All messages are
big-endian. - python-can has great tools for debugging.
- build with
cd firmware; make
CAN messages
base_address is selectable by rotary switch. All messages have an offset from that address.
uint8_t arbitration_id = base_address << 8; // address 0 would be: 0x000 and 7: 0x070
| offset | parameter | I/O | bytes |
|---|---|---|---|
| 0x0 | servo 1 | I | 1 |
| ... | servo ... | I | 1 |
| 0x7 | servo 8 | I | 1 |
| 0x8 | battery Voltage | O | 2 |
| 0x9 | battery Current | O | 2 |
| 0xa | sensors 1 .. 8 | O | 1 |
Servo
PWM in 1 µs resolution and if channel hasn't been set within 1 s it will default to 1500 µs. For example: servo 3 with base_address = 5 would be set to -90° with:
$ cansend can0 052#3e8
Battery monitor
Analog signals directly from A/D, maximum: 4095
Inputs
One byte where each bit represents an input
bool value = inputs >> n-1 & 0x1;
ROS2 node
Provided node bridges firmware to ros topics.
Installation
apt install python3-rosdep python3-colcon-common-extensions
ln -s ros2_can_rover ~/ros2_ws/src/can_rover
cd ~/ros2_ws/
colcon build
source install/setup.bash
rosdep init
rosdep update
rosdep install --from-paths src -y --ignore-src
ros2 run can_rover can_rover
Topics and parameters
Interfaces provided are bare minimum for simplicity
| topic | type | publish / subscribe | min | max |
|---|---|---|---|---|
/rover/voltage |
Float32 | publish | 0 * | 20* |
/rover/current |
Float32 | publish | -10 * | 30* |
/rover/watts |
Float32 | publish | -200* | 600* |
/rover/wattHours |
Float32 | publish | ||
/rover/setWattHours |
Float32 | subscribe | ||
/rover/channel_<n> |
Float32 | subscribe | -1 | 1 |
/rover/input_<n> |
Bool | publish | 0 | 1 |
*min/max values limited by hardware tolerances and calibration
| parameter | type | default |
|---|---|---|
/rover/voltage_scale |
Float32 | 20 / 2^12 |
/rover/voltage_offset |
Float32 | 0 |
/rover/current_scale |
Float32 | -40 / 2^12 |
/rover/current_offset |
Float32 | 10 |
/rover/channel_<n>_scale |
Float32 | 500 |
/rover/channel_<n>_offset |
Float32 | 1500 |