Open SapanaChaudhary opened 8 months ago
@JacopoPan @spencerteetaert any idea?
Yes, the XY positions of the inputs/motors on the quadrotor are described in the URDF, e.g., see in the lines below that prop0
is at positive 2.8cm from the center of the quad, in the quad frame, then the others in CCW order.
(AFAIK, this is true across the repo, except for the beta-iros-competition
and aer1217-
branches that use the Bitcraze firmware convention because they are controlled via SITL firmware instead of direct motor input).
Thank you for the reference to the urdf file. Considering x and y axis as below:
If the action dimensions are in the same order as prop_links in the urdf file, then action dimensions look like the figure below, as opposed to the figure I had included earlier.
Is this correct?
Yes, you can also just look at these lines mapping inputs and the forces/torque in Bullet https://github.com/utiasDSL/safe-control-gym/blob/83fae93172782f7c6e98063da0b2425d3f741f1b/safe_control_gym/envs/gym_pybullet_drones/base_aviary.py#L392-L406
Hello!
The base model for quadrotor is Bitcraze Craziflie 2.0 in the X configuration. I was wondering here https://github.com/utiasDSL/safe-control-gym/blob/83fae93172782f7c6e98063da0b2425d3f741f1b/safe_control_gym/envs/gym_pybullet_drones/quadrotor.py#L613 which action dimension corresponds to which motor from the image below?