RflySimSDK v3.08
RflySimSDK说明文档
载入中...
搜索中...
未找到
Crazyflie类 参考

表示单个机器人对象的类。 本类封装了控制单个Crazyflie飞行器的主要功能,包括起飞、降落、移动和悬停等操作。 更多...

Public 成员函数

 __init__ (self, id, initialPosition, tf, mode)
 构造函数,初始化Crazyflie对象的相关参数和控制接口。
 
 loop (self)
 循环线程函数,用于初始化控制循环环境。
 
 setGroupMask (self, groupMask)
 设置此机器人的组掩码位,用于同步执行多机编排动作。
 
 enableCollisionAvoidance (self, others, ellipsoidRadii)
 启用机载避碰功能,使用缓冲Voronoi单元方法避免与其他无人机碰撞。
 
 disableCollisionAvoidance (self)
 禁用机载避碰功能。
 
 takeoff (self, targetHeight, duration, groupMask=0)
 执行起飞动作,以设定的速度飞到指定高度并保持悬停。
 
 land (self, targetHeight, duration, groupMask=0)
 执行降落动作,以设定的速度飞回指定高度。
 
 stop (self, groupMask=0)
 停止飞行器(在低级命令模式下切断电机电源)。
 
 goTo (self, goal, yaw, duration, relative=False, groupMask=0)
 平滑移动到指定目标位置(并悬停),支持绝对或相对坐标和偏航角设定。
 
 uploadTrajectory (self, trajectoryId, pieceOffset, trajectory)
 上传分段多项式轨迹以供后续执行。
 
 startTrajectory (self, trajectoryId, timescale=1.0, reverse=False, relative=True, groupMask=0)
 开始执行预先上传的轨迹。
 
 notifySetpointsStop (self, remainValidMillisecs=100, groupMask=0)
 通知飞行器低级控制指令(如cmdVelocityWorld、cmdFullState)即将停止发送,随后返回上层行为。
 
 position (self)
 返回最近一次由运动捕捉系统测量的飞行器真实位置。
 
 getParam (self, name)
 获取指定名称的机载参数的当前值。
 
 setParam (self, name, value)
 设置指定名称参数的值。
 
 setParams (self, params)
 批量设置多个参数的值。
 
 cmdFullState (self, pos, vel, acc, yaw, omega)
 发送全状态(setFullState)控制指令,包括位置、速度、加速度、偏航角及角速度。
 
 cmdVelocityWorld (self, vel, yawRate)
 发送世界坐标系下的速度与偏航角速度控制指令。
 
 cmdStop (self)
 停止飞行器,在高层命令模式下切断电机动力。
 
 cmdVel (self, roll, pitch, yawrate, thrust)
 发送用于初学者模式(绝对滚转/俯仰角度、偏航角速度和推力)的流式指令。
 
 cmdPosition (self, pos, yaw=0)
 发送绝对位置和偏航角的流式指令,飞行器将移动并保持在指定位置上空。
 
 setLEDColor (self, r, g, b)
 设置LED颜色(需要将param "ring/effect"设置为7才能生效)。
 
 readmsg (self)
 读取消息(占位函数,尚未实现)。
 
 getMotionPos (self)
 获取当前飞行器运动位置(通过底层接口获得NED坐标系下位置后转换)。
 
 getMotionVel (self)
 获取当前飞行器运动位置(通过底层接口获得NED坐标系下位置后转换)。
 
 getMotionAcc (self)
 获取当前飞行器运动加速度(通过底层接口获得NED坐标系下加速度后转换)。
 

Public 属性

 id
 
 mode
 
 prefix
 
 initialPosition
 
 tf
 
 ctrl
 
 mapini
 
 ini_success
 

详细描述

表示单个机器人对象的类。 本类封装了控制单个Crazyflie飞行器的主要功能,包括起飞、降落、移动和悬停等操作。

Object representing a single robot.

The bulk of the module's functionality is contained in this class.

构造及析构函数说明

◆ __init__()

__init__ ( self,
id,
initialPosition,
tf,
mode )

