AP_DDS: Enable the DDS parameter by default
* DDS is still disabled by default in all builds for the library level compile flag * This parameter was blocking running ROS 2 automated testing in CI * This can be changed once ENABLE_DDS compiler flag is enabled in SITL or for the 4.5 release Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
parent
0d87479314
commit
2c5f90adca
@ -15,6 +15,9 @@
|
||||
#include "AP_DDS_Topic_Table.h"
|
||||
#include "AP_DDS_Service_Table.h"
|
||||
|
||||
// Enable DDS at runtime by default
|
||||
static constexpr uint8_t ENABLED_BY_DEFAULT = 1;
|
||||
|
||||
static constexpr uint16_t DELAY_TIME_TOPIC_MS = 10;
|
||||
static constexpr uint16_t DELAY_BATTERY_STATE_TOPIC_MS = 1000;
|
||||
static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = 33;
|
||||
@ -42,7 +45,7 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] {
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_DDS_Client, enabled, 0, AP_PARAM_FLAG_ENABLE),
|
||||
AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_DDS_Client, enabled, ENABLED_BY_DEFAULT, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
#if AP_DDS_UDP_ENABLED
|
||||
// @Param: _UDP_PORT
|
||||
|
@ -104,25 +104,28 @@ sudo apt-get install socat
|
||||
Set up your [SITL](https://ardupilot.org/dev/docs/setting-up-sitl-on-linux.html).
|
||||
Run the simulator with the following command. If using UDP, the only parameter you need to set it `DDS_ENABLE`.
|
||||
|
||||
| Name | Description |
|
||||
| - | - |
|
||||
| DDS_ENABLE | Set to 1 to enable DDS |
|
||||
| SERIAL1_BAUD | The serial baud rate for DDS |
|
||||
| SERIAL1_PROTOCOL | Set this to 45 to use DDS on the serial port |
|
||||
| Name | Description | Default |
|
||||
| - | - | - |
|
||||
| DDS_ENABLE | Set to 1 to enable DDS, or 0 to disable | 1 |
|
||||
| SERIAL1_BAUD | The serial baud rate for DDS | 57 |
|
||||
| SERIAL1_PROTOCOL | Set this to 45 to use DDS on the serial port | 0 |
|
||||
```bash
|
||||
# Wipe params till you see "AP: ArduPilot Ready"
|
||||
# Select your favorite vehicle type
|
||||
sim_vehicle.py -w -v ArduPlane --console -DG --enable-dds
|
||||
|
||||
# Enable DDS (both for UDP or Serial)
|
||||
param set DDS_ENABLE 1
|
||||
|
||||
# Only for Serial
|
||||
# Only set this for Serial, which means 115200 baud
|
||||
param set SERIAL1_BAUD 115
|
||||
# See libraries/AP_SerialManager/AP_SerialManager.h AP_SerialManager SerialProtocol_DDS_XRCE
|
||||
param set SERIAL1_PROTOCOL 45
|
||||
```
|
||||
Because `DDS_ENABLE` requires a reboot, stop the simulator with ctrl+C and proceed to the next section.
|
||||
|
||||
DDS is currently enabled by default, if it's part of the build. To disable it, run the following and reboot the simulator.
|
||||
```
|
||||
param set DDS_ENABLE 0
|
||||
REBOOT
|
||||
```
|
||||
|
||||
## Setup ROS 2 and micro-ROS
|
||||
|
||||
Follow the steps to use the microROS Agent
|
||||
|
Loading…
Reference in New Issue
Block a user