mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2025-12-15 12:26:44 +08:00
* Add vitepress tree * Update existing workflows so they dont trigger on changes in the docs path * Add nojekyll, package.json, LICENCE etc * Add crowdin docs upload/download scripts * Add docs flaw checker workflows * Used docs prefix for docs workflows * Crowdin obvious fixes * ci: docs move to self hosted runner runs on a beefy server for faster builds Signed-off-by: Ramon Roche <mrpollo@gmail.com> * ci: don't run build action for docs or ci changes Signed-off-by: Ramon Roche <mrpollo@gmail.com> * ci: update runners Signed-off-by: Ramon Roche <mrpollo@gmail.com> * Add docs/en * Add docs assets and scripts * Fix up editlinks to point to PX4 sources * Download just the translations that are supported * Add translation sources for zh, uk, ko * Update latest tranlsation and uorb graphs * update vitepress to latest --------- Signed-off-by: Ramon Roche <mrpollo@gmail.com> Co-authored-by: Ramon Roche <mrpollo@gmail.com>
2.2 KiB
2.2 KiB
PositionSetpoint (UORB message)
this file is only used in the position_setpoint triple as a dependency
# this file is only used in the position_setpoint triple as a dependency
uint64 timestamp # time since system start (microseconds)
uint8 SETPOINT_TYPE_POSITION=0 # position setpoint
uint8 SETPOINT_TYPE_VELOCITY=1 # velocity setpoint
uint8 SETPOINT_TYPE_LOITER=2 # loiter setpoint
uint8 SETPOINT_TYPE_TAKEOFF=3 # takeoff setpoint
uint8 SETPOINT_TYPE_LAND=4 # land setpoint, altitude must be ignored, descend until landing
uint8 SETPOINT_TYPE_IDLE=5 # do nothing, switch off motors or keep at idle speed (MC)
uint8 LOITER_TYPE_ORBIT=0 # Circular pattern
uint8 LOITER_TYPE_FIGUREEIGHT=1 # Pattern resembling an 8
bool valid # true if setpoint is valid
uint8 type # setpoint type to adjust behavior of position controller
float32 vx # local velocity setpoint in m/s in NED
float32 vy # local velocity setpoint in m/s in NED
float32 vz # local velocity setpoint in m/s in NED
float64 lat # latitude, in deg
float64 lon # longitude, in deg
float32 alt # altitude AMSL, in m
float32 yaw # yaw (only in hover), in rad [-PI..PI), NaN = leave to flight task
float32 loiter_radius # loiter major axis radius in m
float32 loiter_minor_radius # loiter minor axis radius (used for non-circular loiter shapes) in m
bool loiter_direction_counter_clockwise # loiter direction is clockwise by default and can be changed using this field
float32 loiter_orientation # Orientation of the major axis with respect to true north in rad [-pi,pi)
uint8 loiter_pattern # loitern pattern to follow
float32 acceptance_radius # horizontal acceptance_radius (meters)
float32 alt_acceptance_radius # vertical acceptance radius, only used for fixed wing guidance, NAN = let guidance choose (meters)
float32 cruising_speed # the generally desired cruising speed (not a hard constraint)
bool gliding_enabled # commands the vehicle to glide if the capability is available (fixed wing only)
float32 cruising_throttle # the generally desired cruising throttle (not a hard constraint), only has an effect for rover