Constructor
class
new QoSOverridingOptions(policyKinds, optsopt)
Parameters:
| Name | Type | Attributes | Description | ||||||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
policyKinds |
Array.<QoSPolicyKind> | Which QoS policies to expose as parameters. | |||||||||||||
opts |
Object |
<optional> |
Properties
|
- Source:
Example
// Override history, depth, and reliability via parameters
const sub = node.createSubscription(
'std_msgs/msg/String', '/chatter',
{ qos: rclnodejs.QoS.profileDefault,
qosOverridingOptions: QoSOverridingOptions.withDefaultPolicies() },
(msg) => console.log(msg.data)
);
// Now you can override via CLI:
// --ros-args -p "qos_overrides./chatter.subscription.depth:=20"
Methods
function
(static) withDefaultPolicies(optsopt) → {QoSOverridingOptions}
Create options that override history, depth, and reliability —
the most commonly tuned policies.
Parameters:
| Name | Type | Attributes | Description | ||||||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
opts |
Object |
<optional> |
Properties
|
- Source:
Returns:
Type
QoSOverridingOptions