mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-04 16:59:31 +00:00
Significant update to simple_offboard node
* Allow using nans for most of services parameters * Add terrain frame * Remove yaw_rate parameter from most services * Add set_yaw and set_yaw_rate services * Correct order for pitch and roll everywhere to match XYZ convention * Add simple_offboard/state topic * Add essential tests * Stop publishing setpoints when land called
This commit is contained in:
@@ -60,8 +60,8 @@ The `SYS_MC_EST_GROUP` parameter defines the estimator subsystem to use.
|
||||
|
||||
Estimator subsystem is a group of modules that calculates the current state of the copter using readings from the sensors. The copter state includes:
|
||||
|
||||
* Angle rate of the copter – pitch_rate, roll_rate, yaw_rate;
|
||||
* Copter orientation (in the local coordinate system) – pitch, roll, yaw (one of presentations);
|
||||
* Angle rate of the copter – roll_rate, pitch_rate, yaw_rate;
|
||||
* Copter orientation (in the local coordinate system) – roll, pitch, yaw (one of presentations);
|
||||
* Copter position (in the local coordinate system) – x, y, z;
|
||||
* Copter speed (in the local coordinate system) – vx, vy, vz;
|
||||
* Global coordinates of the copter – latitude, longitude, altitude;
|
||||
|
||||
@@ -51,11 +51,11 @@ Response format:
|
||||
* `lat, lon` – drone latitude and longitude *(degrees)*, requires [GPS](gps.md) module;
|
||||
* `alt` – altitude in the global coordinate system (according to [WGS-84](https://ru.wikipedia.org/wiki/WGS_84) standard, not <abbr title="Above Mean Sea Level">AMSL</abbr>!), requires [GPS](gps.md) module;
|
||||
* `vx, vy, vz` – drone velocity *(m/s)*;
|
||||
* `pitch` – pitch angle *(radians)*;
|
||||
* `roll` – roll angle *(radians)*;
|
||||
* `pitch` – pitch angle *(radians)*;
|
||||
* `yaw` — yaw angle *(radians)*;
|
||||
* `pitch_rate` — angular pitch velocity *(rad/s)*;
|
||||
* `roll_rate` – angular roll velocity *(rad/s)*;
|
||||
* `pitch_rate` — angular pitch velocity *(rad/s)*;
|
||||
* `yaw_rate` – angular yaw velocity *(rad/s)*;
|
||||
* `voltage` – total battery voltage *(V)*;
|
||||
* `cell_voltage` – battery cell voltage *(V)*.
|
||||
@@ -261,22 +261,22 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
|
||||
|
||||
### set_attitude
|
||||
|
||||
Set pitch, roll, yaw and throttle level (similar to [the `STABILIZED` mode](modes.md)). This service may be used for lower level control of the drone behavior, or controlling the drone when no reliable data on its position is available.
|
||||
Set roll, pitch, yaw and throttle level (similar to [the `STABILIZED` mode](modes.md)). This service may be used for lower level control of the drone behavior, or controlling the drone when no reliable data on its position is available.
|
||||
|
||||
Parameters:
|
||||
|
||||
* `pitch`, `roll`, `yaw` – requested pitch, roll, and yaw angle *(radians)*;
|
||||
* `roll`, `pitch`, `yaw` – requested roll, pitch, and yaw angle *(radians)*;
|
||||
* `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
|
||||
* `auto_arm` – switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
|
||||
* `frame_id` – [coordinate system](frames.md) for `yaw` (Default value: `map`).
|
||||
|
||||
### set_rates
|
||||
|
||||
Set pitch, roll, and yaw rates and the throttle level (similar to [the `ACRO` mode](modes.md)). This is the lowest drone control level (excluding direct control of motor rotation speed). This service may be used to automatically perform aerobatic tricks (e.g., flips).
|
||||
Set roll, pitch, and yaw rates and the throttle level (similar to [the `ACRO` mode](modes.md)). This is the lowest drone control level (excluding direct control of motor rotation speed). This service may be used to automatically perform aerobatic tricks (e.g., flips).
|
||||
|
||||
Parameters:
|
||||
|
||||
* `pitch_rate`, `roll_rate`, `yaw_rate` – pitch, roll, and yaw rates *(rad/s)*;
|
||||
* `roll_rate`, `pitch_rate`, `yaw_rate` – pitch, roll, and yaw rates *(rad/s)*;
|
||||
* `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
|
||||
* `auto_arm` – switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**);
|
||||
|
||||
|
||||
@@ -144,7 +144,7 @@ Determine whether the copter is turned upside-down:
|
||||
PI_2 = math.pi / 2
|
||||
telem = get_telemetry()
|
||||
|
||||
flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
|
||||
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2
|
||||
```
|
||||
|
||||
### # {#angle-hor}
|
||||
@@ -155,8 +155,8 @@ Calculate the copter horizontal angle:
|
||||
PI_2 = math.pi / 2
|
||||
telem = get_telemetry()
|
||||
|
||||
flipped = not -PI_2 <= telem.pitch <= PI_2 or not -PI_2 <= telem.roll <= PI_2
|
||||
angle_to_horizon = math.atan(math.hypot(math.tan(telem.pitch), math.tan(telem.roll)))
|
||||
flipped = not -PI_2 <= telem.roll <= PI_2 or not -PI_2 <= telem.pitch <= PI_2
|
||||
angle_to_horizon = math.atan(math.hypot(math.tan(telem.roll), math.tan(telem.pitch)))
|
||||
if flipped:
|
||||
angle_to_horizon = math.pi - angle_to_horizon
|
||||
```
|
||||
@@ -324,7 +324,7 @@ def flip():
|
||||
|
||||
while True:
|
||||
telem = get_telemetry()
|
||||
flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
|
||||
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2
|
||||
if flipped:
|
||||
break
|
||||
|
||||
|
||||
Reference in New Issue
Block a user