构造函数,初始化Crazyflie对象的相关参数和控制接口。

  • 参数
    id(int): 机器人ID,范围[0, 255]。该ID用作无线电地址的最后一个字节。
    initialPosition(iterable of float): 初始位置[x, y, z],通常在实验空间的地面上(z=0)。
    tf(tf.TransformListener): ROS的TransformListener对象,用于查询机器人的当前状态。
    mode(int): 工作模式选择参数,影响通信方式(redis或udp)。
    Constructor.
    
    Args:
        id (int): Integer ID in range [0, 255]. The last byte of the robot's
            radio address.
        initialPosition (iterable of float): Initial position of the robot:
            [x, y, z]. Typically on the floor of the experiment space with
            z == 0.0.
        tf (tf.TransformListener): ROS TransformListener used to query the
            robot's current state.
    
+ 函数调用图:

成员函数说明

◆ cmdFullState()

cmdFullState ( self,
pos,
vel,
acc,
yaw,
omega )

发送全状态(setFullState)控制指令,包括位置、速度、加速度、偏航角及角速度。

  • 发送此类型指令会使飞行器切换到低级控制模式,不再响应高层命令(如land、goTo)。
    参数
    pos(array-like[3]): 位置(米)。
    vel(array-like[3]): 速度(米/秒)。
    acc(array-like[3]): 加速度(米/秒²)。
    yaw(float): 偏航角(弧度)。
    omega(array-like[3]): 机体坐标系下的角速度(弧度/秒)。
    Sends a streaming full-state controller setpoint command.
    
    The full-state setpoint is most useful for aggressive maneuvers where
    feedforward inputs for acceleration and angular velocity are critical
    to obtaining good tracking performance. Full-state setpoints can be
    obtained from any trajectory parameterization that is at least three
    times differentiable, e.g. piecewise polynomials.
    
    Sending a streaming setpoint of any type will force a change from
    high-level to low-level command mode. Currently, there is no mechanism
    to change back, but it is a high-priority feature to implement.
    This means it is not possible to use e.g. :meth:`land()` or
    :meth:`goTo()` after a streaming setpoint has been sent.
    
    Args:
        pos (array-like of float[3]): Position. Meters.
        vel (array-like of float[3]): Velocity. Meters / second.
        acc (array-like of float[3]): Acceleration. Meters / second^2.
        yaw (float): Yaw angle. Radians.
        omega (array-like of float[3]): Angular velocity in body frame.
            Radians / sec.
    

◆ cmdPosition()

cmdPosition ( self,
pos,
yaw = 0 )

发送绝对位置和偏航角的流式指令,飞行器将移动并保持在指定位置上空。

  • 若缓慢改变位置目标,则此函数适用;若目标点变化较慢且距离较远,建议使用goTo()。 发送流式指令会切换到低级控制模式,不能再使用高层指令(如land、goTo)。
参数
pos(array-like of float[3]): 期望位置(米)。
yaw(float): 偏航角(弧度)。
Sends a streaming command of absolute position and yaw setpoint.

Useful for slow maneuvers where a high-level planner determines the
desired position, and the rest is left to the onboard controller.

For more information on streaming setpoint commands, see the
:meth:`cmdFullState()` documentation.

.. warning::
    As a streaming setpoint, ``cmdPosition`` must be sent many times
    per second (10Hz is a conservative minimum). For applications that
    generate goal positions slowly, :meth:`goTo()` may be more
    appropriate, especially if the goal positions are far apart.

Args:
    pos (array-like of float[3]): Position. Meters.
    yaw (float): Yaw angle. Radians.

◆ cmdStop()

cmdStop ( self)

停止飞行器,在高层命令模式下切断电机动力。

  • 后续的低/高层命令可以重新启动电机。
Interrupts any high-level command to stop and cut motor power.

Intended for non-emergency scenarios, e.g. landing with the possibility
of taking off again later. Future low- or high-level commands will
restart the motors. Equivalent of :meth:`stop()` when in high-level mode.

◆ cmdVel()

cmdVel ( self,
roll,
pitch,
yawrate,
thrust )

发送用于初学者模式(绝对滚转/俯仰角度、偏航角速度和推力)的流式指令。

  • 在此模式下,通过绝对角度而不是角速度来控制滚转和俯仰,适合初学者手动操作。 发送流式指令会切换到低级控制模式,不能再使用高层指令(如land、goTo)。
