8.11. Example I²C code for Linux in C

The example C code below uses the I²C API provided by the Linux kernel to send and receive data from a Simple Motor Controller G2. This code only works on Linux.

If you are using a Raspberry Pi, please note that the Raspberry Pi’s hardware I²C module has a bug that might cause this code to be unreliable. As a workaround, we recommend disabling hardware I²C (if you previously enabled it) and enabling the i2c-gpio overlay instead. To enable the overlay, add the following line to /boot/config.txt and reboot:

dtoverlay=i2c-gpio,i2c_gpio_sda=2,i2c_gpio_scl=3

The Raspberry Pi overlay documentation has information about the parameters on that line. Connect the Simple Motor Controller’s SDA line to GPIO2 and connect the Simple Motor Controller’s SCL line to GPIO3. The i2c-gpio overlay creates a new I²C bus device named /dev/i2c-3, and the code below uses that device. To give your user permission to access I²C busses without being root, you might have to add yourself to the i2c group by running sudo usermod -a -G i2c $(whoami) and restarting.

// Uses the Linux I2C API to send and receive data from an SMC G2.
// NOTE: The SMC's input mode must be "Serial / I2C / USB".
// NOTE: For reliable operation on a Raspberry Pi, enable the i2c-gpio
//   overlay and use the I2C device it provides (usually /dev/i2c-3).
// NOTE: You might need to change the 'const char * device' line below
//   to specify the correct I2C device.
// NOTE: You might need to change the `const uint8_t address' line below
// to match the device number of your Simple Motor Controller.

#include <fcntl.h>
#include <linux/i2c.h>
#include <linux/i2c-dev.h>
#include <stdint.h>
#include <stdio.h>
#include <sys/ioctl.h>
#include <unistd.h>

// Opens the specified I2C device.  Returns a non-negative file descriptor
// on success, or -1 on failure.
int open_i2c_device(const char * device)
{
  int fd = open(device, O_RDWR);
  if (fd == -1)
  {
    perror(device);
    return -1;
  }
  return fd;
}

// Reads a variable from the SMC.
// Returns 0 on success or -1 on failure.
int smc_get_variable(int fd, uint8_t address, uint8_t variable_id,
  uint16_t * value)
{
  uint8_t command[] = { 0xA1, variable_id };
  uint8_t response[2];
  struct i2c_msg messages[] = {
    { address, 0, sizeof(command), command },
    { address, I2C_M_RD, sizeof(response), response },
  };
  struct i2c_rdwr_ioctl_data ioctl_data = { messages, 2 };
  int result = ioctl(fd, I2C_RDWR, &ioctl_data);
  if (result != 2)
  {
    perror("failed to get variable");
    return -1;
  }
  *value = response[0] + 256 * response[1];
  return 0;
}

// Gets the target speed (-3200 to 3200).
// Returns 0 on success, -1 on failure.
int smc_get_target_speed(int fd, uint8_t address, int16_t * value)
{
  return smc_get_variable(fd, address, 20, (uint16_t *)value);
}

// Gets a number where each bit represents a different error, and the
// bit is 1 if the error is currently active.
// See the user's guide for definitions of the different error bits.
// Returns 0 on success, -1 on failure.
int smc_get_error_status(int fd, uint8_t address, uint16_t * value)
{
  return smc_get_variable(fd, address, 0, value);
}

// Sends the Exit Safe Start command, which is required to drive the motor.
// Returns 0 on success, -1 on failure.
int smc_exit_safe_start(int fd, uint8_t address)
{
  uint8_t command = 0x83;
  struct i2c_msg message = { address, 0, 1, &command };
  struct i2c_rdwr_ioctl_data ioctl_data = { &message, 1 };
  int result = ioctl(fd, I2C_RDWR, &ioctl_data);
  if (result != 1)
  {
    perror("failed to exit safe start");
    return -1;
  }
  return 0;
}

// Sets the SMC's target speed (-3200 to 3200).
// Returns 0 on success, -1 on failure.
int smc_set_target_speed(int fd, uint8_t address, int16_t speed)
{
  uint8_t command[3];

  if (speed < 0)
  {
    command[0] = 0x86; // Motor Reverse
    speed = -speed;
  }
  else
  {
    command[0] = 0x85; // Motor Forward
  }
  command[1] = speed & 0x1F;
  command[2] = speed >> 5 & 0x7F;

  struct i2c_msg message = { address, 0, sizeof(command), command };
  struct i2c_rdwr_ioctl_data ioctl_data = { &message, 1 };
  int result = ioctl(fd, I2C_RDWR, &ioctl_data);
  if (result != 1)
  {
    perror("failed to set speed");
    return -1;
  }
  return 0;
}

int main()
{
  // Choose the I2C device.
  const char * device = "/dev/i2c-3";

  // Set the I2C address of the SMC (the device number).
  const uint8_t address = 13;

  int fd = open_i2c_device(device);
  if (fd < 0) { return 1; }

  int result = smc_exit_safe_start(fd, address);
  if (result) { return 1; }

  uint16_t error_status;
  result = smc_get_error_status(fd, address, &error_status);
  if (result) { return 1; }
  printf("Error status: 0x%04x\n", error_status);

  int16_t target_speed;
  result = smc_get_target_speed(fd, address, &target_speed);
  if (result) { return 1; }
  printf("Target speed is %d.\n", target_speed);

  int16_t new_speed = (target_speed <= 0) ? 3200 : -3200;
  printf("Setting target speed to %d.\n", new_speed);
  result = smc_set_target_speed(fd, address, new_speed);
  if (result) { return 1; }

  close(fd);
  return 0;
}

Related Products

High-Power Simple Motor Controller G2 18v15 (Connectors Soldered)
High-Power Simple Motor Controller G2 18v15
High-Power Simple Motor Controller G2 24v12 (Connectors Soldered)
High-Power Simple Motor Controller G2 24v12
High-Power Simple Motor Controller G2 18v25
High-Power Simple Motor Controller G2 24v19
Log In
Pololu Robotics & Electronics
Shopping cart
(702) 262-6648
Same-day shipping, worldwide
Menu
Shop Blog Forum Support
My account Comments or questions? About Pololu Contact Ordering information Distributors