Skip to content

Commit

Permalink
Update PX4 Firmware metadata Tue Jan 14 14:01:09 UTC 2025
Browse files Browse the repository at this point in the history
  • Loading branch information
PX4BuildBot committed Jan 14, 2025
1 parent f9071d6 commit fc9dfe7
Show file tree
Hide file tree
Showing 12 changed files with 43 additions and 12 deletions.
30 changes: 30 additions & 0 deletions en/advanced_config/parameter_reference.md
Original file line number Diff line number Diff line change
Expand Up @@ -18353,6 +18353,36 @@ Reboot | minValue | maxValue | increment | default | unit
--- | --- | --- | --- | --- | ---
  | -1 | 1 | 0.1 | 0.45 |

### CA_HELI_RPM_I (`FLOAT`) {#CA_HELI_RPM_I}

Integral gain for rpm control.

Same definition as the proportional gain but for integral.

Reboot | minValue | maxValue | increment | default | unit
--- | --- | --- | --- | --- | ---
  | 0 | 10 | 0.1 | 0.0 |

### CA_HELI_RPM_P (`FLOAT`) {#CA_HELI_RPM_P}

Proportional gain for rpm control.

Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it. motor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000

Reboot | minValue | maxValue | increment | default | unit
--- | --- | --- | --- | --- | ---
  | 0 | 10 | 0.1 | 0.0 |

### CA_HELI_RPM_SP (`FLOAT`) {#CA_HELI_RPM_SP}

Setpoint for main rotor rpm.

Requires rpm feedback for the controller.

Reboot | minValue | maxValue | increment | default | unit
--- | --- | --- | --- | --- | ---
  | 100 | 10000 | 1 | 1500 |

### CA_HELI_THR_C0 (`FLOAT`) {#CA_HELI_THR_C0}

Throttle curve at position 0.
Expand Down
8 changes: 4 additions & 4 deletions en/msg_docs/PwmInput.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PwmInput.msg)

```c
uint64 timestamp # Time since system start (microseconds)
uint64 error_count # Timer overcapture error flag (AUX5 or MAIN5)
uint32 pulse_width # Pulse width, timer counts
uint32 period # Period, timer counts
uint64 timestamp # Time since system start (microseconds)
uint64 error_count # Timer overcapture error flag (AUX5 or MAIN5)
uint32 pulse_width # Pulse width, timer counts (microseconds)
uint32 period # Period, timer counts (microseconds)

```
1 change: 1 addition & 0 deletions en/msg_docs/Rpm.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
```c
uint64 timestamp # time since system start (microseconds)

# rpm values of 0.0 mean within a timeout there is no movement measured
float32 rpm_estimate # filtered revolutions per minute
float32 rpm_raw

Expand Down
2 changes: 1 addition & 1 deletion public/config/failsafe/index.js

Large diffs are not rendered by default.

Binary file modified public/config/failsafe/index.wasm
Binary file not shown.
2 changes: 1 addition & 1 deletion public/config/failsafe/parameters.json

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion public/middleware/graph_full.json

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion public/middleware/graph_full_no_mavlink.json

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion public/middleware/graph_px4_fmu-v2.json

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion public/middleware/graph_px4_fmu-v4.json

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion public/middleware/graph_px4_fmu-v5.json

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion public/middleware/graph_px4_sitl.json

Large diffs are not rendered by default.

0 comments on commit fc9dfe7

Please sign in to comment.