参数
roll(float): 滚转角度(度),正值表示向右滚转。
pitch(float): 俯仰角度(度),正值表示向前/向下俯仰。
yawrate(float): 偏航角速度(度/秒),正值表示逆时针旋转。
thrust(float): 推力大小,无单位标度,范围[0, 65535]。
Sends a streaming command of the "easy mode" manual control inputs.

The (absolute roll & pitch, yaw rate, thrust) inputs are typically
used for manual flying by beginners or causal pilots, as opposed to the
"acrobatic mode" inputs where roll and pitch rates are controlled
instead of absolute angles. This mode limits the possible maneuvers,
e.g. it is not possible to do a flip because the controller joystick
would need to rotate 360 degrees.

For more information on streaming setpoint commands, see the
:meth:`cmdFullState()` documentation.

!NOTE!: The angles and angular velocities in this command are in
degrees, whereas they are in radians for cmdFullState.

TODO: should we change the name from cmdVel to something else?
IMO (japreiss), cmdVel implies controlling linear velocity.

Args:
    roll (float): Roll angle. Degrees. Positive values == roll right.
    pitch (float): Pitch angle. Degrees. Positive values == pitch
        forward/down.
    yawrate (float): Yaw angular velocity. Degrees / second. Positive
        values == turn counterclockwise.
    thrust (float): Thrust magnitude. Non-meaningful units in [0, 2^16),
        where the maximum value corresponds to maximum thrust.

◆ cmdVelocityWorld()

cmdVelocityWorld ( self,
vel,
yawRate )

发送世界坐标系下的速度与偏航角速度控制指令。

  • 该指令以速度矢量和偏航角速度作为输入。 发送流式(setpoint)指令会使飞行器进入低级控制模式,不再响应高层指令(如land、goTo)。
参数
vel(array-like of float[3]): 期望速度(米/秒)。
yawRate(float): 偏航角速度(度/秒)。
Sends a streaming velocity-world controller setpoint command.

In this mode, the PC specifies desired velocity vector and yaw rate.
The onboard controller will try to achive this velocity.

NOTE: the Mellinger controller is Crazyswarm's default controller, but
it has not been tuned (or even tested) for velocity control mode.
Switch to the PID controller by changing
`firmwareParams.stabilizer.controller` to `1` in your launch file.

Sending a streaming setpoint of any type will force a change from
high-level to low-level command mode. Currently, there is no mechanism
to change back, but it is a high-priority feature to implement.
This means it is not possible to use e.g. :meth:`land()` or
:meth:`goTo()` after a streaming setpoint has been sent.

Args:
    vel (array-like of float[3]): Velocity. Meters / second.
    yawRate (float): Yaw angular velocity. Degrees / second.

◆ disableCollisionAvoidance()

disableCollisionAvoidance ( self)

禁用机载避碰功能。

Disables onboard collision avoidance.

◆ enableCollisionAvoidance()

enableCollisionAvoidance ( self,
others,
ellipsoidRadii )

启用机载避碰功能,使用缓冲Voronoi单元方法避免与其他无人机碰撞。

  • 参数
    others(List[Crazyflie]): 在仿真中,与列表中的其他对象避碰。 在真实硬件中忽略该列表,并对同一信道上的所有Crazyflie进行避碰。
    ellipsoidRadii(array-like of float[3]): 椭球碰撞体的半径,单位:米。
    Enables onboard collision avoidance.
    
    When enabled, avoids colliding with other Crazyflies by using the
    Buffered Voronoi Cells method [1]. Computation is performed onboard.
    
    Args:
        others (List[Crazyflie]): List of other :obj:`Crazyflie` objects.
            In simulation, collision avoidance is checked only with members
            of this list.  With real hardware, this list is **ignored**, and
            collision avoidance is checked with all other Crazyflies on the
            same radio channel.
        ellipsoidRadii (array-like of float[3]): Radii of collision volume ellipsoid in meters.
            The Crazyflie's boundary for collision checking is a tall
            ellipsoid. This accounts for the downwash effect: Due to the
            fast-moving stream of air produced by the rotors, the safe
            distance to pass underneath another rotorcraft is much further
            than the safe distance to pass to the side.
    
    [1] D. Zhou, Wang, Z., Bandyopadhyay, S., and Schwager, M.
        Fast, On-line Collision Avoidance for Dynamic Vehicles using
        Buffered Voronoi Cells.  IEEE Robotics and Automation Letters
        (RA-L), vol. 2, no. 2, pp. 1047 - 1054, 2017.
        https://msl.stanford.edu/fast-line-collision-avoidance-dynamic-vehicles-using-buffered-voronoi-cells
    

