API¶
Receive IP Broadcast¶
Robomaster broadcast its IP address under router mode.
-
robomasterpy.
get_broadcast_ip
(timeout: float = None) → str¶ 接收广播以获取机甲IP
- Parameters
timeout – 等待超时(秒)
- Returns
机甲IP地址
Commander¶
Commander is a client for Robomaster TCP API.
-
class
robomasterpy.
Commander
(ip: str = '', timeout: float = 30)¶ -
armor_event
(attr: str, switch: bool) → str¶ 控制装甲板检测事件上报
- Parameters
attr – 事件属性名称,范围见 ARMOR_ENUMS
switch – 是否开启上报
- Returns
ok,否则raise
-
armor_sensitivity
(value: int) → str¶ 设置装甲板打击检测灵敏度
- Parameters
value – 装甲板灵敏度,数值越大,越容易检测到打击。默认灵敏度值为 5.
- Returns
ok,否则raise
-
audio
(switch: bool) → str¶ 音频流开关控制
- Parameters
switch – 打开/关闭
- Returns
ok,否则raise
-
blaster_fire
() → str¶ 控制水弹枪发射一次
- Returns
ok,否则raise
-
chassis_move
(x: float = 0, y: float = 0, z: float = 0, speed_xy: float = None, speed_z: float = None) → str¶ 控制底盘运动当指定位置,坐标轴原点为当前位置
- Parameters
x – x 轴向运动距离,单位 m
y – y 轴向运动距离,单位 m
z – z 轴向旋转角度,单位 °
speed_xy – xy 轴向运动速度,单位 m/s
speed_z – z 轴向旋转速度, 单位 °/s
- Return ok
ok,否则raise
-
chassis_push_off
(position: bool = False, attitude: bool = False, status: bool = False, all: bool = False) → str¶ 关闭底盘中相应属性的信息推送。
- Parameters
position – 是否关闭位置推送
attitude – 是否关闭姿态推送
status – 是否关闭状态推送
all – 关闭所有推送
- Returns
ok,否则raise
-
chassis_push_on
(position_freq: int = None, attitude_freq: int = None, status_freq: int = None, all_freq: int = None) → str¶ 打开底盘中相应属性的信息推送,支持的频率 1, 5, 10, 20, 30, 50
- Parameters
position_freq – 位置推送频率,不开启则设为None
attitude_freq – 姿态推送频率,不开启则设为None
status_freq – 状态推送频率,不开启则设为None
all_freq – 统一设置所有推送频率,设置则开启所有推送
- Returns
ok,否则raise
-
chassis_speed
(x: float = 0, y: float = 0, z: float = 0) → str¶ 控制底盘运动速度
- Parameters
x – x 轴向运动速度,单位 m/s
y – y 轴向运动速度,单位 m/s
z – z 轴向旋转速度,单位 °/s
- Returns
ok,否则raise
-
chassis_wheel
(w1: int = 0, w2: int = 0, w3: int = 0, w4: int = 0) → str¶ 底盘轮子速度控制
- Parameters
w1 – 右前麦轮速度,单位 rpm
w2 – 左前麦轮速度,单位 rpm
w3 – 右后麦轮速度,单位 rpm
w4 – 左后麦轮速度,单位 rpm
- Return ok
ok,否则raise
-
close
()¶
-
do
(*args) → str¶ 执行任意命令
- Parameters
args – 命令内容,list
- Returns
命令返回
-
get_armor_sensitivity
() → int¶ 获取装甲板打击检测灵敏度 :return: 装甲板灵敏度
-
get_chassis_attitude
() → robomasterpy.client.ChassisAttitude¶ 获取底盘姿态信息
- Returns
pitch 轴角度(°),roll 轴角度(°),yaw 轴角度(°)
-
get_chassis_position
() → robomasterpy.client.ChassisPosition¶ 获取底盘当前的位置(以上电时刻位置为原点)
- Returns
x 轴位置(m),y 轴位置(m),偏航角度(°)
-
get_chassis_speed
() → robomasterpy.client.ChassisSpeed¶ 获取底盘速度信息
- Returns
x 轴向运动速度(m/s),y 轴向运动速度(m/s),z 轴向旋转速度(°/s),w1 右前麦轮速度(rpm),w2 左前麦轮速速(rpm),w3 右后麦轮速度(rpm),w4 左后麦轮速度(rpm)
-
get_chassis_status
() → robomasterpy.client.ChassisStatus¶ 获取底盘状态信息
- Returns
底盘状态,详见 ChassisStatus
-
get_gimbal_attitude
() → robomasterpy.client.GimbalAttitude¶ 获取云台姿态信息 :return: pitch 轴角度(°),yaw 轴角度(°)
-
get_ip
() → str¶ 返回机甲IP
- Returns
机甲IP
-
get_ir_sensor_distance
(id: int) → int¶ 获取指定 ID 的红外深度传感器距离
- Parameters
id – 红外传感器的 ID
- Returns
指定 ID 的红外传感器测得的距离值,单位 mm
-
get_robot_mode
() → str¶ 查询当前机器人运动模式
- Returns
三种模式之一,见enum MODE_*
-
gimbal_move
(pitch: float = 0, yaw: float = 0, pitch_speed: float = None, yaw_speed: float = None) → str¶ 控制云台运动到指定位置,坐标轴原点为当前位置
- Parameters
pitch – pitch 轴角度, 单位 °
yaw – yaw 轴角度, 单位 °
pitch_speed – pitch 轴运动速速,单位 °/s
yaw_speed – yaw 轴运动速速,单位 °/s
- Returns
ok,否则raise
-
gimbal_moveto
(pitch: float = 0, yaw: float = 0, pitch_speed: float = None, yaw_speed: float = None) → str¶ 控制云台运动到指定位置,坐标轴原点为上电位置
- Parameters
pitch – pitch 轴角度, 单位 °
yaw – yaw 轴角度, 单位 °
pitch_speed – pitch 轴运动速速,单位 °/s
yaw_speed – yaw 轴运动速速,单位 °/s
- Returns
ok,否则raise
-
gimbal_push_off
(attitude: bool = True) → str¶ 关闭云台中相应属性的信息推送
- Parameters
attitude – 关闭姿态推送
- Returns
ok,否则raise
-
gimbal_push_on
(attitude_freq: int = 5) → str¶ 打开云台中相应属性的信息推送,支持的频率 1, 5, 10, 20, 30, 50
- Parameters
attitude_freq – 姿态推送频率
- Returns
ok,否则raise
-
gimbal_recenter
()¶ 控制云台回中 :return: ok,否则raise
-
gimbal_resume
()¶ 控制云台从休眠状态中恢复 :return: ok,否则raise
-
gimbal_speed
(pitch: float, yaw: float) → str¶ 控制云台运动速度
- Parameters
pitch – pitch 轴速度,单位 °/s
yaw – yaw 轴速度,单位 °/s
- Returns
ok,否则raise
-
gimbal_suspend
()¶ 使云台进入休眠状态 :return: ok,否则raise
-
ir_sensor_measure
(switch: bool = True)¶ 打开/关闭所有红外传感器开关
- Parameters
switch – 打开/关闭
- Returns
ok,否则raise
-
led_control
(comp: str, effect: str, r: int, g: int, b: int) → str¶ 控制 LED 灯效。跑马灯效果仅可作用于云台两侧 LED。
- Parameters
comp – LED 编号,见 LED_ENUMS
effect – 灯效类型,见 LED_EFFECT_ENUMS
r – RGB 红色分量值
g – RGB 绿色分量值
b – RGB 蓝色分量值
- Returns
ok,否则raise
-
robot_mode
(mode: str) → str¶ 机器人运动模式控制
- Parameters
mode – 三种模式之一,见enum MODE_*
- Returns
ok,否则raise
-
sound_event
(attr: str, switch: bool) → str¶ 声音识别事件上报控制
- Parameters
attr – 事件属性名称,范围见 SOUND_ENUMS
switch – 是否开启上报
- Returns
ok,否则raise
-
stream
(switch: bool) → str¶ 视频流开关控制
- Parameters
switch – 打开/关闭
- Returns
ok,否则raise
-
version
() → str¶ query robomaster SDK version
- Returns
version string
-
Framework¶
The framework deals with video streaming, push and event, you can build your controlling logic basing on it, for example(TODO: add links):
Drive your robomaster using keyboard;
Make your robomaster a goalkeeper.
-
class
robomasterpy.framework.
Hub
¶ -
TERMINATION_TIMEOUT
= 10¶
-
close
()¶
-
run
()¶ Start workers and block the main process until all workers terminate.
Mind tries to shutdown itself gracefully when receiving SIGTERM or SIGINT.
-
worker
(worker_class, name: str, args: Tuple = (), kwargs=None)¶ Register worker to process sensor data fetching, calculation, inference,controlling, communication and more. All workers run in their own operating system process.
- Parameters
worker_class –
name –
args – args to func
kwargs – kwargs to func
-
-
class
robomasterpy.framework.
Worker
(name: str, out: Optional[multiprocessing.context.BaseContext.Queue], protocol: Optional[str], address: Tuple[str, int], timeout: Optional[float], loop: bool = True)¶ -
QUEUE_TIMEOUT
: float = 0.05¶
-
close
()¶
-
property
closed
¶
-
get_address
() → Tuple[str, int]¶
-
property
logger
¶
-
property
name
¶
-
work
() → None¶
-
-
class
robomasterpy.framework.
Vision
(name: str, out: Optional[multiprocessing.context.BaseContext.Queue], ip: str, processing: Callable[[…], None], none_is_valid=False)¶ -
QUEUE_TIMEOUT
= 0.05¶
-
TIMEOUT
: float = 5.0¶
-
close
()¶
-
property
closed
¶
-
get_address
() → Tuple[str, int]¶
-
property
logger
¶
-
property
name
¶
-
work
() → None¶
-
-
class
robomasterpy.framework.
PushListener
(name: str, out: multiprocessing.context.BaseContext.Queue)¶ -
PUSH_TYPES
: Tuple[str] = ('chassis', 'gimbal')¶
-
PUSH_TYPE_CHASSIS
: str = 'chassis'¶
-
PUSH_TYPE_GIMBAL
: str = 'gimbal'¶
-
QUEUE_TIMEOUT
= 0.05¶
-
close
()¶
-
property
closed
¶
-
get_address
() → Tuple[str, int]¶
-
property
logger
¶
-
property
name
¶
-
work
() → None¶
-
-
class
robomasterpy.framework.
EventListener
(name: str, out: multiprocessing.context.BaseContext.Queue, ip: str)¶ -
EVENT_TYPES
: Tuple[str] = ('armor', 'sound')¶
-
EVENT_TYPE_ARMOR
: str = 'armor'¶
-
EVENT_TYPE_SOUND
: str = 'sound'¶
-
QUEUE_TIMEOUT
= 0.05¶
-
close
()¶
-
property
closed
¶
-
get_address
() → Tuple[str, int]¶
-
property
logger
¶
-
property
name
¶
-
work
() → None¶
-
-
class
robomasterpy.framework.
Mind
(name: str, queues: Tuple[multiprocessing.context.BaseContext.Queue, …], ip: str, processing: Callable[[…], None], timeout: float = 30, loop: bool = True)¶ -
QUEUE_TIMEOUT
: float = 0.05¶
-
close
()¶
-
property
closed
¶
-
get_address
() → Tuple[str, int]¶
-
property
logger
¶
-
property
name
¶
-
work
() → None¶
-
Helpers for Measure¶
Some helpers for measure and analyze distance from video stream.
-
robomasterpy.measure.
pinhole_distance
(actual_size: float, pixel_size: float, focal_length: float = 710) → float¶ 使用针孔相机模型估测物体到相机的距离。
Estimate distance between camera and object using pinhole camera model.
- Parameters
actual_size – 实际大小,单位米。 Actual object size in meters.
pixel_size – 像素大小,单位像素。 Object size in pixels.
focal_length – (可选)当前分辨率下的等效焦距,和分辨率相关。默认使用1280*720分辨率。Perceived focal length at specified image resolution, default to 1280*720.
- Returns
物体到相机的距离,单位米。 Distance between camera and object, in meters.
-
robomasterpy.measure.
distance_decomposition
(pixel_x: float, distance: float, horizontal_pixels: float = 1280, horizontal_degrees: float = 96) → Tuple[float, float, float]¶ 将距离分解为前进分量(前为正)和侧向分量(右为正)。本函数要求线段的两端在相同海拔高度。
Decomposition distance into forward vector(forward as positive) and lateral vector(right as positive). This function requires that both ends of the line segment are at the same altitude.
- Parameters
pixel_x – 物体在图像上的x坐标,单位像素。 the x coordinate of the object on the image, in pixels.
distance – 距离,单位米。 Distance in meter.
horizontal_pixels – 图像横向的像素数目,默认1280. The number of pixels in the horizontal direction of the image, the default is 1280.
horizontal_degrees – 图像横向的视角大小,默认96. The horizontal viewing angle of the image, the default is 96.
- Returns
前进分量和侧向分量,单位米;水平偏转角度,单位度。 forward vector and lateral vector in meters; horizontal angle in degrees.