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

Public 成员函数

 __init__ (self, id, initialPosition, tf, mode)
 
 loop (self)
 
 setGroupMask (self, groupMask)
 
 enableCollisionAvoidance (self, others, ellipsoidRadii)
 
 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)
 
 position (self)
 
 getParam (self, name)
 
 setParam (self, name, value)
 
 setParams (self, params)
 
 cmdFullState (self, pos, vel, acc, yaw, omega)
 
 cmdVelocityWorld (self, vel, yawRate)
 
 cmdStop (self)
 
 cmdVel (self, roll, pitch, yawrate, thrust)
 
 cmdPosition (self, pos, yaw=0)
 
 setLEDColor (self, r, g, b)
 
 readmsg (self)
 
 getMotionPos (self)
 
 getMotionVel (self)
 
 getMotionAcc (self)
 

Public 属性

 id
 
 mode
 
 prefix
 
 initialPosition
 
 tf
 
 ctrl
 
 mapini
 
 ini_success
 

详细描述

Object representing a single robot.

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

构造及析构函数说明

◆ __init__()

__init__ ( self,
id,
initialPosition,
tf,
mode )
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 )
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 )
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 )
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 )
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 )
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

◆ getParam()

getParam ( self,
name )
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 )
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 )
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.
+ 函数调用图:
+ 这是这个函数的调用关系图:

◆ notifySetpointsStop()

notifySetpointsStop ( self,
remainValidMillisecs = 100,
groupMask = 0 )
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)
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.

◆ setGroupMask()

setGroupMask ( self,
groupMask )
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 )
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 )
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 )
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 )
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 )
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 )
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 )
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.

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