◆ getMotionAcc()

getMotionAcc ( self)

获取当前飞行器运动加速度(通过底层接口获得NED坐标系下加速度后转换)。

  • 返回
    np.array([ax, ay, az]): 当前加速度(米/秒²)。

◆ getMotionPos()

getMotionPos ( self)

获取当前飞行器运动位置(通过底层接口获得NED坐标系下位置后转换)。

  • 返回
    np.array([x, y, z]): 当前位置(米)。

◆ getMotionVel()

getMotionVel ( self)

获取当前飞行器运动位置(通过底层接口获得NED坐标系下位置后转换)。

  • 返回
    np.array([x, y, z]): 当前位置(米)。

◆ getParam()

getParam ( self,
name )

获取指定名称的机载参数的当前值。

  • 参数由固件中的变量决定,可用于调节控制器或其他内部行为。
    参数
    name(str): 参数名称。
    返回
    Any: 参数值。
    Returns the current value of the onboard named parameter.
    
    Parameters are named values of various primitive C types that control
    the firmware's behavior. For more information, see
    https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/userguides/logparam/.
    
    Parameters are read at system startup over the radio and cached.
    The ROS launch file can also be used to set parameter values at startup.
    Subsequent calls to :meth:`setParam()` will update the cached value.
    However, if the parameter changes for any other reason, the cached value
    might become stale. This situation is not common.
    
    Args:
        name (str): The parameter's name.
    
    Returns:
        value (Any): The parameter's value.
    

◆ goTo()

goTo ( self,
goal,
yaw,
duration,
relative = False,
groupMask = 0 )

平滑移动到指定目标位置(并悬停),支持绝对或相对坐标和偏航角设定。

  • 参数
    goal(iterable of float): 目标位置 [x, y, z],单位:米。
    yaw(float): 目标偏航角(弧度)。
    duration(float): 从当前状态到达目标点所需时间(秒)。
    relative(bool): 若为True,则goal为相对当前位置的偏移量;否则为绝对坐标。
    groupMask(int): 组掩码。
    Move smoothly to the goal, then hover indefinitely.
    
    Asynchronous command; returns immediately.
    
    Plans a smooth trajectory from the current state to the goal position.
    Will stop smoothly at the goal with minimal overshoot. If the current
    state is at hover, the planned trajectory will be a straight line;
    however, if the current velocity is nonzero, the planned trajectory
    will be a smooth curve.
    
    Plans the trajectory by solving for the unique degree-7 polynomial that
    satisfies the initial conditions of the current position, velocity,
    and acceleration, and ends at the goal position with zero velocity and
    acceleration. The jerk (derivative of acceleration) is fixed at zero at
    both boundary conditions.
    
    .. warning::
        Calling ``goTo`` rapidly and/or with short durations (<< 1 sec) can
        cause instability. Consider using :meth:`cmdPosition()` instead.
    
    Args:
        goal (iterable of 3 floats): The goal position. Meters.
        yaw (float): The goal yaw angle (heading). Radians.
        duration (float): How long until the goal is reached. Seconds.
        relative (bool): If true, the goal position is interpreted as a
            relative offset from the current position. Otherwise, the goal
            position is interpreted as absolute coordintates in the global
            reference frame.
        groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.
    

◆ land()

land ( self,
targetHeight,
duration,
groupMask = 0 )

执行降落动作,以设定的速度飞回指定高度。

  • 参数
    targetHeight(float): 降落到的目标高度(z坐标,米)。
    duration(float): 达到目标高度所需时间(秒)。
    groupMask(int): 组掩码。
    Execute a landing - fly straight down. User must cut power after.
    
    Asynchronous command; returns immediately.
    
    Args:
        targetHeight (float): The z-coordinate at which to land. Meters.
            Usually should be a few centimeters above the initial position
            to ensure that the controller does not try to penetrate the
            floor if the mocap coordinate origin is not perfect.
        duration (float): How long until the height is reached. Seconds.
        groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ loop()

