udaan.models.quadrotor_cspayload.base module¶
QuadrotorCsPayloadBase — pure dynamics and state, no rendering.
Rigid body with cable-suspended payload dynamics with ZOH (zero-order hold) Euler integration.
Dynamics reference: Koushil Sreenath, Taeyoung Lee, and Vijay Kumar. “Geometric control and differential flatness of a quadrotor UAV with a cable-suspended load.” In 52nd IEEE Conference on Decision and Control, pp. 2269-2274. IEEE, 2013. https://hybrid-robotics.berkeley.edu/publications/CDC2013_supplement.pdf
- class udaan.models.quadrotor_cspayload.base.QuadrotorCsPayloadBase[source]¶
Bases:
objectBase quadrotor-cable-suspended payload model — pure dynamics, no rendering.
Supports multiple input types (acceleration, wrench, propeller forces) and force types (wrench, propeller forces). Controllers are pluggable via position_controller and attitude_controller properties.
- property attitude_controller¶
- property inertia¶
- property inertia_inv¶
- property mass¶
- property payload_controller¶
- property position_controller¶
- class udaan.models.quadrotor_cspayload.base.QuadrotorCsPayloadState[source]¶
Bases:
objectQuadrotor with cable-suspended payload state.
- __init__(position=<factory>, velocity=<factory>, orientation=<factory>, angular_velocity=<factory>, payload_position=<factory>, payload_velocity=<factory>, cable_attitude=<factory>, cable_angular_velocity=<factory>)¶