Class UnitreeDriverο
Defined in File unitree_driver.hpp
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
-
std::array<UNITREE_LEGGED_SDK::MotorState, 12> get_joint_states()ο
Retrieves the state of each joint of the robot.
- Returns:
std::array<UNITREE_LEGGED_SDK::MotorState, 20>: The joint states of the robot. [ fr_hip, fr_tight, fr_calf, fl_hip, fl_tight, fl_calf, br_hip, br_tight, br_calf, bl_hip, bl_tight, bl_calf ]
-
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.
-
UnitreeDriver(std::string ip_addr = "192.168.123.161", int target_port = 8082)ο