loop ( self)

循环线程函数,用于初始化控制循环环境。


  • 当offboard模式启用时,此函数在后台线程中执行初始设置。
+ 这是这个函数的调用关系图:

◆ notifySetpointsStop()

notifySetpointsStop ( self,
remainValidMillisecs = 100,
groupMask = 0 )

通知飞行器低级控制指令(如cmdVelocityWorld、cmdFullState)即将停止发送,随后返回上层行为。

  • 参数
    remainValidMillisecs(int): 最后一次低级控制指令在无更新下保持有效的毫秒数。
    groupMask(int): 组掩码。
    Informs that streaming low-level setpoint packets are about to stop.
    
    Streaming setpoints are :meth:`cmdVelocityWorld`, :meth:`cmdFullState`,
    and so on. For safety purposes, they normally preempt onboard high-level
    commands such as :meth:`goTo`.
    
    Once preempted, the Crazyflie will not switch back to high-level
    commands (or other behaviors determined by onboard planning/logic) until
    a significant amount of time has elapsed where no low-level setpoint
    was received.
    
    This command short-circuits that waiting period to a user-chosen time.
    It should be called after sending the last low-level setpoint, and
    before sending any high-level command.
    
    A common use case is to execute the :meth:`land` command after using
    streaming setpoint modes.
    
    Args:
        remainValidMillisecs (int): Number of milliseconds that the last
            streaming setpoint should be followed before reverting to the
            onboard-determined behavior. May be longer e.g. if one radio
            is controlling many robots.
    

◆ position()

position ( self)

返回最近一次由运动捕捉系统测量的飞行器真实位置。

  • 如无测量数据,本函数将阻塞直到接收到第一条位置测量数据。
    返回
    np.array[3]: 当前位置(米)。
    Returns the last true position measurement from motion capture.
    
    If at least one position measurement for this robot has been received
    from the motion capture system since startup, this function returns
    immediately with the most recent measurement. However, if **no**
    position measurements have been received, it blocks until the first
    one arrives.
    
    Returns:
        position (np.array[3]): Current position. Meters.
    

◆ readmsg()

readmsg ( self)

读取消息(占位函数,尚未实现)。

◆ setGroupMask()

setGroupMask ( self,
groupMask )

设置此机器人的组掩码位,用于同步执行多机编排动作。

  • 参数
    groupMask(int): 8位整数,每一位表示此机器人是否属于对应组。
    Sets the group mask bits for this robot.
    
    The purpose of groups is to make it possible to trigger an action
    (for example, executing a previously-uploaded trajectory) on a subset
    of all robots without needing to send more than one radio packet.
    This is important to achieve tight, synchronized "choreography".
    
    Up to 8 groups may exist, corresponding to bits in the groupMask byte.
    When a broadcast command is triggered on the :obj:`CrazyflieServer` object
    with a groupMask argument, the command only affects those robots whose
    groupMask has a nonzero bitwise-AND with the command's groupMask.
    A command with a groupMask of zero applies to all robots regardless of
    group membership.
    
    Some individual robot (not broadcast) commands also support groupMask,
    but it is not especially useful in that case.
    
    Args:
        groupMask (int): An 8-bit integer representing this robot's
            membership status in each of the <= 8 possible groups.
    

◆ setLEDColor()

setLEDColor ( self,
r,
g,
b )

设置LED颜色(需要将param "ring/effect"设置为7才能生效)。

  • 此为阻塞命令,在大编队或高频率变化时可能引发稳定性问题。
参数
r(float): 红色分量,[0, 1]。
g(float): 绿色分量,[0, 1]。
b(float): 蓝色分量,[0, 1]。
Sets the color of the LED ring deck.

While most params (such as PID gains) only need to be set once, it is
common to change the LED ring color many times during a flight, e.g.
as some kind of status indicator. This method makes it convenient.

PRECONDITION: The param "ring/effect" must be set to 7 (solid color)
for this command to have any effect. The default mode uses the ring
color to indicate radio connection quality.

