mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
New Crowdin translations - ko
This commit is contained in:
parent
dc8e313c0d
commit
5af5bdb478
@ -47,7 +47,7 @@ PX4 v1.14 (and later) supports the [LightWare LiDAR SF45](../sensor/sf45_rotatin
|
||||
|
||||
- Attach and configure the distance sensor on a particular port (see [sensor-specific docs](../sensor/rangefinders.md)) and enable collision prevention using [CP_DIST](#CP_DIST).
|
||||
- 방향을 설정하려면 드라이버를 수정하십시오.
|
||||
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
|
||||
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
|
||||
- Modify the driver to set the _field of view_ in the distance sensor UORB topic (`distance_sensor_s.h_fov`).
|
||||
|
||||
## PX4 (Software) Setup
|
||||
@ -203,85 +203,85 @@ The Lua script works by extracting the `obstacle_distance_fused` data at each ti
|
||||
|
||||
2. Configure PX4 to publish obstacle distance data (so that it is available to PlotJuggler):
|
||||
|
||||
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
|
||||
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
|
||||
|
||||
```sh
|
||||
- topic: /fmu/out/obstacle_distance_fused
|
||||
type: px4_msgs::msg::ObstacleDistance
|
||||
```
|
||||
```sh
|
||||
- topic: /fmu/out/obstacle_distance_fused
|
||||
type: px4_msgs::msg::ObstacleDistance
|
||||
```
|
||||
|
||||
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in _uXRCE-DDS (PX4-ROS 2/DDS Bridge)_.
|
||||
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)_.
|
||||
|
||||
3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section.
|
||||
In the **Script Editor** tab, add following scripts in the appropriate sections:
|
||||
In the **Script Editor** tab, add following scripts in the appropriate sections:
|
||||
|
||||
- **Global code, executed once:**
|
||||
- **Global code, executed once:**
|
||||
|
||||
```lua
|
||||
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
|
||||
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
|
||||
```
|
||||
```lua
|
||||
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
|
||||
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
|
||||
```
|
||||
|
||||
- **function(tracker_time)**
|
||||
- **function(tracker_time)**
|
||||
|
||||
```lua
|
||||
obs_dist_fused_xy:clear()
|
||||
```lua
|
||||
obs_dist_fused_xy:clear()
|
||||
|
||||
i = 0
|
||||
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
|
||||
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
|
||||
min_dist = 65535
|
||||
i = 0
|
||||
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
|
||||
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
|
||||
min_dist = 65535
|
||||
|
||||
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
|
||||
local angle_offset_value = angle_offset:atTime(tracker_time)
|
||||
local increment_value = increment:atTime(tracker_time)
|
||||
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
|
||||
local angle_offset_value = angle_offset:atTime(tracker_time)
|
||||
local increment_value = increment:atTime(tracker_time)
|
||||
|
||||
if increment_value == nil or increment_value <= 0 then
|
||||
print("Invalid increment value: " .. tostring(increment_value))
|
||||
return
|
||||
end
|
||||
if increment_value == nil or increment_value <= 0 then
|
||||
print("Invalid increment value: " .. tostring(increment_value))
|
||||
return
|
||||
end
|
||||
|
||||
local max_steps = math.floor(360 / increment_value)
|
||||
local max_steps = math.floor(360 / increment_value)
|
||||
|
||||
while i < max_steps do
|
||||
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
|
||||
local distance = TimeseriesView.find(str)
|
||||
if distance == nil then
|
||||
print("No distance data for: " .. str)
|
||||
break
|
||||
end
|
||||
while i < max_steps do
|
||||
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
|
||||
local distance = TimeseriesView.find(str)
|
||||
if distance == nil then
|
||||
print("No distance data for: " .. str)
|
||||
break
|
||||
end
|
||||
|
||||
local dist = distance:atTime(tracker_time)
|
||||
if dist ~= nil and dist < 65535 then
|
||||
-- Calculate angle and Cartesian coordinates
|
||||
local angle = angle_offset_value + i * increment_value
|
||||
local y = dist * math.cos(math.rad(angle))
|
||||
local x = dist * math.sin(math.rad(angle))
|
||||
local dist = distance:atTime(tracker_time)
|
||||
if dist ~= nil and dist < 65535 then
|
||||
-- Calculate angle and Cartesian coordinates
|
||||
local angle = angle_offset_value + i * increment_value
|
||||
local y = dist * math.cos(math.rad(angle))
|
||||
local x = dist * math.sin(math.rad(angle))
|
||||
|
||||
obs_dist_fused_xy:push_back(x, y)
|
||||
obs_dist_fused_xy:push_back(x, y)
|
||||
|
||||
-- Update minimum distance
|
||||
if dist < min_dist then
|
||||
min_dist = dist
|
||||
end
|
||||
end
|
||||
-- Update minimum distance
|
||||
if dist < min_dist then
|
||||
min_dist = dist
|
||||
end
|
||||
end
|
||||
|
||||
i = i + 1
|
||||
end
|
||||
i = i + 1
|
||||
end
|
||||
|
||||
-- Push minimum distance once after the loop
|
||||
if min_dist < 65535 then
|
||||
obs_dist_min:push_back(tracker_time, min_dist)
|
||||
else
|
||||
print("No valid minimum distance found")
|
||||
end
|
||||
```
|
||||
-- Push minimum distance once after the loop
|
||||
if min_dist < 65535 then
|
||||
obs_dist_min:push_back(tracker_time, min_dist)
|
||||
else
|
||||
print("No valid minimum distance found")
|
||||
end
|
||||
```
|
||||
|
||||
4. Enter a name for the script on the top right, and press **Save**.
|
||||
Once saved, the script should appear in the _Active Scripts_ section.
|
||||
Once saved, the script should appear in the _Active Scripts_ section.
|
||||
|
||||
5. Start streaming the data using the approach described in [Plotting uORB Topic Data in Real Time using PlotJuggler](../debug/plotting_realtime_uorb_data.md).
|
||||
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
|
||||
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
|
||||
|
||||
Note that you have to press **Save** again to re-enable the scripts after loading a new log file or otherwise clearing data.
|
||||
|
||||
|
||||
@ -96,13 +96,13 @@ Exporting the messages allows ROS 2 and the uXRCE-DDS agent to be independent of
|
||||
|
||||
While `px4_msgs` has messages for all uORB topics in PX4, not all messages in `px4_msgs` are available to ROS 2/PlotJuggler by default.
|
||||
The set that are available must be built into the client running on PX4.
|
||||
These are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
|
||||
These are defined in [dds_topics.yaml](../middleware/dds_topics.md).
|
||||
|
||||
The instructions below explain the changes needed to monitor topics that are not available by default.
|
||||
|
||||
### Missing Topics
|
||||
|
||||
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) to include the topic and rebuild PX4.
|
||||
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](../middleware/dds_topics.md) ([source](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) to include the topic and rebuild PX4.
|
||||
|
||||
If working with real hardware you will need to build and [install](../config/firmware.md#installing-px4-main-beta-or-custom-firmware) custom firmware after changing the YAML file.
|
||||
|
||||
@ -122,7 +122,7 @@ cd ~/ros2_ws/ && colcon build
|
||||
|
||||
### Custom Topics
|
||||
|
||||
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and export the new message into your ROS 2 workspace.
|
||||
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](../middleware/dds_topics.md), and export the new message into your ROS 2 workspace.
|
||||
|
||||
## See also
|
||||
|
||||
|
||||
@ -128,8 +128,7 @@ In EKF2 mode, the replay will automatically create the ORB publisher rules descr
|
||||
|
||||
To perform an EKF2 replay:
|
||||
|
||||
- Record the original log.
|
||||
Optionally set `SDLOG_MODE` to `1` to log from boot.
|
||||
- Record the original log with `SDLOG_MODE` set to `1` to log from boot.
|
||||
|
||||
- In addition to the `replay` environment variable, set `replay_mode` to `ekf2`:
|
||||
|
||||
|
||||
@ -61,12 +61,12 @@ For example the [VelocityLimits](../msg_docs/VelocityLimits.md) message definiti
|
||||
```text
|
||||
# Velocity and yaw rate limits for a multicopter position slow mode only
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp # [us] Time since system start.
|
||||
|
||||
# absolute speeds, NAN means use default limit
|
||||
float32 horizontal_velocity # [m/s]
|
||||
float32 vertical_velocity # [m/s]
|
||||
float32 yaw_rate # [rad/s]
|
||||
float32 horizontal_velocity # [m/s] Horizontal velocity.
|
||||
float32 vertical_velocity # [m/s] Vertical velocity.
|
||||
float32 yaw_rate # [rad/s] Yaw rate.
|
||||
```
|
||||
|
||||
By default this message definition will be compiled to a single topic with an id `velocity_limits`, a direct conversion from the CamelCase name to a snake_case version.
|
||||
@ -92,15 +92,34 @@ To nest a message, simply include the nested message type in the parent message
|
||||
|
||||
```text
|
||||
# Global position setpoint triplet in WGS84 coordinates.
|
||||
#
|
||||
# This are the three next waypoints (or just the next two or one).
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp # [us] Time since system start.
|
||||
|
||||
PositionSetpoint previous
|
||||
PositionSetpoint current
|
||||
PositionSetpoint next
|
||||
```
|
||||
|
||||
### uORB Buffer Length (ORB_QUEUE_LENGTH)
|
||||
|
||||
uORB messages have a single-message buffer by default, which may be overwritten if the message publication rate is too high.
|
||||
In most cases this does not matter: either we are only interested in the latest sample of a topic, such as a sensor value or a setpoint, or losing a few samples is not a particular problem.
|
||||
For relatively few cases, such as vehicle commands, it is important that we don't drop topics.
|
||||
|
||||
In order to reduce the chance that messages will be dropped we can use named constant `ORB_QUEUE_LENGTH` to create a buffer of the specified length.
|
||||
For example, to create a four-message queue, add the following line to your message definition:
|
||||
|
||||
```sh
|
||||
uint8 ORB_QUEUE_LENGTH = 4
|
||||
```
|
||||
|
||||
As long as subscribers are able to read messages out of the buffer quickly enough than it isn't ever fully filled to the queue length (by publishers), they will be able to get all messages that are sent.
|
||||
Messages will still be lost they are published when the queue is filled.
|
||||
|
||||
Note that the queue length value must be a power of 2 (so 2, 4, 8, ...).
|
||||
|
||||
### Message/Field Deprecation {#deprecation}
|
||||
|
||||
As there are external tools using uORB messages from log files, such as [Flight Review](https://github.com/PX4/flight_review), certain aspects need to be considered when updating existing messages:
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user