mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_DDS: add param DDS_DOMAIN_ID
- Require reboot. - Set DDS_DOMAIN_ID range: 0 to 232.. Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
8674bb84a6
commit
5919ef69cb
@ -74,6 +74,14 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] {
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// @Param: _DOMAIN_ID
|
||||||
|
// @DisplayName: DDS DOMAIN ID
|
||||||
|
// @Description: Set the ROS_DOMAIN_ID
|
||||||
|
// @Range: 0 232
|
||||||
|
// @RebootRequired: True
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("_DOMAIN_ID", 4, AP_DDS_Client, domain_id, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -819,9 +827,8 @@ bool AP_DDS_Client::create()
|
|||||||
.type = UXR_PARTICIPANT_ID
|
.type = UXR_PARTICIPANT_ID
|
||||||
};
|
};
|
||||||
const char* participant_name = "ardupilot_dds";
|
const char* participant_name = "ardupilot_dds";
|
||||||
const uint16_t domain_id = 0;
|
|
||||||
const auto participant_req_id = uxr_buffer_create_participant_bin(&session, reliable_out, participant_id,
|
const auto participant_req_id = uxr_buffer_create_participant_bin(&session, reliable_out, participant_id,
|
||||||
domain_id, participant_name, UXR_REPLACE);
|
static_cast<uint16_t>(domain_id), participant_name, UXR_REPLACE);
|
||||||
|
|
||||||
//Participant requests
|
//Participant requests
|
||||||
constexpr uint8_t nRequestsParticipant = 1;
|
constexpr uint8_t nRequestsParticipant = 1;
|
||||||
|
@ -213,6 +213,9 @@ public:
|
|||||||
//! @brief Parameter storage
|
//! @brief Parameter storage
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
//! @brief ROS_DOMAIN_ID
|
||||||
|
AP_Int32 domain_id;
|
||||||
|
|
||||||
//! @brief Enum used to mark a topic as a data reader or writer
|
//! @brief Enum used to mark a topic as a data reader or writer
|
||||||
enum class Topic_rw : uint8_t {
|
enum class Topic_rw : uint8_t {
|
||||||
DataReader = 0,
|
DataReader = 0,
|
||||||
|
Loading…
Reference in New Issue
Block a user