This is a blocking command, so it may cause stability problems for
large swarms and/or high-frequency changes.

Args:
    r (float): Red component of color, in range [0, 1].
    g (float): Green component of color, in range [0, 1].
    b (float): Blue component of color, in range [0, 1].

◆ setParam()

setParam ( self,
name,
value )

设置指定名称参数的值。

  • 参数
    name(str): 参数名称。
    value(Any): 参数新值。
    Changes the value of the given parameter.
    
    See :meth:`getParam()` docs for overview of the parameter system.
    
    Args:
        name (str): The parameter's name.
        value (Any): The parameter's value.
    

◆ setParams()

setParams ( self,
params )

批量设置多个参数的值。

  • 参数
    params(Dict[str, Any]): 参数名-值对的字典。
    Changes the value of several parameters at once.
    
    See :meth:`getParam()` docs for overview of the parameter system.
    
    Args:
        params (Dict[str, Any]): Dict of parameter names/values.
    

◆ startTrajectory()

startTrajectory ( self,
trajectoryId,
timescale = 1.0,
reverse = False,
relative = True,
groupMask = 0 )

开始执行预先上传的轨迹。

  • 参数
    trajectoryId(int): 轨迹ID,对应uploadTrajectory上传的ID。
    timescale(float): 时间缩放因子,大于1表示执行时间更长。
    reverse(bool): 若为True,轨迹按时间反向执行。
    relative(bool): 若为True,轨迹的起点位置为当前定位点,否则为绝对位置。
    groupMask(int): 组掩码,用于多机同步控制
    Begins executing a previously uploaded trajectory.
    
    Asynchronous command; returns immediately.
    
    Args:
        trajectoryId (int): ID number as given to :meth:`uploadTrajectory()`.
        timescale (float): Scales the trajectory duration by this factor.
            For example if timescale == 2.0, the trajectory will take twice
            as long to execute as the nominal duration.
        reverse (bool): If true, executes the trajectory backwards in time.
        relative (bool): If true (default), the position of the trajectory
            is shifted such that it begins at the current position setpoint.
            This is usually the desired behavior.
        groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.
    

◆ stop()

stop ( self,
groupMask = 0 )

停止飞行器(在低级命令模式下切断电机电源)。

  • 将电机关闭,但后续低/高级命令能再次重启电机。
    参数
    groupMask(int): 组掩码。
    Cuts power to the motors when operating in low-level command mode.
    
    Intended for non-emergency scenarios, e.g. landing with the possibility
    of taking off again later. Future low- or high-level commands will
    restart the motors.
    
    Args:
        groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.
    

◆ takeoff()

takeoff ( self,
targetHeight,
duration,
groupMask = 0 )

执行起飞动作,以设定的速度飞到指定高度并保持悬停。

  • 参数
    targetHeight(float): 期望的悬停高度(z坐标,米)。
    duration(float): 达到目标高度所需时间(秒)。
    groupMask(int): 组掩码,用于同步多个飞行器动作。
    Execute a takeoff - fly straight up, then hover indefinitely.
    
    Asynchronous command; returns immediately.
    
    Args:
        targetHeight (float): The z-coordinate at which to hover.
        duration (float): How long until the height is reached. Seconds.
        groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.
    
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ uploadTrajectory()

uploadTrajectory ( self,
trajectoryId,
pieceOffset,
trajectory )

上传分段多项式轨迹以供后续执行。

  • 参数
    trajectoryId(int): 轨迹ID号,可上传多个轨迹,每条轨迹有唯一ID。
    pieceOffset(int): 分段起始偏移量(具体含义待补充)。
    trajectory(Trajectory): 分段多项式轨迹对象,详见uav_trajectory.py说明。
    Uploads a piecewise polynomial trajectory for later execution.
    
    See uav_trajectory.py for more information about piecewise polynomial
    trajectories.
    
    Args:
        trajectoryId (int): ID number of this trajectory. Multiple
            trajectories can be uploaded. TODO: what is the maximum ID?
        pieceOffset (int): TODO(whoenig): explain this.
        trajectory (:obj:`pycrazyswarm.uav_trajectory.Trajectory`): Trajectory object.
    

该类的文档由以下文件生成: