rclnodejs 0.21.3 → 0.22.0
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- package/.github/workflows/identify-ros-distro.yml +1 -0
- package/.github/workflows/linux-build-and-test-compatibility.yml +9 -8
- package/.github/workflows/linux-build-and-test.yml +3 -3
- package/.github/workflows/windows-build-and-test-compatibility.yml +9 -7
- package/.github/workflows/windows-build-and-test.yml +9 -4
- package/README.md +1 -1
- package/bin/linux-x64-110/rclnodejs.node +0 -0
- package/binding.gyp +5 -3
- package/index.js +4 -0
- package/lib/action/client.js +1 -2
- package/lib/action/server.js +1 -2
- package/lib/client.js +3 -2
- package/lib/distro.js +1 -1
- package/lib/entity.js +40 -0
- package/lib/node.js +86 -38
- package/lib/rmw.js +29 -0
- package/lib/subscription.js +52 -2
- package/package.json +13 -6
- package/rosidl_gen/blocklist.json +5 -0
- package/rosidl_gen/filter.js +104 -0
- package/rosidl_gen/idl_generator.js +7 -0
- package/rosidl_gen/index.js +19 -6
- package/rosidl_gen/packages.js +39 -39
- package/rostsd_gen/index.js +9 -1
- package/scripts/npmjs-readme.md +1 -1
- package/scripts/run_test.js +0 -6
- package/src/rcl_bindings.cpp +185 -1
- package/types/entity.d.ts +1 -0
- package/types/interfaces.d.ts +123 -0
- package/types/node.d.ts +79 -2
- package/types/subscription.d.ts +28 -0
package/src/rcl_bindings.cpp
CHANGED
|
@@ -36,6 +36,7 @@
|
|
|
36
36
|
#include <rosidl_generator_c/string_functions.h>
|
|
37
37
|
#endif
|
|
38
38
|
|
|
39
|
+
#include <iostream>
|
|
39
40
|
#include <memory>
|
|
40
41
|
#include <string>
|
|
41
42
|
#include <vector>
|
|
@@ -652,6 +653,8 @@ NAN_METHOD(CreateSubscription) {
|
|
|
652
653
|
*Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked()));
|
|
653
654
|
std::string topic(
|
|
654
655
|
*Nan::Utf8String(info[4]->ToString(currentContent).ToLocalChecked()));
|
|
656
|
+
v8::Local<v8::Object> options =
|
|
657
|
+
info[5]->ToObject(currentContent).ToLocalChecked();
|
|
655
658
|
|
|
656
659
|
rcl_subscription_t* subscription =
|
|
657
660
|
reinterpret_cast<rcl_subscription_t*>(malloc(sizeof(rcl_subscription_t)));
|
|
@@ -659,12 +662,75 @@ NAN_METHOD(CreateSubscription) {
|
|
|
659
662
|
|
|
660
663
|
rcl_subscription_options_t subscription_ops =
|
|
661
664
|
rcl_subscription_get_default_options();
|
|
662
|
-
auto qos_profile = GetQoSProfile(info[5]);
|
|
663
665
|
|
|
666
|
+
v8::Local<v8::Value> qos =
|
|
667
|
+
Nan::Get(options, Nan::New("qos").ToLocalChecked()).ToLocalChecked();
|
|
668
|
+
auto qos_profile = GetQoSProfile(qos);
|
|
664
669
|
if (qos_profile) {
|
|
665
670
|
subscription_ops.qos = *qos_profile;
|
|
666
671
|
}
|
|
667
672
|
|
|
673
|
+
#if ROS_VERSION >= 2205 // 2205 => Humble+
|
|
674
|
+
if (Nan::Has(options, Nan::New("contentFilter").ToLocalChecked())
|
|
675
|
+
.FromMaybe(false)) {
|
|
676
|
+
// configure content-filter
|
|
677
|
+
v8::MaybeLocal<v8::Value> contentFilterVal =
|
|
678
|
+
Nan::Get(options, Nan::New("contentFilter").ToLocalChecked());
|
|
679
|
+
|
|
680
|
+
if (!Nan::Equals(contentFilterVal.ToLocalChecked(), Nan::Undefined())
|
|
681
|
+
.ToChecked()) {
|
|
682
|
+
v8::Local<v8::Object> contentFilter = contentFilterVal.ToLocalChecked()
|
|
683
|
+
->ToObject(currentContent)
|
|
684
|
+
.ToLocalChecked();
|
|
685
|
+
|
|
686
|
+
// expression property is required
|
|
687
|
+
std::string expression(*Nan::Utf8String(
|
|
688
|
+
Nan::Get(contentFilter, Nan::New("expression").ToLocalChecked())
|
|
689
|
+
.ToLocalChecked()
|
|
690
|
+
->ToString(currentContent)
|
|
691
|
+
.ToLocalChecked()));
|
|
692
|
+
|
|
693
|
+
// parameters property (string[]) is optional
|
|
694
|
+
int argc = 0;
|
|
695
|
+
char** argv = nullptr;
|
|
696
|
+
|
|
697
|
+
if (Nan::Has(contentFilter, Nan::New("parameters").ToLocalChecked())
|
|
698
|
+
.FromMaybe(false)) {
|
|
699
|
+
v8::Local<v8::Array> jsArgv = v8::Local<v8::Array>::Cast(
|
|
700
|
+
Nan::Get(contentFilter, Nan::New("parameters").ToLocalChecked())
|
|
701
|
+
.ToLocalChecked());
|
|
702
|
+
argc = jsArgv->Length();
|
|
703
|
+
if (argc > 0) {
|
|
704
|
+
argv = reinterpret_cast<char**>(malloc(argc * sizeof(char*)));
|
|
705
|
+
for (int i = 0; i < argc; i++) {
|
|
706
|
+
Nan::MaybeLocal<v8::Value> jsElement = Nan::Get(jsArgv, i);
|
|
707
|
+
Nan::Utf8String utf8_arg(jsElement.ToLocalChecked());
|
|
708
|
+
int len = utf8_arg.length() + 1;
|
|
709
|
+
argv[i] = reinterpret_cast<char*>(malloc(len * sizeof(char*)));
|
|
710
|
+
snprintf(argv[i], len, "%s", *utf8_arg);
|
|
711
|
+
}
|
|
712
|
+
}
|
|
713
|
+
}
|
|
714
|
+
|
|
715
|
+
rcl_ret_t ret = rcl_subscription_options_set_content_filter_options(
|
|
716
|
+
expression.c_str(), argc, (const char**)argv, &subscription_ops);
|
|
717
|
+
|
|
718
|
+
if (ret != RCL_RET_OK) {
|
|
719
|
+
Nan::ThrowError(rcl_get_error_string().str);
|
|
720
|
+
rcl_reset_error();
|
|
721
|
+
}
|
|
722
|
+
|
|
723
|
+
if (argc) {
|
|
724
|
+
for (int i = 0; i < argc; i++) {
|
|
725
|
+
free(argv[i]);
|
|
726
|
+
}
|
|
727
|
+
free(argv);
|
|
728
|
+
}
|
|
729
|
+
}
|
|
730
|
+
}
|
|
731
|
+
|
|
732
|
+
#endif
|
|
733
|
+
|
|
668
734
|
const rosidl_message_type_support_t* ts =
|
|
669
735
|
GetMessageTypeSupport(package_name, message_sub_folder, message_name);
|
|
670
736
|
|
|
@@ -689,6 +755,121 @@ NAN_METHOD(CreateSubscription) {
|
|
|
689
755
|
}
|
|
690
756
|
}
|
|
691
757
|
|
|
758
|
+
NAN_METHOD(HasContentFilter) {
|
|
759
|
+
#if ROS_VERSION < 2205 // 2205 => Humble+
|
|
760
|
+
info.GetReturnValue().Set(Nan::False());
|
|
761
|
+
return;
|
|
762
|
+
#else
|
|
763
|
+
|
|
764
|
+
RclHandle* subscription_handle = RclHandle::Unwrap<RclHandle>(
|
|
765
|
+
Nan::To<v8::Object>(info[0]).ToLocalChecked());
|
|
766
|
+
rcl_subscription_t* subscription =
|
|
767
|
+
reinterpret_cast<rcl_subscription_t*>(subscription_handle->ptr());
|
|
768
|
+
|
|
769
|
+
bool is_valid = rcl_subscription_is_cft_enabled(subscription);
|
|
770
|
+
info.GetReturnValue().Set(Nan::New(is_valid));
|
|
771
|
+
#endif
|
|
772
|
+
}
|
|
773
|
+
|
|
774
|
+
NAN_METHOD(SetContentFilter) {
|
|
775
|
+
#if ROS_VERSION < 2205 // 2205 => Humble+
|
|
776
|
+
info.GetReturnValue().Set(Nan::False());
|
|
777
|
+
return;
|
|
778
|
+
#else
|
|
779
|
+
v8::Local<v8::Context> currentContext = Nan::GetCurrentContext();
|
|
780
|
+
RclHandle* subscription_handle = RclHandle::Unwrap<RclHandle>(
|
|
781
|
+
Nan::To<v8::Object>(info[0]).ToLocalChecked());
|
|
782
|
+
rcl_subscription_t* subscription =
|
|
783
|
+
reinterpret_cast<rcl_subscription_t*>(subscription_handle->ptr());
|
|
784
|
+
|
|
785
|
+
v8::Local<v8::Object> contentFilter =
|
|
786
|
+
info[1]->ToObject(currentContext).ToLocalChecked();
|
|
787
|
+
|
|
788
|
+
Nan::MaybeLocal<v8::Value> jsExpression =
|
|
789
|
+
Nan::Get(contentFilter, Nan::New("expression").ToLocalChecked());
|
|
790
|
+
Nan::Utf8String utf8_arg(jsExpression.ToLocalChecked());
|
|
791
|
+
int len = utf8_arg.length() + 1;
|
|
792
|
+
char* expression = reinterpret_cast<char*>(malloc(len * sizeof(char*)));
|
|
793
|
+
snprintf(expression, len, "%s", *utf8_arg);
|
|
794
|
+
|
|
795
|
+
// parameters property (string[]) is optional
|
|
796
|
+
int argc = 0;
|
|
797
|
+
char** argv = nullptr;
|
|
798
|
+
|
|
799
|
+
if (Nan::Has(contentFilter, Nan::New("parameters").ToLocalChecked())
|
|
800
|
+
.FromMaybe(false)) {
|
|
801
|
+
v8::Local<v8::Array> jsArgv = v8::Local<v8::Array>::Cast(
|
|
802
|
+
Nan::Get(contentFilter, Nan::New("parameters").ToLocalChecked())
|
|
803
|
+
.ToLocalChecked());
|
|
804
|
+
argc = jsArgv->Length();
|
|
805
|
+
if (argc > 0) {
|
|
806
|
+
argv = reinterpret_cast<char**>(malloc(argc * sizeof(char*)));
|
|
807
|
+
for (int i = 0; i < argc; i++) {
|
|
808
|
+
Nan::MaybeLocal<v8::Value> jsElement = Nan::Get(jsArgv, i);
|
|
809
|
+
Nan::Utf8String utf8_arg(jsElement.ToLocalChecked());
|
|
810
|
+
int len = utf8_arg.length() + 1;
|
|
811
|
+
argv[i] = reinterpret_cast<char*>(malloc(len * sizeof(char*)));
|
|
812
|
+
snprintf(argv[i], len, "%s", *utf8_arg);
|
|
813
|
+
}
|
|
814
|
+
}
|
|
815
|
+
}
|
|
816
|
+
|
|
817
|
+
// create ctf options
|
|
818
|
+
rcl_subscription_content_filter_options_t options =
|
|
819
|
+
rcl_get_zero_initialized_subscription_content_filter_options();
|
|
820
|
+
|
|
821
|
+
THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK,
|
|
822
|
+
rcl_subscription_content_filter_options_set(
|
|
823
|
+
subscription,
|
|
824
|
+
expression, // expression.c_str(),
|
|
825
|
+
argc, (const char**)argv, &options),
|
|
826
|
+
rcl_get_error_string().str);
|
|
827
|
+
|
|
828
|
+
THROW_ERROR_IF_NOT_EQUAL(
|
|
829
|
+
RCL_RET_OK, rcl_subscription_set_content_filter(subscription, &options),
|
|
830
|
+
rcl_get_error_string().str);
|
|
831
|
+
|
|
832
|
+
if (argc) {
|
|
833
|
+
free(expression);
|
|
834
|
+
|
|
835
|
+
for (int i = 0; i < argc; i++) {
|
|
836
|
+
free(argv[i]);
|
|
837
|
+
}
|
|
838
|
+
free(argv);
|
|
839
|
+
}
|
|
840
|
+
|
|
841
|
+
info.GetReturnValue().Set(Nan::True());
|
|
842
|
+
#endif
|
|
843
|
+
}
|
|
844
|
+
|
|
845
|
+
NAN_METHOD(ClearContentFilter) {
|
|
846
|
+
#if ROS_VERSION < 2205 // 2205 => Humble+
|
|
847
|
+
info.GetReturnValue().Set(Nan::False());
|
|
848
|
+
return;
|
|
849
|
+
#else
|
|
850
|
+
RclHandle* subscription_handle = RclHandle::Unwrap<RclHandle>(
|
|
851
|
+
Nan::To<v8::Object>(info[0]).ToLocalChecked());
|
|
852
|
+
rcl_subscription_t* subscription =
|
|
853
|
+
reinterpret_cast<rcl_subscription_t*>(subscription_handle->ptr());
|
|
854
|
+
|
|
855
|
+
// create ctf options
|
|
856
|
+
rcl_subscription_content_filter_options_t options =
|
|
857
|
+
rcl_get_zero_initialized_subscription_content_filter_options();
|
|
858
|
+
|
|
859
|
+
THROW_ERROR_IF_NOT_EQUAL(
|
|
860
|
+
RCL_RET_OK,
|
|
861
|
+
rcl_subscription_content_filter_options_init(
|
|
862
|
+
subscription, "", 0, (const char**)nullptr, &options),
|
|
863
|
+
rcl_get_error_string().str);
|
|
864
|
+
|
|
865
|
+
THROW_ERROR_IF_NOT_EQUAL(
|
|
866
|
+
RCL_RET_OK, rcl_subscription_set_content_filter(subscription, &options),
|
|
867
|
+
rcl_get_error_string().str);
|
|
868
|
+
|
|
869
|
+
info.GetReturnValue().Set(Nan::True());
|
|
870
|
+
#endif
|
|
871
|
+
}
|
|
872
|
+
|
|
692
873
|
NAN_METHOD(CreatePublisher) {
|
|
693
874
|
v8::Local<v8::Context> currentContent = Nan::GetCurrentContext();
|
|
694
875
|
// Extract arguments
|
|
@@ -1783,6 +1964,9 @@ std::vector<BindingMethod> binding_methods = {
|
|
|
1783
1964
|
{"getRosTimeOverrideIsEnabled", GetRosTimeOverrideIsEnabled},
|
|
1784
1965
|
{"rclTake", RclTake},
|
|
1785
1966
|
{"createSubscription", CreateSubscription},
|
|
1967
|
+
{"hasContentFilter", HasContentFilter},
|
|
1968
|
+
{"setContentFilter", SetContentFilter},
|
|
1969
|
+
{"clearContentFilter", ClearContentFilter},
|
|
1786
1970
|
{"createPublisher", CreatePublisher},
|
|
1787
1971
|
{"publish", Publish},
|
|
1788
1972
|
{"getTopic", GetTopic},
|
package/types/entity.d.ts
CHANGED
package/types/interfaces.d.ts
CHANGED
|
@@ -1751,7 +1751,39 @@ declare module 'rclnodejs' {
|
|
|
1751
1751
|
}
|
|
1752
1752
|
|
|
1753
1753
|
namespace rosbag2_interfaces {
|
|
1754
|
+
namespace msg {
|
|
1755
|
+
export interface ReadSplitEvent {
|
|
1756
|
+
closed_file: string;
|
|
1757
|
+
opened_file: string;
|
|
1758
|
+
}
|
|
1759
|
+
export interface ReadSplitEventConstructor {
|
|
1760
|
+
new(other?: ReadSplitEvent): ReadSplitEvent;
|
|
1761
|
+
}
|
|
1762
|
+
export interface WriteSplitEvent {
|
|
1763
|
+
closed_file: string;
|
|
1764
|
+
opened_file: string;
|
|
1765
|
+
}
|
|
1766
|
+
export interface WriteSplitEventConstructor {
|
|
1767
|
+
new(other?: WriteSplitEvent): WriteSplitEvent;
|
|
1768
|
+
}
|
|
1769
|
+
}
|
|
1754
1770
|
namespace srv {
|
|
1771
|
+
export interface BurstConstructor extends ROSService {
|
|
1772
|
+
readonly Request: Burst_RequestConstructor;
|
|
1773
|
+
readonly Response: Burst_ResponseConstructor;
|
|
1774
|
+
}
|
|
1775
|
+
export interface Burst_Request {
|
|
1776
|
+
num_messages: number;
|
|
1777
|
+
}
|
|
1778
|
+
export interface Burst_RequestConstructor {
|
|
1779
|
+
new(other?: Burst_Request): Burst_Request;
|
|
1780
|
+
}
|
|
1781
|
+
export interface Burst_Response {
|
|
1782
|
+
actually_burst: number;
|
|
1783
|
+
}
|
|
1784
|
+
export interface Burst_ResponseConstructor {
|
|
1785
|
+
new(other?: Burst_Response): Burst_Response;
|
|
1786
|
+
}
|
|
1755
1787
|
export interface GetRateConstructor extends ROSService {
|
|
1756
1788
|
readonly Request: GetRate_RequestConstructor;
|
|
1757
1789
|
readonly Response: GetRate_ResponseConstructor;
|
|
@@ -1857,6 +1889,21 @@ declare module 'rclnodejs' {
|
|
|
1857
1889
|
export interface SetRate_ResponseConstructor {
|
|
1858
1890
|
new(other?: SetRate_Response): SetRate_Response;
|
|
1859
1891
|
}
|
|
1892
|
+
export interface SnapshotConstructor extends ROSService {
|
|
1893
|
+
readonly Request: Snapshot_RequestConstructor;
|
|
1894
|
+
readonly Response: Snapshot_ResponseConstructor;
|
|
1895
|
+
}
|
|
1896
|
+
export interface Snapshot_Request {
|
|
1897
|
+
}
|
|
1898
|
+
export interface Snapshot_RequestConstructor {
|
|
1899
|
+
new(other?: Snapshot_Request): Snapshot_Request;
|
|
1900
|
+
}
|
|
1901
|
+
export interface Snapshot_Response {
|
|
1902
|
+
success: boolean;
|
|
1903
|
+
}
|
|
1904
|
+
export interface Snapshot_ResponseConstructor {
|
|
1905
|
+
new(other?: Snapshot_Response): Snapshot_Response;
|
|
1906
|
+
}
|
|
1860
1907
|
export interface TogglePausedConstructor extends ROSService {
|
|
1861
1908
|
readonly Request: TogglePaused_RequestConstructor;
|
|
1862
1909
|
readonly Response: TogglePaused_ResponseConstructor;
|
|
@@ -2252,12 +2299,14 @@ declare module 'rclnodejs' {
|
|
|
2252
2299
|
export interface SolidPrimitive {
|
|
2253
2300
|
type: number;
|
|
2254
2301
|
dimensions: number[] | Float64Array;
|
|
2302
|
+
polygon: geometry_msgs.msg.Polygon;
|
|
2255
2303
|
}
|
|
2256
2304
|
export interface SolidPrimitiveConstructor {
|
|
2257
2305
|
readonly BOX: number;
|
|
2258
2306
|
readonly SPHERE: number;
|
|
2259
2307
|
readonly CYLINDER: number;
|
|
2260
2308
|
readonly CONE: number;
|
|
2309
|
+
readonly PRISM: number;
|
|
2261
2310
|
readonly BOX_X: number;
|
|
2262
2311
|
readonly BOX_Y: number;
|
|
2263
2312
|
readonly BOX_Z: number;
|
|
@@ -2266,6 +2315,7 @@ declare module 'rclnodejs' {
|
|
|
2266
2315
|
readonly CYLINDER_RADIUS: number;
|
|
2267
2316
|
readonly CONE_HEIGHT: number;
|
|
2268
2317
|
readonly CONE_RADIUS: number;
|
|
2318
|
+
readonly PRISM_HEIGHT: number;
|
|
2269
2319
|
new(other?: SolidPrimitive): SolidPrimitive;
|
|
2270
2320
|
}
|
|
2271
2321
|
}
|
|
@@ -2772,6 +2822,41 @@ declare module 'rclnodejs' {
|
|
|
2772
2822
|
export interface BasicTypesConstructor {
|
|
2773
2823
|
new(other?: BasicTypes): BasicTypes;
|
|
2774
2824
|
}
|
|
2825
|
+
export interface BoundedPlainSequences {
|
|
2826
|
+
bool_values: boolean[];
|
|
2827
|
+
byte_values: number[] | Uint8Array;
|
|
2828
|
+
char_values: number[] | Int8Array;
|
|
2829
|
+
float32_values: number[] | Float32Array;
|
|
2830
|
+
float64_values: number[] | Float64Array;
|
|
2831
|
+
int8_values: number[] | Int8Array;
|
|
2832
|
+
uint8_values: number[] | Uint8Array;
|
|
2833
|
+
int16_values: number[] | Int16Array;
|
|
2834
|
+
uint16_values: number[] | Uint16Array;
|
|
2835
|
+
int32_values: number[] | Int32Array;
|
|
2836
|
+
uint32_values: number[] | Uint32Array;
|
|
2837
|
+
int64_values: number[];
|
|
2838
|
+
uint64_values: number[];
|
|
2839
|
+
basic_types_values: test_msgs.msg.BasicTypes[];
|
|
2840
|
+
constants_values: test_msgs.msg.Constants[];
|
|
2841
|
+
defaults_values: test_msgs.msg.Defaults[];
|
|
2842
|
+
bool_values_default: boolean[];
|
|
2843
|
+
byte_values_default: number[] | Uint8Array;
|
|
2844
|
+
char_values_default: number[] | Int8Array;
|
|
2845
|
+
float32_values_default: number[] | Float32Array;
|
|
2846
|
+
float64_values_default: number[] | Float64Array;
|
|
2847
|
+
int8_values_default: number[] | Int8Array;
|
|
2848
|
+
uint8_values_default: number[] | Uint8Array;
|
|
2849
|
+
int16_values_default: number[] | Int16Array;
|
|
2850
|
+
uint16_values_default: number[] | Uint16Array;
|
|
2851
|
+
int32_values_default: number[] | Int32Array;
|
|
2852
|
+
uint32_values_default: number[] | Uint32Array;
|
|
2853
|
+
int64_values_default: number[];
|
|
2854
|
+
uint64_values_default: number[];
|
|
2855
|
+
alignment_check: number;
|
|
2856
|
+
}
|
|
2857
|
+
export interface BoundedPlainSequencesConstructor {
|
|
2858
|
+
new(other?: BoundedPlainSequences): BoundedPlainSequences;
|
|
2859
|
+
}
|
|
2775
2860
|
export interface BoundedSequences {
|
|
2776
2861
|
bool_values: boolean[];
|
|
2777
2862
|
byte_values: number[] | Uint8Array;
|
|
@@ -3552,8 +3637,12 @@ declare module 'rclnodejs' {
|
|
|
3552
3637
|
frame_locked: boolean;
|
|
3553
3638
|
points: geometry_msgs.msg.Point[];
|
|
3554
3639
|
colors: std_msgs.msg.ColorRGBA[];
|
|
3640
|
+
texture_resource: string;
|
|
3641
|
+
texture: sensor_msgs.msg.CompressedImage;
|
|
3642
|
+
uv_coordinates: visualization_msgs.msg.UVCoordinate[];
|
|
3555
3643
|
text: string;
|
|
3556
3644
|
mesh_resource: string;
|
|
3645
|
+
mesh_file: visualization_msgs.msg.MeshFile;
|
|
3557
3646
|
mesh_use_embedded_materials: boolean;
|
|
3558
3647
|
}
|
|
3559
3648
|
export interface MarkerConstructor {
|
|
@@ -3594,6 +3683,20 @@ declare module 'rclnodejs' {
|
|
|
3594
3683
|
readonly ROSLAUNCH: number;
|
|
3595
3684
|
new(other?: MenuEntry): MenuEntry;
|
|
3596
3685
|
}
|
|
3686
|
+
export interface MeshFile {
|
|
3687
|
+
filename: string;
|
|
3688
|
+
data: number[] | Uint8Array;
|
|
3689
|
+
}
|
|
3690
|
+
export interface MeshFileConstructor {
|
|
3691
|
+
new(other?: MeshFile): MeshFile;
|
|
3692
|
+
}
|
|
3693
|
+
export interface UVCoordinate {
|
|
3694
|
+
u: number;
|
|
3695
|
+
v: number;
|
|
3696
|
+
}
|
|
3697
|
+
export interface UVCoordinateConstructor {
|
|
3698
|
+
new(other?: UVCoordinate): UVCoordinate;
|
|
3699
|
+
}
|
|
3597
3700
|
}
|
|
3598
3701
|
namespace srv {
|
|
3599
3702
|
export interface GetInteractiveMarkersConstructor extends ROSService {
|
|
@@ -3814,6 +3917,10 @@ declare module 'rclnodejs' {
|
|
|
3814
3917
|
'ros2cli_test_interfaces/msg/ShortVariedNested': ros2cli_test_interfaces.msg.ShortVariedNested,
|
|
3815
3918
|
'ros2cli_test_interfaces/srv/ShortVariedMultiNested_Request': ros2cli_test_interfaces.srv.ShortVariedMultiNested_Request,
|
|
3816
3919
|
'ros2cli_test_interfaces/srv/ShortVariedMultiNested_Response': ros2cli_test_interfaces.srv.ShortVariedMultiNested_Response,
|
|
3920
|
+
'rosbag2_interfaces/msg/ReadSplitEvent': rosbag2_interfaces.msg.ReadSplitEvent,
|
|
3921
|
+
'rosbag2_interfaces/msg/WriteSplitEvent': rosbag2_interfaces.msg.WriteSplitEvent,
|
|
3922
|
+
'rosbag2_interfaces/srv/Burst_Request': rosbag2_interfaces.srv.Burst_Request,
|
|
3923
|
+
'rosbag2_interfaces/srv/Burst_Response': rosbag2_interfaces.srv.Burst_Response,
|
|
3817
3924
|
'rosbag2_interfaces/srv/GetRate_Request': rosbag2_interfaces.srv.GetRate_Request,
|
|
3818
3925
|
'rosbag2_interfaces/srv/GetRate_Response': rosbag2_interfaces.srv.GetRate_Response,
|
|
3819
3926
|
'rosbag2_interfaces/srv/IsPaused_Request': rosbag2_interfaces.srv.IsPaused_Request,
|
|
@@ -3828,6 +3935,8 @@ declare module 'rclnodejs' {
|
|
|
3828
3935
|
'rosbag2_interfaces/srv/Seek_Response': rosbag2_interfaces.srv.Seek_Response,
|
|
3829
3936
|
'rosbag2_interfaces/srv/SetRate_Request': rosbag2_interfaces.srv.SetRate_Request,
|
|
3830
3937
|
'rosbag2_interfaces/srv/SetRate_Response': rosbag2_interfaces.srv.SetRate_Response,
|
|
3938
|
+
'rosbag2_interfaces/srv/Snapshot_Request': rosbag2_interfaces.srv.Snapshot_Request,
|
|
3939
|
+
'rosbag2_interfaces/srv/Snapshot_Response': rosbag2_interfaces.srv.Snapshot_Response,
|
|
3831
3940
|
'rosbag2_interfaces/srv/TogglePaused_Request': rosbag2_interfaces.srv.TogglePaused_Request,
|
|
3832
3941
|
'rosbag2_interfaces/srv/TogglePaused_Response': rosbag2_interfaces.srv.TogglePaused_Response,
|
|
3833
3942
|
'rosgraph_msgs/msg/Clock': rosgraph_msgs.msg.Clock,
|
|
@@ -3922,6 +4031,7 @@ declare module 'rclnodejs' {
|
|
|
3922
4031
|
'test_msgs/action/NestedMessage_SendGoal_Response': test_msgs.action.NestedMessage_SendGoal_Response,
|
|
3923
4032
|
'test_msgs/msg/Arrays': test_msgs.msg.Arrays,
|
|
3924
4033
|
'test_msgs/msg/BasicTypes': test_msgs.msg.BasicTypes,
|
|
4034
|
+
'test_msgs/msg/BoundedPlainSequences': test_msgs.msg.BoundedPlainSequences,
|
|
3925
4035
|
'test_msgs/msg/BoundedSequences': test_msgs.msg.BoundedSequences,
|
|
3926
4036
|
'test_msgs/msg/Builtins': test_msgs.msg.Builtins,
|
|
3927
4037
|
'test_msgs/msg/Constants': test_msgs.msg.Constants,
|
|
@@ -3985,6 +4095,8 @@ declare module 'rclnodejs' {
|
|
|
3985
4095
|
'visualization_msgs/msg/Marker': visualization_msgs.msg.Marker,
|
|
3986
4096
|
'visualization_msgs/msg/MarkerArray': visualization_msgs.msg.MarkerArray,
|
|
3987
4097
|
'visualization_msgs/msg/MenuEntry': visualization_msgs.msg.MenuEntry,
|
|
4098
|
+
'visualization_msgs/msg/MeshFile': visualization_msgs.msg.MeshFile,
|
|
4099
|
+
'visualization_msgs/msg/UVCoordinate': visualization_msgs.msg.UVCoordinate,
|
|
3988
4100
|
'visualization_msgs/srv/GetInteractiveMarkers_Request': visualization_msgs.srv.GetInteractiveMarkers_Request,
|
|
3989
4101
|
'visualization_msgs/srv/GetInteractiveMarkers_Response': visualization_msgs.srv.GetInteractiveMarkers_Response,
|
|
3990
4102
|
};
|
|
@@ -4191,6 +4303,10 @@ declare module 'rclnodejs' {
|
|
|
4191
4303
|
'ros2cli_test_interfaces/msg/ShortVariedNested': ros2cli_test_interfaces.msg.ShortVariedNestedConstructor,
|
|
4192
4304
|
'ros2cli_test_interfaces/srv/ShortVariedMultiNested_Request': ros2cli_test_interfaces.srv.ShortVariedMultiNested_RequestConstructor,
|
|
4193
4305
|
'ros2cli_test_interfaces/srv/ShortVariedMultiNested_Response': ros2cli_test_interfaces.srv.ShortVariedMultiNested_ResponseConstructor,
|
|
4306
|
+
'rosbag2_interfaces/msg/ReadSplitEvent': rosbag2_interfaces.msg.ReadSplitEventConstructor,
|
|
4307
|
+
'rosbag2_interfaces/msg/WriteSplitEvent': rosbag2_interfaces.msg.WriteSplitEventConstructor,
|
|
4308
|
+
'rosbag2_interfaces/srv/Burst_Request': rosbag2_interfaces.srv.Burst_RequestConstructor,
|
|
4309
|
+
'rosbag2_interfaces/srv/Burst_Response': rosbag2_interfaces.srv.Burst_ResponseConstructor,
|
|
4194
4310
|
'rosbag2_interfaces/srv/GetRate_Request': rosbag2_interfaces.srv.GetRate_RequestConstructor,
|
|
4195
4311
|
'rosbag2_interfaces/srv/GetRate_Response': rosbag2_interfaces.srv.GetRate_ResponseConstructor,
|
|
4196
4312
|
'rosbag2_interfaces/srv/IsPaused_Request': rosbag2_interfaces.srv.IsPaused_RequestConstructor,
|
|
@@ -4205,6 +4321,8 @@ declare module 'rclnodejs' {
|
|
|
4205
4321
|
'rosbag2_interfaces/srv/Seek_Response': rosbag2_interfaces.srv.Seek_ResponseConstructor,
|
|
4206
4322
|
'rosbag2_interfaces/srv/SetRate_Request': rosbag2_interfaces.srv.SetRate_RequestConstructor,
|
|
4207
4323
|
'rosbag2_interfaces/srv/SetRate_Response': rosbag2_interfaces.srv.SetRate_ResponseConstructor,
|
|
4324
|
+
'rosbag2_interfaces/srv/Snapshot_Request': rosbag2_interfaces.srv.Snapshot_RequestConstructor,
|
|
4325
|
+
'rosbag2_interfaces/srv/Snapshot_Response': rosbag2_interfaces.srv.Snapshot_ResponseConstructor,
|
|
4208
4326
|
'rosbag2_interfaces/srv/TogglePaused_Request': rosbag2_interfaces.srv.TogglePaused_RequestConstructor,
|
|
4209
4327
|
'rosbag2_interfaces/srv/TogglePaused_Response': rosbag2_interfaces.srv.TogglePaused_ResponseConstructor,
|
|
4210
4328
|
'rosgraph_msgs/msg/Clock': rosgraph_msgs.msg.ClockConstructor,
|
|
@@ -4299,6 +4417,7 @@ declare module 'rclnodejs' {
|
|
|
4299
4417
|
'test_msgs/action/NestedMessage_SendGoal_Response': test_msgs.action.NestedMessage_SendGoal_ResponseConstructor,
|
|
4300
4418
|
'test_msgs/msg/Arrays': test_msgs.msg.ArraysConstructor,
|
|
4301
4419
|
'test_msgs/msg/BasicTypes': test_msgs.msg.BasicTypesConstructor,
|
|
4420
|
+
'test_msgs/msg/BoundedPlainSequences': test_msgs.msg.BoundedPlainSequencesConstructor,
|
|
4302
4421
|
'test_msgs/msg/BoundedSequences': test_msgs.msg.BoundedSequencesConstructor,
|
|
4303
4422
|
'test_msgs/msg/Builtins': test_msgs.msg.BuiltinsConstructor,
|
|
4304
4423
|
'test_msgs/msg/Constants': test_msgs.msg.ConstantsConstructor,
|
|
@@ -4362,6 +4481,8 @@ declare module 'rclnodejs' {
|
|
|
4362
4481
|
'visualization_msgs/msg/Marker': visualization_msgs.msg.MarkerConstructor,
|
|
4363
4482
|
'visualization_msgs/msg/MarkerArray': visualization_msgs.msg.MarkerArrayConstructor,
|
|
4364
4483
|
'visualization_msgs/msg/MenuEntry': visualization_msgs.msg.MenuEntryConstructor,
|
|
4484
|
+
'visualization_msgs/msg/MeshFile': visualization_msgs.msg.MeshFileConstructor,
|
|
4485
|
+
'visualization_msgs/msg/UVCoordinate': visualization_msgs.msg.UVCoordinateConstructor,
|
|
4365
4486
|
'visualization_msgs/srv/GetInteractiveMarkers_Request': visualization_msgs.srv.GetInteractiveMarkers_RequestConstructor,
|
|
4366
4487
|
'visualization_msgs/srv/GetInteractiveMarkers_Response': visualization_msgs.srv.GetInteractiveMarkers_ResponseConstructor,
|
|
4367
4488
|
};
|
|
@@ -4399,6 +4520,7 @@ declare module 'rclnodejs' {
|
|
|
4399
4520
|
'rcl_interfaces/srv/SetParameters': rcl_interfaces.srv.SetParametersConstructor,
|
|
4400
4521
|
'rcl_interfaces/srv/SetParametersAtomically': rcl_interfaces.srv.SetParametersAtomicallyConstructor,
|
|
4401
4522
|
'ros2cli_test_interfaces/srv/ShortVariedMultiNested': ros2cli_test_interfaces.srv.ShortVariedMultiNestedConstructor,
|
|
4523
|
+
'rosbag2_interfaces/srv/Burst': rosbag2_interfaces.srv.BurstConstructor,
|
|
4402
4524
|
'rosbag2_interfaces/srv/GetRate': rosbag2_interfaces.srv.GetRateConstructor,
|
|
4403
4525
|
'rosbag2_interfaces/srv/IsPaused': rosbag2_interfaces.srv.IsPausedConstructor,
|
|
4404
4526
|
'rosbag2_interfaces/srv/Pause': rosbag2_interfaces.srv.PauseConstructor,
|
|
@@ -4406,6 +4528,7 @@ declare module 'rclnodejs' {
|
|
|
4406
4528
|
'rosbag2_interfaces/srv/Resume': rosbag2_interfaces.srv.ResumeConstructor,
|
|
4407
4529
|
'rosbag2_interfaces/srv/Seek': rosbag2_interfaces.srv.SeekConstructor,
|
|
4408
4530
|
'rosbag2_interfaces/srv/SetRate': rosbag2_interfaces.srv.SetRateConstructor,
|
|
4531
|
+
'rosbag2_interfaces/srv/Snapshot': rosbag2_interfaces.srv.SnapshotConstructor,
|
|
4409
4532
|
'rosbag2_interfaces/srv/TogglePaused': rosbag2_interfaces.srv.TogglePausedConstructor,
|
|
4410
4533
|
'sensor_msgs/srv/SetCameraInfo': sensor_msgs.srv.SetCameraInfoConstructor,
|
|
4411
4534
|
'std_srvs/srv/Empty': std_srvs.srv.EmptyConstructor,
|
package/types/node.d.ts
CHANGED
|
@@ -13,6 +13,30 @@ declare module 'rclnodejs' {
|
|
|
13
13
|
name: string;
|
|
14
14
|
};
|
|
15
15
|
|
|
16
|
+
/**
|
|
17
|
+
* A filter description similar to a SQL WHERE clause that limits
|
|
18
|
+
* the data wanted by a Subscription.
|
|
19
|
+
*
|
|
20
|
+
* The `expression` grammar is defined in the DDS 1.4 specification, Annex B.
|
|
21
|
+
* https://www.omg.org/spec/DDS/1.4/PDF
|
|
22
|
+
*/
|
|
23
|
+
interface SubscriptionContentFilter {
|
|
24
|
+
/**
|
|
25
|
+
* Specifies the criteria to select the data samples of
|
|
26
|
+
* interest. It is similar to the WHERE part of an SQL clause.
|
|
27
|
+
* Must be a valid query clause.
|
|
28
|
+
*/
|
|
29
|
+
readonly expression: string;
|
|
30
|
+
|
|
31
|
+
/**
|
|
32
|
+
* The values for the ‘parameters’ (i.e., "%n" tokens) in
|
|
33
|
+
* the filter_expression string. There must be a 1-1 match
|
|
34
|
+
* between values and expression parameters. The maximum
|
|
35
|
+
* number of parameters is 100.
|
|
36
|
+
*/
|
|
37
|
+
readonly parameters?: Array<any>;
|
|
38
|
+
}
|
|
39
|
+
|
|
16
40
|
/**
|
|
17
41
|
* Configuration options when creating new Publishers, Subscribers,
|
|
18
42
|
* Clients and Services.
|
|
@@ -37,16 +61,23 @@ declare module 'rclnodejs' {
|
|
|
37
61
|
* ROS Middleware "quality of service" setting, default: QoS.profileDefault.
|
|
38
62
|
*/
|
|
39
63
|
qos?: T;
|
|
64
|
+
|
|
65
|
+
/**
|
|
66
|
+
* An optional filter descriptions similar to a SQL WHERE clause used by a Subscription to
|
|
67
|
+
* inspect and limit messages that it accepts.
|
|
68
|
+
*/
|
|
69
|
+
contentFilter?: SubscriptionContentFilter;
|
|
40
70
|
}
|
|
41
71
|
|
|
42
72
|
/**
|
|
43
|
-
* Default options when creating a
|
|
73
|
+
* Default options when creating a Publisher, Subscription, Client or Service
|
|
44
74
|
*
|
|
45
75
|
* ```ts
|
|
46
76
|
* {
|
|
47
77
|
* enableTypedArray: true,
|
|
48
78
|
* qos: QoS.profileDefault,
|
|
49
|
-
* isRaw: false
|
|
79
|
+
* isRaw: false,
|
|
80
|
+
* contentFilter: undefined
|
|
50
81
|
* }
|
|
51
82
|
* ```
|
|
52
83
|
*/
|
|
@@ -133,6 +164,21 @@ declare module 'rclnodejs' {
|
|
|
133
164
|
options?: NodeOptions
|
|
134
165
|
);
|
|
135
166
|
|
|
167
|
+
/**
|
|
168
|
+
* Create an Options instance initialized with default values.
|
|
169
|
+
* @returns {Options} - The new initialized instance.
|
|
170
|
+
* @example
|
|
171
|
+
* ```
|
|
172
|
+
* {
|
|
173
|
+
* enableTypedArray: true,
|
|
174
|
+
* isRaw: false,
|
|
175
|
+
* qos: QoS.profileDefault,
|
|
176
|
+
* contentFilter: undefined,
|
|
177
|
+
* }
|
|
178
|
+
* ```
|
|
179
|
+
*/
|
|
180
|
+
static getDefaultOptions(): Options;
|
|
181
|
+
|
|
136
182
|
/**
|
|
137
183
|
* Get the name of the node.
|
|
138
184
|
*
|
|
@@ -248,6 +294,21 @@ declare module 'rclnodejs' {
|
|
|
248
294
|
options?: Options
|
|
249
295
|
): Publisher<T>;
|
|
250
296
|
|
|
297
|
+
/**
|
|
298
|
+
* Create a Subscription.
|
|
299
|
+
*
|
|
300
|
+
* @param typeClass - Type of ROS messages the subscription will subscribe to
|
|
301
|
+
* @param topic - Name of the topic the subcription will subscribe to.
|
|
302
|
+
* @param callback - Called when a new message is received.
|
|
303
|
+
* The serialized message will be null-terminated.
|
|
304
|
+
* @returns New instance of Subscription.
|
|
305
|
+
*/
|
|
306
|
+
createSubscription<T extends TypeClass<MessageTypeClassName>>(
|
|
307
|
+
typeClass: T,
|
|
308
|
+
topic: string,
|
|
309
|
+
callback: SubscriptionCallback<T>
|
|
310
|
+
): Subscription;
|
|
311
|
+
|
|
251
312
|
/**
|
|
252
313
|
* Create a Subscription.
|
|
253
314
|
*
|
|
@@ -256,6 +317,8 @@ declare module 'rclnodejs' {
|
|
|
256
317
|
* @param options - Configuration options, see DEFAULT_OPTIONS
|
|
257
318
|
* @param callback - Called when a new message is received. The serialized message will be null-terminated.
|
|
258
319
|
* @returns New instance of Subscription.
|
|
320
|
+
* @throws Error - May throw an RMW error if options.content-filter is malformed.
|
|
321
|
+
* @see {@link https://www.omg.org/spec/DDS/1.4/PDF|Content-filter details at DDS 1.4 specification, Annex B}
|
|
259
322
|
*/
|
|
260
323
|
createSubscription<T extends TypeClass<MessageTypeClassName>>(
|
|
261
324
|
typeClass: T,
|
|
@@ -278,6 +341,20 @@ declare module 'rclnodejs' {
|
|
|
278
341
|
options?: Options
|
|
279
342
|
): Client<T>;
|
|
280
343
|
|
|
344
|
+
/**
|
|
345
|
+
* Create a Service.
|
|
346
|
+
*
|
|
347
|
+
* @param typeClass - Service type
|
|
348
|
+
* @param serviceName - Name of the service.
|
|
349
|
+
* @param callback - Callback function for notification of incoming requests.
|
|
350
|
+
* @returns An instance of Service.
|
|
351
|
+
*/
|
|
352
|
+
createService<T extends TypeClass<ServiceTypeClassName>>(
|
|
353
|
+
typeClass: T,
|
|
354
|
+
serviceName: string,
|
|
355
|
+
callback: ServiceRequestHandler<T>
|
|
356
|
+
): ServiceType<T>;
|
|
357
|
+
|
|
281
358
|
/**
|
|
282
359
|
* Create a Service.
|
|
283
360
|
*
|
package/types/subscription.d.ts
CHANGED
|
@@ -6,6 +6,7 @@ declare module 'rclnodejs' {
|
|
|
6
6
|
*
|
|
7
7
|
* @remarks
|
|
8
8
|
* See {@link Node#createSubscription | Node.createSubscription}
|
|
9
|
+
* See {@link SubscriptionContentFilter}
|
|
9
10
|
* See {@link Node#createPublisher | Node.createPublisher}
|
|
10
11
|
* See {@link Publisher}
|
|
11
12
|
* See {@link Subscription}
|
|
@@ -22,5 +23,32 @@ declare module 'rclnodejs' {
|
|
|
22
23
|
* Topic to listen for messages on.
|
|
23
24
|
*/
|
|
24
25
|
readonly topic: string;
|
|
26
|
+
|
|
27
|
+
/**
|
|
28
|
+
* Specifies if messages are in raw (binary) format
|
|
29
|
+
*/
|
|
30
|
+
readonly isRaw: boolean;
|
|
31
|
+
|
|
32
|
+
/**
|
|
33
|
+
* Test if the RMW supports content-filtered topics and that this subscription
|
|
34
|
+
* is configured with a well formed content-filter.
|
|
35
|
+
* @returns {boolean} True if content-filtering will be applied; otherwise false.
|
|
36
|
+
*/
|
|
37
|
+
hasContentFilter(): boolean;
|
|
38
|
+
|
|
39
|
+
/**
|
|
40
|
+
* Set a content-filter if the RMW supports content-filtered topics.
|
|
41
|
+
* @param contentFilter - The content-filter description to apply.
|
|
42
|
+
* @returns True if successful; false otherwise
|
|
43
|
+
* @remarks
|
|
44
|
+
* @see {@link https://www.omg.org/spec/DDS/1.4/PDF|DDS 1.4 specification, Annex B}
|
|
45
|
+
*/
|
|
46
|
+
setContentFilter(filter: SubscriptionContentFilter): boolean;
|
|
47
|
+
|
|
48
|
+
/**
|
|
49
|
+
* Clear the current content-filter. No filtering is to be applied.
|
|
50
|
+
* @returns True if successful; false otherwise
|
|
51
|
+
*/
|
|
52
|
+
clearContentFilter(): boolean;
|
|
25
53
|
}
|
|
26
54
|
}
|