ROS Control with the JetBot Part 1: Using I2C to control PWM
The first part of a new series - setting up the JetBot to work with ROS Control interfaces!
1
if 96 in addresses:
- Forwards - red wire has voltage, black wire is 0V
- Backwards - black wire has voltage, red wire is 0V
- Motor off - both wires are 0V
- Motor brakes - both wires have voltage
jetbot-motors-pt1
.I2CDevice
constructor by opening the I2C bus with the Linux I2C driver; selecting the FeatherWing device by address; setting its mode to reset it; and setting its clock using a few reads and writes of the mode and prescaler registers. Once this is done, the chip is ready to move the motors.1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
I2CDevice::I2CDevice() {
i2c_fd_ = open("/dev/i2c-1", O_RDWR);
if (!i2c_fd_) {
std::__throw_runtime_error("Failed to open I2C interface!");
}
// Select the PWM device
if (!trySelectDevice())
std::__throw_runtime_error("Failed to select PWM device!");
// Reset the PWM device
if (!tryReset()) std::__throw_runtime_error("Failed to reset PWM device!");
// Set the PWM device clock
if (!trySetClock()) std::__throw_runtime_error("Failed to set PWM clock!");
}
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
// Headers needed for Linux I2C driver
// ...
// Open the I2C bus
i2c_fd_ = open("/dev/i2c-1", O_RDWR);
// Check that the open was successful
if (!i2c_fd_) {
std::__throw_runtime_error("Failed to open I2C interface!");
}
i2c_fd_
with Linux system calls to select the device address and read/write data. To select the device by address:1
2
3
bool I2CDevice::trySelectDevice() {
return ioctl(i2c_fd_, I2C_SLAVE, kDefaultDeviceAddress) >= 0;
}
ioctl
function to select a slave device by the default device address 0x60. It checks the return code to see if it was successful. Assuming it was, we can proceed to reset:1
bool I2CDevice::tryReset() { return tryWriteReg(kMode1Reg, 0x00); }
I2CDevice
exposes two methods: one to enable the motors, and one to set a duty cycle. The motor enable sets a particular pin on, so I'll skip that function. The duty cycle setter has more logic:1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
buf_[0] = kPwmReg + 4 * pin;
if (duty_cycle == 0xFFFF) {
// Special case - fully on
buf_[1] = 0x00;
buf_[2] = 0x10;
buf_[3] = 0x00;
buf_[4] = 0x00;
} else if (duty_cycle < 0x0010) {
// Special case - fully off
buf_[1] = 0x00;
buf_[2] = 0x00;
buf_[3] = 0x00;
buf_[4] = 0x10;
} else {
// Shift by 4 to fit 12-bit register
uint16_t value = duty_cycle >> 4;
buf_[1] = 0x00;
buf_[2] = 0x00;
buf_[3] = value & 0xFF;
buf_[4] = (value >> 8) & 0xFF;
}
0x1000
. If below a minimum, it sets the duty cycle to its minimum. Anywhere in between will shift the value by 4 bits to match the size of the register in the PWM chip, then transmit that. Between the three if
blocks, the I2CDevice
has the ability to set any duty cycle for a particular pin. It's then up to the Motor
class to decide which pins should be set, and the duty cycle to set them to.I2CDevice
, each Motor
gets a reference to the I2CDevice
to allow it to talk to the PWM chip, as well as a set of pins that correspond to the motor. The pins are as follows:Motor | Enable Pin | Positive Pin | Negative Pin |
---|---|---|---|
Motor 1 | 8 | 9 | 10 |
Motor 2 | 13 | 11 | 12 |
I2CDevice
and Motor
s are constructed in the JetBot control node. Note that the pins are passed inline:1
2
3
4
device_ptr_ = std::make_shared<JetBotControl::I2CDevice>();
motor_1_ = JetBotControl::Motor(device_ptr_, std::make_tuple(8, 9, 10), 1);
motor_2_ =
JetBotControl::Motor(device_ptr_, std::make_tuple(13, 11, 12), 2);
1
2
3
4
5
6
7
8
9
Motor::Motor(I2CDevicePtr i2c, MotorPins pins, uint32_t motor_number)
: i2c_{i2c}, pins_{pins}, motor_number_{motor_number} {
u8 enable_pin = std::get<0>(pins_);
if (!i2c_->tryEnableMotor(enable_pin)) {
std::string error =
"Failed to enable motor " + std::to_string(motor_number) + "!";
std::__throw_runtime_error(error.c_str());
}
}
1
2
motor_1_.trySetSpinning(spinning_);
motor_2_.trySetSpinning(spinning_);
0xFFFF
, while the negative pin is set to off:1
2
3
4
5
6
if (!i2c_->trySetDutyCycle(pos_pin, 0xFFFF)) {
return false;
}
if (!i2c_->trySetDutyCycle(neg_pin, 0)) {
return false;
}
0xFFFF
:1
2
3
4
5
6
if (!i2c_->trySetDutyCycle(pos_pin, 0xFFFF)) {
return false;
}
if (!i2c_->trySetDutyCycle(neg_pin, 0xFFFF)) {
return false;
}
Motor
class:1
2
3
Motor::~Motor() {
trySetSpinning(false);
}
Motor
class only has the ability to turn fully on or fully off, it has the code to set a duty cycle anywhere between 0 and 0xFFFF
- which means we can set any speed in the direction we want the motors to spin!1
2
3
4
source /opt/ros/humble/setup.bash
colcon build
source install/setup.bash
ros2 run jetbot_control jetbot_control