Class UnitreeDriver

Class Documentation

class UnitreeDriver

Public Functions

UnitreeDriver(std::string ip_addr = "192.168.123.161", int target_port = 8082)

Constructor of the class UnitreeDriver.

Parameters:
  • ip_addr – Address to be used to communicate with robot (default: 192.168.12.1)

  • target_port_ – Port to be used to communicate with robot (default: 8082)

~UnitreeDriver()
void stand_up()

Stand up the robot.

void stand_down()

Stand down the robot.

void damping_mode()

Go into damping mode. Motor will be disabled so use with caution. Make the robot stand down before using this method.

@comment In case the robot is not in stand mode, this will not be executed.

void walk_w_vel(float x, float y, float yaw)

Move robot with with velocity commands.

Parameters:
  • x – forward(+)/backards(-) direction

  • y – left(+)/right(-) direction

  • yaw – rotation along the z axis (+ccw)

void walk_w_pos(position_t position, quarternion_t orientation)

Move robot with position commands relative where the robot was booted (Never tested)

Parameters:
  • position – {x, y z}

  • orientation – {z, y, z, w}

odom_t get_odom()

Retrieves odometry from the robot.

Returns:

odom_t: The odometry from the robot

UNITREE_LEGGED_SDK::IMU get_imu()

Retrieves IMU data from the robot.

Returns:

UNITREE_LEGGED_SDK::IMU: The IMU data from the robot

UNITREE_LEGGED_SDK::BmsState get_bms()

Retrieves BMS (Battery Management System) data from the robot it.

Returns:

UNITREE_LEGGED_SDK::BMS: The BMS data from the robot

sensor_ranges_t get_radar_ranges()

Retrieves the distances comming from the radar sensors from the front and sides of the robot.

Returns:

sensor_ranges_t: the 3 ranges from the radars

uint8_t get_battery_percentage()

Retrieves the current battery percentage of the robot’s battery.

Returns:

uint8_t: battery percentage (0-100%)

void set_mode(mode_enum mode)

Changes the current mode the robot should be in The possible modes are:

  • MODE_IDDLE = 0,

  • WALK_W_VEL = 2,

  • WALK_W_POS = 3,

  • STAND_DOWN = 5,

  • STAND_UP = 6,

  • DAMPING_MODE = 7,

Parameters:

mode – mode to be set

void set_gaitype(gaitype_enum gaitype)

Changes the current gaitype the robot should be in The possible modes are:

  • GAITYPE_IDDLE = 0,

  • TROT = 1,

  • TROT_RUNNING = 2,

  • CLIMB_STAIR = 3,

  • TROT_OBSTACLE = 4,

Parameters:

gaitype – gaitype to be set

void enable_obstacle_avoidance(bool flag)

Enables/disables robot’s obstacle avoidance.

Parameters:

flag – true: enables | false: disables

void stop()

Makes the robot stand down and disable motors.

void set_head_led(uint8_t r, uint8_t g, uint8_t b)

Sets the robot face LEDs color.

Parameters:
  • r – percentage of the red color (0-254)

  • g – percentage of the green color (0-254)

  • b – percentage of the blue color (0-254)

void set_head_led(UNITREE_LEGGED_SDK::LED led)

Sets the robot face LEDs color.

Parameters:

led – struct containing the 3 primary colors

void update_robot_status()

Sends the colors to the face LEDs based on the robot status.