|
| __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) |
|
Object representing a single robot.
The bulk of the module's functionality is contained in this class.
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.
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.
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
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.
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.
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 |
( |
| 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].