diff --git a/binding.gyp b/binding.gyp index 5833877d..73658b23 100644 --- a/binding.gyp +++ b/binding.gyp @@ -28,8 +28,7 @@ './src/shadow_node.cpp', ], 'include_dirs': [ - '.', - " + +// ...existing code... + +// N-API initialization function +napi_value Init(napi_env env, napi_value exports) { + // ...existing code... + return exports; +} + +// ...existing code... + +NAPI_MODULE(NODE_GYP_MODULE_NAME, Init) diff --git a/example_node_api.cc b/example_node_api.cc new file mode 100644 index 00000000..64213e4a --- /dev/null +++ b/example_node_api.cc @@ -0,0 +1,13 @@ +#include + +// ...existing code... + +// Node-API initialization function +napi_value Init(napi_env env, napi_value exports) { + // ...existing code... + return exports; +} + +// ...existing code... + +NAPI_MODULE(NODE_GYP_MODULE_NAME, Init) diff --git a/package.json b/package.json index e38e185b..c97ae176 100644 --- a/package.json +++ b/package.json @@ -80,6 +80,7 @@ "is-close": "^1.3.3", "json-bigint": "^1.0.0", "nan": "^2.22.0", + "node-addon-api": "^5.0.0", "terser": "^5.39.0", "walk": "^2.3.15" }, diff --git a/src/addon.cpp b/src/addon.cpp index b29d75cb..c8171b36 100644 --- a/src/addon.cpp +++ b/src/addon.cpp @@ -12,7 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include +#include #include "macros.hpp" #include "rcl_action_bindings.hpp" @@ -23,27 +24,29 @@ #include "rcutils/macros.h" #include "shadow_node.hpp" -bool IsRunningInElectronRenderer() { - auto global = Nan::GetCurrentContext()->Global(); - auto process = - Nan::To(Nan::Get(global, Nan::New("process").ToLocalChecked()) - .ToLocalChecked()) - .ToLocalChecked(); - auto process_type = - Nan::Get(process, Nan::New("type").ToLocalChecked()).ToLocalChecked(); - return process_type->StrictEquals(Nan::New("renderer").ToLocalChecked()); +bool IsRunningInElectronRenderer(napi_env env) { + napi_value global, process, process_type; + napi_get_global(env, &global); + napi_get_named_property(env, global, "process", &process); + napi_get_named_property(env, process, "type", &process_type); + + bool is_renderer; + napi_value renderer_str; + napi_create_string_utf8(env, "renderer", NAPI_AUTO_LENGTH, &renderer_str); + napi_strict_equals(env, process_type, renderer_str, &is_renderer); + return is_renderer; } -void InitModule(v8::Local exports) { -// workaround process name mangling by chromium -// -// rcl logging uses `program_invocation_name` to determine the log file, -// chromium mangles the program name to include all args, this causes a -// ENAMETOOLONG error when starting ros. Workaround is to replace the first -// occurence of ' -' with the null terminator. see: -// https://unix.stackexchange.com/questions/432419/unexpected-non-null-encoding-of-proc-pid-cmdline +napi_value Init(napi_env env, napi_value exports) { + // workaround process name mangling by chromium + // + // rcl logging uses `program_invocation_name` to determine the log file, + // chromium mangles the program name to include all args, this causes a + // ENAMETOOLONG error when starting ros. Workaround is to replace the first + // occurence of ' -' with the null terminator. see: + // https://unix.stackexchange.com/questions/432419/unexpected-non-null-encoding-of-proc-pid-cmdline #if defined(__linux__) && defined(__GLIBC__) - if (IsRunningInElectronRenderer()) { + if (IsRunningInElectronRenderer(env)) { auto prog_name = program_invocation_name; auto end = strstr(prog_name, " -"); assert(end); @@ -51,34 +54,25 @@ void InitModule(v8::Local exports) { } #endif - v8::Local context = exports->GetIsolate()->GetCurrentContext(); + napi_value context; + napi_get_named_property(env, exports, "context", &context); for (uint32_t i = 0; i < rclnodejs::binding_methods.size(); i++) { - Nan::Set( - exports, Nan::New(rclnodejs::binding_methods[i].name).ToLocalChecked(), - Nan::New(rclnodejs::binding_methods[i].function) - ->GetFunction(context) - .ToLocalChecked()); + napi_value func; + napi_create_function(env, NULL, 0, rclnodejs::binding_methods[i].function, NULL, &func); + napi_set_named_property(env, exports, rclnodejs::binding_methods[i].name, func); } for (uint32_t i = 0; i < rclnodejs::action_binding_methods.size(); i++) { - Nan::Set( - exports, - Nan::New(rclnodejs::action_binding_methods[i].name).ToLocalChecked(), - Nan::New( - rclnodejs::action_binding_methods[i].function) - ->GetFunction(context) - .ToLocalChecked()); + napi_value func; + napi_create_function(env, NULL, 0, rclnodejs::action_binding_methods[i].function, NULL, &func); + napi_set_named_property(env, exports, rclnodejs::action_binding_methods[i].name, func); } for (uint32_t i = 0; i < rclnodejs::lifecycle_binding_methods.size(); i++) { - Nan::Set( - exports, - Nan::New(rclnodejs::lifecycle_binding_methods[i].name).ToLocalChecked(), - Nan::New( - rclnodejs::lifecycle_binding_methods[i].function) - ->GetFunction(context) - .ToLocalChecked()); + napi_value func; + napi_create_function(env, NULL, 0, rclnodejs::lifecycle_binding_methods[i].function, NULL, &func); + napi_set_named_property(env, exports, rclnodejs::lifecycle_binding_methods[i].name, func); } rclnodejs::ShadowNode::Init(exports); @@ -89,6 +83,8 @@ void InitModule(v8::Local exports) { RCUTILS_LOG_SEVERITY_DEBUG); RCUTILS_UNUSED(result); #endif + + return exports; } -NODE_MODULE(rclnodejs, InitModule); +NAPI_MODULE(NODE_GYP_MODULE_NAME, Init) diff --git a/src/rcl_action_bindings.cpp b/src/rcl_action_bindings.cpp index 4d96901c..f7bfe077 100644 --- a/src/rcl_action_bindings.cpp +++ b/src/rcl_action_bindings.cpp @@ -95,21 +95,16 @@ NAN_METHOD(ActionCreateClient) { } } -NAN_METHOD(ActionCreateServer) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +napi_value ActionCreateServer(napi_env env, napi_callback_info info) { + Napi::Env env = info.Env(); + RclHandle* node_handle = RclHandle::Unwrap(info[0].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); - RclHandle* clock_handle = RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()); + RclHandle* clock_handle = RclHandle::Unwrap(info[1].As()); rcl_clock_t* clock = reinterpret_cast(clock_handle->ptr()); - std::string action_name( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); - std::string interface_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); - std::string package_name( - *Nan::Utf8String(info[4]->ToString(currentContent).ToLocalChecked())); - int64_t result_timeout = info[10]->IntegerValue(currentContent).FromJust(); + std::string action_name = info[2].As().Utf8Value(); + std::string interface_name = info[3].As().Utf8Value(); + std::string package_name = info[4].As().Utf8Value(); + int64_t result_timeout = info[10].As().Int64Value(); const rosidl_action_type_support_t* ts = GetActionTypeSupport(package_name, interface_name); @@ -160,29 +155,24 @@ NAN_METHOD(ActionCreateServer) { THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); }); - info.GetReturnValue().Set(js_obj); + return js_obj; } else { - Nan::ThrowError(GetErrorMessageAndClear().c_str()); + Napi::Error::New(env, GetErrorMessageAndClear()).ThrowAsJavaScriptException(); + return env.Undefined(); } } -NAN_METHOD(ActionServerIsAvailable) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); - rcl_node_t* node = reinterpret_cast(node_handle->ptr()); - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()); - rcl_action_client_t* action_client = - reinterpret_cast(action_client_handle->ptr()); +Napi::Value ActionServerIsAvailable(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* action_server_handle = RclHandle::Unwrap(info[0].As()); + rcl_action_server_t* action_server = + reinterpret_cast(action_server_handle->ptr()); + rcl_action_goal_info_t* buffer = reinterpret_cast( + node::Buffer::Data(info[1].As())); - bool is_available; - THROW_ERROR_IF_NOT_EQUAL( - RCL_RET_OK, - rcl_action_server_is_available(node, action_client, &is_available), - rcl_get_error_string().str); + bool exists = rcl_action_server_goal_exists(action_server, buffer); - v8::Local result = Nan::New(is_available); - info.GetReturnValue().Set(result); + return Napi::Boolean::New(env, exists); } NAN_METHOD(ActionSendGoalRequest) { @@ -687,35 +677,31 @@ NAN_METHOD(ActionServerGoalExists) { info.GetReturnValue().Set(result); } -NAN_METHOD(ActionExpireGoals) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionExpireGoals(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* action_server_handle = RclHandle::Unwrap(info[0].As()); rcl_action_server_t* action_server = reinterpret_cast(action_server_handle->ptr()); - int64_t max_num_goals = info[1]->IntegerValue(currentContent).FromJust(); + int64_t max_num_goals = info[1].As().Int64Value(); rcl_action_goal_info_t* buffer = reinterpret_cast( - node::Buffer::Data(Nan::To(info[2]).ToLocalChecked())); + node::Buffer::Data(info[2].As())); size_t num_expired; THROW_ERROR_IF_NOT_EQUAL(rcl_action_expire_goals(action_server, buffer, max_num_goals, &num_expired), RCL_RET_OK, rcl_get_error_string().str); - v8::Local result = - Nan::New(static_cast(num_expired)); - info.GetReturnValue().Set(result); + return Napi::Number::New(env, static_cast(num_expired)); } -NAN_METHOD(ActionGetClientNamesAndTypesByNode) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionGetClientNamesAndTypesByNode(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* node_handle = RclHandle::Unwrap(info[0].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); std::string node_name = - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked()); + info[1].As().Utf8Value(); std::string node_namespace = - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked()); + info[2].As().Utf8Value(); rcl_names_and_types_t names_and_types = rcl_get_zero_initialized_names_and_types(); @@ -726,15 +712,14 @@ NAN_METHOD(ActionGetClientNamesAndTypesByNode) { node_namespace.c_str(), &names_and_types), "Failed to action client names and types."); - v8::Local result_list = - Nan::New(names_and_types.names.size); - ExtractNamesAndTypes(names_and_types, &result_list); + Napi::Array result_list = Napi::Array::New(env, names_and_types.names.size); + ExtractNamesAndTypes(env, names_and_types, result_list); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_names_and_types_fini(&names_and_types), "Failed to destroy names_and_types"); - info.GetReturnValue().Set(result_list); + return result_list; } NAN_METHOD(ActionGetServerNamesAndTypesByNode) { diff --git a/src/rcl_bindings.cpp b/src/rcl_bindings.cpp index 4514d09e..6846c901 100644 --- a/src/rcl_bindings.cpp +++ b/src/rcl_bindings.cpp @@ -59,52 +59,49 @@ namespace rclnodejs { static v8::Local wrapParameters( rcl_params_t* params); // NOLINT(whitespace/line_length) -NAN_METHOD(Init) { +napi_value Init(napi_env env, napi_value exports) { rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_init_options_init(&init_options, allocator), rcl_get_error_string().str); - // preprocess Context - RclHandle* context_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); + return exports; +} + +napi_value CreateNode(napi_env env, napi_callback_info info) { + size_t argc = 3; + napi_value args[3]; + napi_get_cb_info(env, info, &argc, args, nullptr, nullptr); + + std::string node_name = GetStringFromValue(env, args[0]); + std::string name_space = GetStringFromValue(env, args[1]); + RclHandle* context_handle = RclHandle::Unwrap(args[2]); rcl_context_t* context = reinterpret_cast(context_handle->ptr()); - // preprocess argc & argv - v8::Local jsArgv = v8::Local::Cast(info[1]); - int argc = jsArgv->Length(); - char** argv = nullptr; - if (argc > 0) { - argv = reinterpret_cast(malloc(argc * sizeof(char*))); - for (int i = 0; i < argc; i++) { - Nan::MaybeLocal jsElement = Nan::Get(jsArgv, i); - Nan::Utf8String utf8_arg(jsElement.ToLocalChecked()); - int len = utf8_arg.length() + 1; - argv[i] = reinterpret_cast(malloc(len * sizeof(char*))); - snprintf(argv[i], len, "%s", *utf8_arg); - } - } + rcl_node_t* node = reinterpret_cast(malloc(sizeof(rcl_node_t))); - THROW_ERROR_IF_NOT_EQUAL( - RCL_RET_OK, - rcl_init(argc, argc > 0 ? argv : nullptr, &init_options, context), - rcl_get_error_string().str); + *node = rcl_get_zero_initialized_node(); + rcl_node_options_t options = rcl_node_get_default_options(); - THROW_ERROR_IF_NOT_EQUAL( - RCL_RET_OK, rcl_logging_configure(&context->global_arguments, &allocator), - rcl_get_error_string().str); + THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, + rcl_node_init(node, node_name.c_str(), + name_space.c_str(), context, &options), + rcl_get_error_string().str); - for (int i = 0; i < argc; i++) { - free(argv[i]); - } - free(argv); + auto handle = RclHandle::NewInstance(env, node, nullptr, [](void* ptr) { + rcl_node_t* node = reinterpret_cast(ptr); + rcl_ret_t ret = rcl_node_fini(node); + free(ptr); + THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); + }); + return handle; } -NAN_METHOD(GetParameterOverrides) { - RclHandle* context_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetParameterOverrides(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* context_handle = RclHandle::Unwrap(info[0].As()); rcl_context_t* context = reinterpret_cast(context_handle->ptr()); @@ -115,13 +112,10 @@ NAN_METHOD(GetParameterOverrides) { rcl_get_error_string().str); if (params == NULL) { - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } - info.GetReturnValue().Set(wrapParameters(params)); - - rcl_yaml_node_struct_fini(params); + return wrapParameters(params); } static const int PARAMETER_NOT_SET = 0; @@ -249,36 +243,9 @@ static v8::Local wrapParameters(rcl_params_t* parsed_args) { return nodes; } -NAN_METHOD(CreateNode) { - std::string node_name(*Nan::Utf8String(info[0])); - std::string name_space(*Nan::Utf8String(info[1])); - RclHandle* context_handle = RclHandle::Unwrap( - Nan::To(info[2]).ToLocalChecked()); - rcl_context_t* context = - reinterpret_cast(context_handle->ptr()); - - rcl_node_t* node = reinterpret_cast(malloc(sizeof(rcl_node_t))); - - *node = rcl_get_zero_initialized_node(); - rcl_node_options_t options = rcl_node_get_default_options(); - - THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, - rcl_node_init(node, node_name.c_str(), - name_space.c_str(), context, &options), - rcl_get_error_string().str); - - auto handle = RclHandle::NewInstance(node, nullptr, [](void* ptr) { - rcl_node_t* node = reinterpret_cast(ptr); - rcl_ret_t ret = rcl_node_fini(node); - free(ptr); - THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); - }); - info.GetReturnValue().Set(handle); -} - -NAN_METHOD(CreateGuardCondition) { - RclHandle* context_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CreateGuardCondition(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* context_handle = RclHandle::Unwrap(info[0].As()); rcl_context_t* context = reinterpret_cast(context_handle->ptr()); @@ -293,36 +260,37 @@ NAN_METHOD(CreateGuardCondition) { rcl_guard_condition_init(gc, context, gc_options), rcl_get_error_string().str); - auto handle = RclHandle::NewInstance(gc, nullptr, [](void* ptr) { + auto handle = RclHandle::NewInstance(env, gc, nullptr, [](void* ptr) { rcl_guard_condition_t* gc = reinterpret_cast(ptr); rcl_ret_t ret = rcl_guard_condition_fini(gc); free(ptr); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); }); - info.GetReturnValue().Set(handle); + return handle; } -NAN_METHOD(TriggerGuardCondition) { - RclHandle* gc_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value TriggerGuardCondition(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* gc_handle = RclHandle::Unwrap(info[0].As()); rcl_guard_condition_t* gc = reinterpret_cast(gc_handle->ptr()); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_trigger_guard_condition(gc), rcl_get_error_string().str); + + return env.Undefined(); } -NAN_METHOD(CreateTimer) { - RclHandle* clock_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CreateTimer(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* clock_handle = RclHandle::Unwrap(info[0].As()); rcl_clock_t* clock = reinterpret_cast(clock_handle->ptr()); - RclHandle* context_handle = RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()); + RclHandle* context_handle = RclHandle::Unwrap(info[1].As()); rcl_context_t* context = reinterpret_cast(context_handle->ptr()); if (!info[2]->IsBigInt()) { - Nan::ThrowTypeError("Timer period must be a BigInt"); - return; + Napi::TypeError::New(env, "Timer period must be a BigInt").ThrowAsJavaScriptException(); + return env.Undefined(); } v8::Local bigInt = info[2].As(); int64_t period_nsec = bigInt->Int64Value(); @@ -343,48 +311,52 @@ NAN_METHOD(CreateTimer) { rcl_get_error_string().str); #endif - auto js_obj = RclHandle::NewInstance(timer, clock_handle, [](void* ptr) { + auto js_obj = RclHandle::NewInstance(env, timer, clock_handle, [](void* ptr) { rcl_timer_t* timer = reinterpret_cast(ptr); rcl_ret_t ret = rcl_timer_fini(timer); free(ptr); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); }); - info.GetReturnValue().Set(js_obj); + return js_obj; } -NAN_METHOD(IsTimerReady) { - RclHandle* timer_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value IsTimerReady(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* timer_handle = RclHandle::Unwrap(info[0].As()); rcl_timer_t* timer = reinterpret_cast(timer_handle->ptr()); bool is_ready = false; THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_timer_is_ready(timer, &is_ready), rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::New(is_ready)); + return Napi::Boolean::New(env, is_ready); } -NAN_METHOD(CallTimer) { - RclHandle* timer_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CallTimer(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* timer_handle = RclHandle::Unwrap(info[0].As()); rcl_timer_t* timer = reinterpret_cast(timer_handle->ptr()); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_timer_call(timer), rcl_get_error_string().str); + + return env.Undefined(); } -NAN_METHOD(CancelTimer) { - RclHandle* timer_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CancelTimer(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* timer_handle = RclHandle::Unwrap(info[0].As()); rcl_timer_t* timer = reinterpret_cast(timer_handle->ptr()); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_timer_cancel(timer), rcl_get_error_string().str); + + return env.Undefined(); } -NAN_METHOD(IsTimerCanceled) { - RclHandle* timer_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value IsTimerCanceled(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* timer_handle = RclHandle::Unwrap(info[0].As()); rcl_timer_t* timer = reinterpret_cast(timer_handle->ptr()); bool is_canceled = false; @@ -392,21 +364,23 @@ NAN_METHOD(IsTimerCanceled) { rcl_timer_is_canceled(timer, &is_canceled), rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::New(is_canceled)); + return Napi::Boolean::New(env, is_canceled); } -NAN_METHOD(ResetTimer) { - RclHandle* timer_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ResetTimer(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* timer_handle = RclHandle::Unwrap(info[0].As()); rcl_timer_t* timer = reinterpret_cast(timer_handle->ptr()); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_timer_reset(timer), rcl_get_error_string().str); + + return env.Undefined(); } -NAN_METHOD(TimerGetTimeUntilNextCall) { - RclHandle* timer_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value TimerGetTimeUntilNextCall(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* timer_handle = RclHandle::Unwrap(info[0].As()); rcl_timer_t* timer = reinterpret_cast(timer_handle->ptr()); int64_t remaining_time = 0; @@ -416,12 +390,12 @@ NAN_METHOD(TimerGetTimeUntilNextCall) { v8::Local bigInt = v8::BigInt::New(v8::Isolate::GetCurrent(), remaining_time); - info.GetReturnValue().Set(bigInt); + return bigInt; } -NAN_METHOD(TimerGetTimeSinceLastCall) { - RclHandle* timer_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value TimerGetTimeSinceLastCall(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* timer_handle = RclHandle::Unwrap(info[0].As()); rcl_timer_t* timer = reinterpret_cast(timer_handle->ptr()); int64_t elapsed_time = 0; @@ -431,17 +405,18 @@ NAN_METHOD(TimerGetTimeSinceLastCall) { v8::Local bigInt = v8::BigInt::New(v8::Isolate::GetCurrent(), elapsed_time); - info.GetReturnValue().Set(bigInt); + return bigInt; } -NAN_METHOD(CreateTimePoint) { +Napi::Value CreateTimePoint(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); if (!info[0]->IsBigInt()) { - Nan::ThrowTypeError("Timer period must be a BigInt"); - return; + Napi::TypeError::New(env, "Timer period must be a BigInt").ThrowAsJavaScriptException(); + return env.Undefined(); } v8::Local bigInt = info[0].As(); const int64_t nanoseconds = bigInt->Int64Value(); - uint32_t clock_type = Nan::To(info[1]).FromJust(); + uint32_t clock_type = info[1].As().Uint32Value(); rcl_time_point_t* time_point = reinterpret_cast(malloc(sizeof(rcl_time_point_t))); @@ -449,24 +424,25 @@ NAN_METHOD(CreateTimePoint) { time_point->clock_type = static_cast(clock_type); auto js_obj = - RclHandle::NewInstance(time_point, nullptr, [](void* ptr) { free(ptr); }); - info.GetReturnValue().Set(js_obj); + RclHandle::NewInstance(env, time_point, nullptr, [](void* ptr) { free(ptr); }); + return js_obj; } -NAN_METHOD(GetNanoseconds) { - RclHandle* time_point_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetNanoseconds(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* time_point_handle = RclHandle::Unwrap(info[0].As()); rcl_time_point_t* time_point = reinterpret_cast(time_point_handle->ptr()); v8::Local bigInt = v8::BigInt::New(v8::Isolate::GetCurrent(), time_point->nanoseconds); - info.GetReturnValue().Set(bigInt); + return bigInt; } -NAN_METHOD(CreateDuration) { +Napi::Value CreateDuration(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); if (!info[0]->IsBigInt()) { - Nan::ThrowTypeError("Timer period must be a BigInt"); - return; + Napi::TypeError::New(env, "Timer period must be a BigInt").ThrowAsJavaScriptException(); + return env.Undefined(); } v8::Local bigInt = info[0].As(); const int64_t nanoseconds = bigInt->Int64Value(); @@ -475,25 +451,25 @@ NAN_METHOD(CreateDuration) { duration->nanoseconds = nanoseconds; auto js_obj = - RclHandle::NewInstance(duration, nullptr, [](void* ptr) { free(ptr); }); - info.GetReturnValue().Set(js_obj); + RclHandle::NewInstance(env, duration, nullptr, [](void* ptr) { free(ptr); }); + return js_obj; } -NAN_METHOD(GetDurationNanoseconds) { - RclHandle* duration_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetDurationNanoseconds(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* duration_handle = RclHandle::Unwrap(info[0].As()); rcl_duration_t* duration = reinterpret_cast(duration_handle->ptr()); v8::Local bigInt = v8::BigInt::New(v8::Isolate::GetCurrent(), duration->nanoseconds); - info.GetReturnValue().Set(bigInt); + return bigInt; } -NAN_METHOD(SetRosTimeOverrideIsEnabled) { - RclHandle* clock_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value SetRosTimeOverrideIsEnabled(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* clock_handle = RclHandle::Unwrap(info[0].As()); rcl_clock_t* clock = reinterpret_cast(clock_handle->ptr()); - bool enabled = Nan::To(info[1]).FromJust(); + bool enabled = info[1].As().Value(); if (enabled) { THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_enable_ros_time_override(clock), @@ -502,39 +478,39 @@ NAN_METHOD(SetRosTimeOverrideIsEnabled) { THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_disable_ros_time_override(clock), rcl_get_error_string().str); } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(SetRosTimeOverride) { - RclHandle* clock_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value SetRosTimeOverride(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* clock_handle = RclHandle::Unwrap(info[0].As()); rcl_clock_t* clock = reinterpret_cast(clock_handle->ptr()); - RclHandle* time_point_handle = RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()); + RclHandle* time_point_handle = RclHandle::Unwrap(info[1].As()); rcl_time_point_t* time_point = reinterpret_cast(time_point_handle->ptr()); THROW_ERROR_IF_NOT_EQUAL( RCL_RET_OK, rcl_set_ros_time_override(clock, time_point->nanoseconds), rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(GetRosTimeOverrideIsEnabled) { - RclHandle* clock_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetRosTimeOverrideIsEnabled(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* clock_handle = RclHandle::Unwrap(info[0].As()); rcl_clock_t* clock = reinterpret_cast(clock_handle->ptr()); bool is_enabled; THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_is_enabled_ros_time_override(clock, &is_enabled), rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::New(is_enabled)); + return Napi::Boolean::New(env, is_enabled); } -NAN_METHOD(CreateClock) { +Napi::Value CreateClock(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); auto clock_type = - static_cast(Nan::To(info[0]).FromJust()); + static_cast(info[0].As().Int32Value()); rcl_clock_t* clock = reinterpret_cast(malloc(sizeof(rcl_clock_t))); rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -543,20 +519,19 @@ NAN_METHOD(CreateClock) { rcl_clock_init(clock_type, clock, &allocator), rcl_get_error_string().str); - info.GetReturnValue().Set( - RclHandle::NewInstance(clock, nullptr, [](void* ptr) { - rcl_clock_t* clock = reinterpret_cast(ptr); - rcl_ret_t ret = rcl_clock_fini(clock); - free(ptr); - THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); - })); + auto handle = RclHandle::NewInstance(env, clock, nullptr, [](void* ptr) { + rcl_clock_t* clock = reinterpret_cast(ptr); + rcl_ret_t ret = rcl_clock_fini(clock); + free(ptr); + THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); + }); + return handle; } -NAN_METHOD(ClockGetNow) { +Napi::Value ClockGetNow(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); rcl_clock_t* clock = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[0].As())->ptr()); rcl_time_point_t time_point; time_point.clock_type = clock->type; @@ -565,47 +540,44 @@ NAN_METHOD(ClockGetNow) { rcl_get_error_string().str); v8::Local bigInt = v8::BigInt::New(v8::Isolate::GetCurrent(), time_point.nanoseconds); - info.GetReturnValue().Set(bigInt); + return bigInt; } -NAN_METHOD(RclTake) { - RclHandle* subscription_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value RclTake(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* subscription_handle = RclHandle::Unwrap(info[0].As()); rcl_subscription_t* subscription = reinterpret_cast(subscription_handle->ptr()); void* msg_taken = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + node::Buffer::Data(info[1].As()); rcl_ret_t ret = rcl_take(subscription, msg_taken, nullptr, nullptr); if (ret != RCL_RET_OK && ret != RCL_RET_SUBSCRIPTION_TAKE_FAILED) { - Nan::ThrowError(rcl_get_error_string().str); + Napi::Error::New(env, rcl_get_error_string().str).ThrowAsJavaScriptException(); rcl_reset_error(); - info.GetReturnValue().Set(Nan::False()); - return; + return env.Undefined(); } if (ret != RCL_RET_SUBSCRIPTION_TAKE_FAILED) { - info.GetReturnValue().Set(Nan::True()); - return; + return Napi::Boolean::New(env, true); } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(CreateSubscription) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CreateSubscription(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* node_handle = RclHandle::Unwrap(info[0].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); std::string package_name( - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[1]->ToString(env).ToLocalChecked())); std::string message_sub_folder( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[2]->ToString(env).ToLocalChecked())); std::string message_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[3]->ToString(env).ToLocalChecked())); std::string topic( - *Nan::Utf8String(info[4]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[4]->ToString(env).ToLocalChecked())); v8::Local options = - info[5]->ToObject(currentContent).ToLocalChecked(); + info[5]->ToObject(env).ToLocalChecked(); rcl_subscription_t* subscription = reinterpret_cast(malloc(sizeof(rcl_subscription_t))); @@ -631,14 +603,13 @@ NAN_METHOD(CreateSubscription) { if (!Nan::Equals(contentFilterVal.ToLocalChecked(), Nan::Undefined()) .ToChecked()) { v8::Local contentFilter = contentFilterVal.ToLocalChecked() - ->ToObject(currentContent) - .ToLocalChecked(); + ->ToObject(env).ToLocalChecked(); // expression property is required std::string expression(*Nan::Utf8String( Nan::Get(contentFilter, Nan::New("expression").ToLocalChecked()) .ToLocalChecked() - ->ToString(currentContent) + ->ToString(env) .ToLocalChecked())); // parameters property (string[]) is optional @@ -654,11 +625,11 @@ NAN_METHOD(CreateSubscription) { if (argc > 0) { argv = reinterpret_cast(malloc(argc * sizeof(char*))); for (int i = 0; i < argc; i++) { - Nan::MaybeLocal jsElement = Nan::Get(jsArgv, i); - Nan::Utf8String utf8_arg(jsElement.ToLocalChecked()); + Napi::Value jsElement = jsArgv[i]; + std::string utf8_arg = jsElement.As().Utf8Value(); int len = utf8_arg.length() + 1; argv[i] = reinterpret_cast(malloc(len * sizeof(char*))); - snprintf(argv[i], len, "%s", *utf8_arg); + snprintf(argv[i], len, "%s", utf8_arg.c_str()); } } } @@ -667,7 +638,7 @@ NAN_METHOD(CreateSubscription) { expression.c_str(), argc, (const char**)argv, &subscription_ops); if (ret != RCL_RET_OK) { - Nan::ThrowError(rcl_get_error_string().str); + Napi::Error::New(env, rcl_get_error_string().str).ThrowAsJavaScriptException(); rcl_reset_error(); } @@ -693,54 +664,48 @@ NAN_METHOD(CreateSubscription) { rcl_get_error_string().str); auto js_obj = - RclHandle::NewInstance(subscription, node_handle, [node](void* ptr) { + RclHandle::NewInstance(env, subscription, node_handle, [node](void* ptr) { rcl_subscription_t* subscription = reinterpret_cast(ptr); rcl_ret_t ret = rcl_subscription_fini(subscription, node); free(ptr); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); }); - info.GetReturnValue().Set(js_obj); + return js_obj; } else { - Nan::ThrowError(GetErrorMessageAndClear().c_str()); + Napi::Error::New(env, GetErrorMessageAndClear().c_str()).ThrowAsJavaScriptException(); } + return env.Undefined(); } -NAN_METHOD(HasContentFilter) { +Napi::Value HasContentFilter(const Napi::CallbackInfo& info) { #if ROS_VERSION < 2205 // 2205 => Humble+ - info.GetReturnValue().Set(Nan::False()); - return; + return Napi::Boolean::New(info.Env(), false); #else - RclHandle* subscription_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); + Napi::Env env = info.Env(); + RclHandle* subscription_handle = RclHandle::Unwrap(info[0].As()); rcl_subscription_t* subscription = reinterpret_cast(subscription_handle->ptr()); bool is_valid = rcl_subscription_is_cft_enabled(subscription); - info.GetReturnValue().Set(Nan::New(is_valid)); + return Napi::Boolean::New(env, is_valid); #endif } -NAN_METHOD(SetContentFilter) { +Napi::Value SetContentFilter(const Napi::CallbackInfo& info) { #if ROS_VERSION < 2205 // 2205 => Humble+ - info.GetReturnValue().Set(Nan::False()); - return; + return Napi::Boolean::New(info.Env(), false); #else - v8::Local currentContext = Nan::GetCurrentContext(); - RclHandle* subscription_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); - rcl_subscription_t* subscription = - reinterpret_cast(subscription_handle->ptr()); - + Napi::Env env = info.Env(); v8::Local contentFilter = - info[1]->ToObject(currentContext).ToLocalChecked(); + info[1]->ToObject(env).ToLocalChecked(); Nan::MaybeLocal jsExpression = Nan::Get(contentFilter, Nan::New("expression").ToLocalChecked()); - Nan::Utf8String utf8_arg(jsExpression.ToLocalChecked()); - int len = utf8_arg.length() + 1; - char* expression = reinterpret_cast(malloc(len * sizeof(char*))); - snprintf(expression, len, "%s", *utf8_arg); + std::string expression(*Nan::Utf8String(jsExpression.ToLocalChecked())); + int len = expression.length() + 1; + char* expression_cstr = reinterpret_cast(malloc(len * sizeof(char*))); + snprintf(expression_cstr, len, "%s", expression.c_str()); // parameters property (string[]) is optional int argc = 0; @@ -755,11 +720,11 @@ NAN_METHOD(SetContentFilter) { if (argc > 0) { argv = reinterpret_cast(malloc(argc * sizeof(char*))); for (int i = 0; i < argc; i++) { - Nan::MaybeLocal jsElement = Nan::Get(jsArgv, i); - Nan::Utf8String utf8_arg(jsElement.ToLocalChecked()); + Napi::Value jsElement = jsArgv[i]; + std::string utf8_arg = jsElement.As().Utf8Value(); int len = utf8_arg.length() + 1; argv[i] = reinterpret_cast(malloc(len * sizeof(char*))); - snprintf(argv[i], len, "%s", *utf8_arg); + snprintf(argv[i], len, "%s", utf8_arg.c_str()); } } } @@ -771,7 +736,7 @@ NAN_METHOD(SetContentFilter) { THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_subscription_content_filter_options_set( subscription, - expression, // expression.c_str(), + expression_cstr, // expression.c_str(), argc, (const char**)argv, &options), rcl_get_error_string().str); @@ -780,7 +745,7 @@ NAN_METHOD(SetContentFilter) { rcl_get_error_string().str); if (argc) { - free(expression); + free(expression_cstr); for (int i = 0; i < argc; i++) { free(argv[i]); @@ -788,17 +753,16 @@ NAN_METHOD(SetContentFilter) { free(argv); } - info.GetReturnValue().Set(Nan::True()); + return Napi::Boolean::New(env, true); #endif } -NAN_METHOD(ClearContentFilter) { +Napi::Value ClearContentFilter(const Napi::CallbackInfo& info) { #if ROS_VERSION < 2205 // 2205 => Humble+ - info.GetReturnValue().Set(Nan::False()); - return; + return Napi::Boolean::New(info.Env(), false); #else - RclHandle* subscription_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); + Napi::Env env = info.Env(); + RclHandle* subscription_handle = RclHandle::Unwrap(info[0].As()); rcl_subscription_t* subscription = reinterpret_cast(subscription_handle->ptr()); @@ -816,24 +780,22 @@ NAN_METHOD(ClearContentFilter) { RCL_RET_OK, rcl_subscription_set_content_filter(subscription, &options), rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::True()); -#endif + return Napi::Boolean::New(env, true); } -NAN_METHOD(CreatePublisher) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value CreatePublisher(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); // Extract arguments - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); + RclHandle* node_handle = RclHandle::Unwrap(info[0].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); std::string package_name( - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[1]->ToString(env).ToLocalChecked())); std::string message_sub_folder( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[2]->ToString(env).ToLocalChecked())); std::string message_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[3]->ToString(env).ToLocalChecked())); std::string topic( - *Nan::Utf8String(info[4]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[4]->ToString(env).ToLocalChecked())); // Prepare publisher object rcl_publisher_t* publisher = @@ -860,7 +822,7 @@ NAN_METHOD(CreatePublisher) { // Wrap the handle into JS object auto js_obj = - RclHandle::NewInstance(publisher, node_handle, [node](void* ptr) { + RclHandle::NewInstance(env, publisher, node_handle, [node](void* ptr) { rcl_publisher_t* publisher = reinterpret_cast(ptr); rcl_ret_t ret = rcl_publisher_fini(publisher, node); free(ptr); @@ -868,57 +830,54 @@ NAN_METHOD(CreatePublisher) { }); // Everything is done - info.GetReturnValue().Set(js_obj); + return js_obj; } else { - Nan::ThrowError(GetErrorMessageAndClear().c_str()); + Napi::Error::New(env, GetErrorMessageAndClear().c_str()).ThrowAsJavaScriptException(); } + return env.Undefined(); } -NAN_METHOD(Publish) { +Napi::Value Publish(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); rcl_publisher_t* publisher = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[0].As())->ptr()); void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + node::Buffer::Data(info[1].As()); THROW_ERROR_IF_NOT_EQUAL(rcl_publish(publisher, buffer, nullptr), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(GetPublisherTopic) { +Napi::Value GetPublisherTopic(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); rcl_publisher_t* publisher = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[0].As())->ptr()); const char* topic = rcl_publisher_get_topic_name(publisher); - info.GetReturnValue().Set(Nan::New(topic).ToLocalChecked()); + return Napi::String::New(env, topic); } -NAN_METHOD(GetSubscriptionTopic) { +Napi::Value GetSubscriptionTopic(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); rcl_subscription_t* subscription = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[0].As())->ptr()); const char* topic = rcl_subscription_get_topic_name(subscription); - info.GetReturnValue().Set(Nan::New(topic).ToLocalChecked()); + return Napi::String::New(env, topic); } -NAN_METHOD(CreateClient) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CreateClient(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* node_handle = RclHandle::Unwrap(info[0].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); std::string service_name( - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[1]->ToString(env).ToLocalChecked())); std::string interface_name( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[2]->ToString(env).ToLocalChecked())); std::string package_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[3]->ToString(env).ToLocalChecked())); const rosidl_service_type_support_t* ts = GetServiceTypeSupport(package_name, interface_name); @@ -939,67 +898,64 @@ NAN_METHOD(CreateClient) { RCL_RET_OK, rcl_get_error_string().str); auto js_obj = - RclHandle::NewInstance(client, node_handle, [node](void* ptr) { + RclHandle::NewInstance(env, client, node_handle, [node](void* ptr) { rcl_client_t* client = reinterpret_cast(ptr); rcl_ret_t ret = rcl_client_fini(client, node); free(ptr); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); }); - info.GetReturnValue().Set(js_obj); + return js_obj; } else { - Nan::ThrowError(GetErrorMessageAndClear().c_str()); + Napi::Error::New(env, GetErrorMessageAndClear().c_str()).ThrowAsJavaScriptException(); } + return env.Undefined(); } -NAN_METHOD(SendRequest) { +Napi::Value SendRequest(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); rcl_client_t* client = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[0].As())->ptr()); void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + node::Buffer::Data(info[1].As()); int64_t sequence_number; THROW_ERROR_IF_NOT_EQUAL(rcl_send_request(client, buffer, &sequence_number), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::New(static_cast(sequence_number))); + return Napi::Number::New(env, static_cast(sequence_number)); } -NAN_METHOD(RclTakeResponse) { +Napi::Value RclTakeResponse(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); rcl_client_t* client = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[0].As())->ptr()); rmw_service_info_t header; void* taken_response = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + node::Buffer::Data(info[1].As()); rcl_ret_t ret = rcl_take_response_with_info(client, &header, taken_response); int64_t sequence_number = header.request_id.sequence_number; if (ret == RCL_RET_OK) { - info.GetReturnValue().Set(Nan::New(static_cast(sequence_number))); - return; + return Napi::Number::New(env, static_cast(sequence_number)); } rcl_reset_error(); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(CreateService) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CreateService(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* node_handle = RclHandle::Unwrap(info[0].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); std::string service_name( - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[1]->ToString(env).ToLocalChecked())); std::string interface_name( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[2]->ToString(env).ToLocalChecked())); std::string package_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[3]->ToString(env).ToLocalChecked())); const rosidl_service_type_support_t* ts = GetServiceTypeSupport(package_name, interface_name); @@ -1019,74 +975,69 @@ NAN_METHOD(CreateService) { rcl_service_init(service, node, ts, service_name.c_str(), &service_ops), RCL_RET_OK, rcl_get_error_string().str); auto js_obj = - RclHandle::NewInstance(service, node_handle, [node](void* ptr) { + RclHandle::NewInstance(env, service, node_handle, [node](void* ptr) { rcl_service_t* service = reinterpret_cast(ptr); rcl_ret_t ret = rcl_service_fini(service, node); free(ptr); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); }); - info.GetReturnValue().Set(js_obj); + return js_obj; } else { - Nan::ThrowError(GetErrorMessageAndClear().c_str()); + Napi::Error::New(env, GetErrorMessageAndClear().c_str()).ThrowAsJavaScriptException(); } + return env.Undefined(); } -NAN_METHOD(RclTakeRequest) { +Napi::Value RclTakeRequest(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); rcl_service_t* service = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[0].As())->ptr()); rmw_request_id_t* header = reinterpret_cast(malloc(sizeof(rmw_request_id_t))); void* taken_request = - node::Buffer::Data(Nan::To(info[2]).ToLocalChecked()); + node::Buffer::Data(info[2].As()); rcl_ret_t ret = rcl_take_request(service, header, taken_request); if (ret != RCL_RET_SERVICE_TAKE_FAILED) { auto js_obj = - RclHandle::NewInstance(header, nullptr, [](void* ptr) { free(ptr); }); - info.GetReturnValue().Set(js_obj); - return; + RclHandle::NewInstance(env, header, nullptr, [](void* ptr) { free(ptr); }); + return js_obj; } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(SendResponse) { +Napi::Value SendResponse(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); rcl_service_t* service = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[0].As())->ptr()); void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + node::Buffer::Data(info[1].As()); rmw_request_id_t* header = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[2]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[2].As())->ptr()); THROW_ERROR_IF_NOT_EQUAL(rcl_send_response(service, header, buffer), RCL_RET_OK, rcl_get_error_string().str); + + return env.Undefined(); } #if ROS_VERSION > 2205 // 2205 == Humble -NAN_METHOD(ConfigureServiceIntrospection) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value ConfigureServiceIntrospection(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()); + RclHandle* node_handle = RclHandle::Unwrap(info[1].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); rcl_clock_t* clock = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[2]).ToLocalChecked()) - ->ptr()); + RclHandle::Unwrap(info[2].As())->ptr()); std::string interface_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[3]->ToString(env).ToLocalChecked())); std::string package_name( - *Nan::Utf8String(info[4]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[4]->ToString(env).ToLocalChecked())); const rosidl_service_type_support_t* ts = GetServiceTypeSupport(package_name, interface_name); @@ -1099,13 +1050,12 @@ NAN_METHOD(ConfigureServiceIntrospection) { rcl_service_introspection_state_t state = static_cast( - Nan::To(info[6]).ToChecked()); + info[6].As().Int32Value()); - bool configureForService = Nan::To(info[7]).FromJust(); + bool configureForService = info[7].As().Value(); if (configureForService) { - RclHandle* service_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); + RclHandle* service_handle = RclHandle::Unwrap(info[0].As()); rcl_service_t* service = reinterpret_cast(service_handle->ptr()); @@ -1115,8 +1065,7 @@ NAN_METHOD(ConfigureServiceIntrospection) { RCL_RET_OK, rcl_get_error_string().str); } else { - RclHandle* client_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); + RclHandle* client_handle = RclHandle::Unwrap(info[0].As()); rcl_client_t* client = reinterpret_cast(client_handle->ptr()); @@ -1127,159 +1076,156 @@ NAN_METHOD(ConfigureServiceIntrospection) { } } else { - Nan::ThrowError(GetErrorMessageAndClear().c_str()); + Napi::Error::New(env, GetErrorMessageAndClear().c_str()).ThrowAsJavaScriptException(); } + return env.Undefined(); } #endif -NAN_METHOD(ValidateFullTopicName) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value ValidateFullTopicName(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); int validation_result; size_t invalid_index; std::string topic_name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); rmw_ret_t ret = rmw_validate_full_topic_name( topic_name.c_str(), &validation_result, &invalid_index); if (ret != RMW_RET_OK) { if (ret == RMW_RET_BAD_ALLOC) { - Nan::ThrowError(rmw_get_error_string().str); + Napi::Error::New(env, rmw_get_error_string().str).ThrowAsJavaScriptException(); } rmw_reset_error(); - return info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } if (validation_result == RMW_NAMESPACE_VALID) { - info.GetReturnValue().Set(Nan::Null()); - return; + return env.Null(); } const char* validation_message = rmw_full_topic_name_validation_result_string(validation_result); THROW_ERROR_IF_EQUAL(nullptr, validation_message, "Unable to get validation error message"); - v8::Local result_list = Nan::New(2); + v8::Local result_list = v8::Array::New(v8::Isolate::GetCurrent(), 2); Nan::Set( result_list, 0, Nan::New(std::string(validation_message)).ToLocalChecked()); Nan::Set(result_list, 1, Nan::New(static_cast(invalid_index))); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(ValidateNodeName) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value ValidateNodeName(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); int validation_result; size_t invalid_index; std::string node_name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); rmw_ret_t ret = rmw_validate_node_name(node_name.c_str(), &validation_result, &invalid_index); if (ret != RMW_RET_OK) { if (ret == RMW_RET_BAD_ALLOC) { - Nan::ThrowError(rmw_get_error_string().str); + Napi::Error::New(env, rmw_get_error_string().str).ThrowAsJavaScriptException(); } rmw_reset_error(); - return info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } if (validation_result == RMW_NODE_NAME_VALID) { - info.GetReturnValue().Set(Nan::Null()); - return; + return env.Null(); } const char* validation_message = rmw_node_name_validation_result_string(validation_result); THROW_ERROR_IF_EQUAL(nullptr, validation_message, "Unable to get validation error message"); - v8::Local result_list = Nan::New(2); + v8::Local result_list = v8::Array::New(v8::Isolate::GetCurrent(), 2); Nan::Set( result_list, 0, Nan::New(std::string(validation_message)).ToLocalChecked()); Nan::Set(result_list, 1, Nan::New(static_cast(invalid_index))); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(ValidateTopicName) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value ValidateTopicName(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); int validation_result; size_t invalid_index; std::string topic_name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); rmw_ret_t ret = rcl_validate_topic_name(topic_name.c_str(), &validation_result, &invalid_index); if (ret != RMW_RET_OK) { if (ret == RMW_RET_BAD_ALLOC) { - Nan::ThrowError(rmw_get_error_string().str); + Napi::Error::New(env, rmw_get_error_string().str).ThrowAsJavaScriptException(); } rmw_reset_error(); - return info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } if (validation_result == RMW_NODE_NAME_VALID) { - info.GetReturnValue().Set(Nan::Null()); - return; + return env.Null(); } const char* validation_message = rcl_topic_name_validation_result_string(validation_result); THROW_ERROR_IF_EQUAL(nullptr, validation_message, "Unable to get validation error message"); - v8::Local result_list = Nan::New(2); + v8::Local result_list = v8::Array::New(v8::Isolate::GetCurrent(), 2); Nan::Set( result_list, 0, Nan::New(std::string(validation_message)).ToLocalChecked()); Nan::Set(result_list, 1, Nan::New(static_cast(invalid_index))); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(ValidateNamespace) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value ValidateNamespace(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); int validation_result; size_t invalid_index; std::string namespace_name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); rmw_ret_t ret = rmw_validate_namespace(namespace_name.c_str(), &validation_result, &invalid_index); if (ret != RMW_RET_OK) { if (ret == RMW_RET_BAD_ALLOC) { - Nan::ThrowError(rmw_get_error_string().str); + Napi::Error::New(env, rmw_get_error_string().str).ThrowAsJavaScriptException(); } rmw_reset_error(); - return info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } if (validation_result == RMW_NODE_NAME_VALID) { - info.GetReturnValue().Set(Nan::Null()); - return; + return env.Null(); } const char* validation_message = rmw_namespace_validation_result_string(validation_result); THROW_ERROR_IF_EQUAL(nullptr, validation_message, "Unable to get validation error message"); - v8::Local result_list = Nan::New(2); + v8::Local result_list = v8::Array::New(v8::Isolate::GetCurrent(), 2); Nan::Set( result_list, 0, Nan::New(std::string(validation_message)).ToLocalChecked()); Nan::Set(result_list, 1, Nan::New(static_cast(invalid_index))); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(ExpandTopicName) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value ExpandTopicName(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); std::string topic_name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); std::string node_name( - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[1]->ToString(env).ToLocalChecked())); std::string node_namespace( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[2]->ToString(env).ToLocalChecked())); char* expanded_topic = nullptr; rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -1291,26 +1237,24 @@ NAN_METHOD(ExpandTopicName) { rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator); if (rcutils_ret != RCUTILS_RET_OK) { if (rcutils_ret == RCUTILS_RET_BAD_ALLOC) { - Nan::ThrowError(rcutils_get_error_string().str); + Napi::Error::New(env, rcutils_get_error_string().str).ThrowAsJavaScriptException(); } rcutils_reset_error(); - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } rcl_ret_t ret = rcl_get_default_topic_name_substitutions(&substitutions_map); if (ret != RCL_RET_OK) { if (ret == RCL_RET_BAD_ALLOC) { - Nan::ThrowError(rcl_get_error_string().str); + Napi::Error::New(env, rcl_get_error_string().str).ThrowAsJavaScriptException(); } rcl_reset_error(); rcutils_ret = rcutils_string_map_fini(&substitutions_map); if (rcutils_ret != RCUTILS_RET_OK) { - Nan::ThrowError(rcutils_get_error_string().str); + Napi::Error::New(env, rcutils_get_error_string().str).ThrowAsJavaScriptException(); rcutils_reset_error(); } - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } ret = rcl_expand_topic_name(topic_name.c_str(), node_name.c_str(), @@ -1319,52 +1263,48 @@ NAN_METHOD(ExpandTopicName) { rcutils_ret = rcutils_string_map_fini(&substitutions_map); if (rcutils_ret != RCUTILS_RET_OK) { - Nan::ThrowError(rcutils_get_error_string().str); + Napi::Error::New(env, rcutils_get_error_string().str).ThrowAsJavaScriptException(); rcutils_reset_error(); allocator.deallocate(expanded_topic, allocator.state); - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } if (ret != RCL_RET_OK) { - Nan::ThrowError(rcl_get_error_string().str); + Napi::Error::New(env, rcl_get_error_string().str).ThrowAsJavaScriptException(); rcl_reset_error(); - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } if (!expanded_topic) { - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } rcl_allocator_t topic_allocator = rcl_get_default_allocator(); std::string topic(expanded_topic); allocator.deallocate(expanded_topic, topic_allocator.state); - info.GetReturnValue().Set(Nan::New(topic).ToLocalChecked()); + return Napi::String::New(env, topic); } -NAN_METHOD(GetNodeName) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetNodeName(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* node_handle = RclHandle::Unwrap(info[0].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); const char* node_name = rcl_node_get_name(node); if (!node_name) { - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } else { - info.GetReturnValue().Set(Nan::New(node_name).ToLocalChecked()); + return Napi::String::New(env, node_name); } } -NAN_METHOD(GetNamespace) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetNamespace(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* node_handle = RclHandle::Unwrap(info[0].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); const char* node_namespace = rcl_node_get_namespace(node); if (!node_namespace) { - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } else { - info.GetReturnValue().Set( - Nan::New(node_namespace).ToLocalChecked()); + return Napi::String::New(env, node_namespace); } } @@ -1421,13 +1361,12 @@ std::unique_ptr GetQosProfileFromObject( } std::unique_ptr GetQoSProfile(v8::Local qos) { - v8::Local currentContent = Nan::GetCurrentContext(); std::unique_ptr qos_profile = std::make_unique(); if (qos->IsString()) { *qos_profile = *GetQoSProfileFromString(std::string( - *Nan::Utf8String(qos->ToString(currentContent).ToLocalChecked()))); + *Nan::Utf8String(qos->ToString().ToLocalChecked()))); } else if (qos->IsObject()) { qos_profile = GetQosProfileFromObject(Nan::To(qos).ToLocalChecked()); @@ -1442,7 +1381,7 @@ int DestroyContext(rcl_context_t* context) { if (context->impl) { if (rcl_context_is_valid(context)) { if (RCL_RET_OK != rcl_shutdown(context)) { - Nan::ThrowError(rcl_get_error_string().str); + Napi::Error::New(v8::Isolate::GetCurrent(), rcl_get_error_string().str).ThrowAsJavaScriptException(); } ret = rcl_context_fini(context); } @@ -1450,9 +1389,9 @@ int DestroyContext(rcl_context_t* context) { return ret; } -NAN_METHOD(Shutdown) { - RclHandle* context_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value Shutdown(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* context_handle = RclHandle::Unwrap(info[0].As()); rcl_context_t* context = reinterpret_cast(context_handle->ptr()); THROW_ERROR_IF_NOT_EQUAL(rcl_shutdown(context), RCL_RET_OK, @@ -1460,12 +1399,13 @@ NAN_METHOD(Shutdown) { THROW_ERROR_IF_NOT_EQUAL(rcl_logging_fini(), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(InitString) { +Napi::Value InitString(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); void* buffer = - node::Buffer::Data(Nan::To(info[0]).ToLocalChecked()); + node::Buffer::Data(info[0].As()); #if ROS_VERSION >= 2006 rosidl_runtime_c__String* ptr = reinterpret_cast(buffer); @@ -1477,35 +1417,35 @@ NAN_METHOD(InitString) { rosidl_generator_c__String__init(ptr); #endif - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } inline char* GetBufAddr(v8::Local buf) { return node::Buffer::Data(buf.As()); } -NAN_METHOD(FreeMemeoryAtOffset) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value FreeMemeoryAtOffset(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); std::string addr_str( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); int64_t result = std::stoull(addr_str, 0, 16); char* addr = reinterpret_cast(result); int64_t offset = - info[1]->IsNumber() ? Nan::To(info[1]).FromJust() : 0; + info[1]->IsNumber() ? info[1].As().Int64Value() : 0; auto ptr = addr + offset; char* val = *reinterpret_cast(ptr); free(val); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(CreateArrayBufferFromAddress) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value CreateArrayBufferFromAddress(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); std::string addr_str( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); int64_t result = std::stoull(addr_str, 0, 16); char* addr = reinterpret_cast(result); - int32_t length = Nan::To(info[1]).FromJust(); + int32_t length = info[1].As().Int32Value(); static_assert(NODE_MAJOR_VERSION > 12, "nodejs version must > 12"); #if (NODE_RUNTIME_ELECTRON && NODE_MODULE_VERSION >= 109) @@ -1527,74 +1467,72 @@ NAN_METHOD(CreateArrayBufferFromAddress) { v8::ArrayBuffer::New(v8::Isolate::GetCurrent(), std::move(backing)); #endif - info.GetReturnValue().Set(array_buffer); + return array_buffer; } -NAN_METHOD(CreateArrayBufferCleaner) { +Napi::Value CreateArrayBufferCleaner(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); auto address = GetBufAddr(info[0]); - int32_t offset = Nan::To(info[1]).FromJust(); + int32_t offset = info[1].As().Int32Value(); char* target = *reinterpret_cast(address + offset); - info.GetReturnValue().Set( - RclHandle::NewInstance(target, nullptr, [](void* ptr) { free(ptr); })); + return + RclHandle::NewInstance(env, target, nullptr, [](void* ptr) { free(ptr); }); } -NAN_METHOD(setLoggerLevel) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value setLoggerLevel(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); std::string name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); - int level = Nan::To(info[1]).FromJust(); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); + int level = info[1].As().Int32Value(); rcutils_ret_t ret = rcutils_logging_set_logger_level(name.c_str(), level); if (ret != RCUTILS_RET_OK) { - Nan::ThrowError(rcutils_get_error_string().str); + Napi::Error::New(env, rcutils_get_error_string().str).ThrowAsJavaScriptException(); rcutils_reset_error(); } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(GetLoggerEffectiveLevel) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value GetLoggerEffectiveLevel(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); std::string name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); int logger_level = rcutils_logging_get_logger_effective_level(name.c_str()); if (logger_level < 0) { - Nan::ThrowError(rcutils_get_error_string().str); + Napi::Error::New(env, rcutils_get_error_string().str).ThrowAsJavaScriptException(); rcutils_reset_error(); - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } - info.GetReturnValue().Set(Nan::New(logger_level)); + return Napi::Number::New(env, logger_level); } -NAN_METHOD(GetNodeLoggerName) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetNodeLoggerName(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + RclHandle* node_handle = RclHandle::Unwrap(info[0].As()); rcl_node_t* node = reinterpret_cast(node_handle->ptr()); const char* node_logger_name = rcl_node_get_logger_name(node); if (!node_logger_name) { - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } - info.GetReturnValue().Set( - Nan::New(node_logger_name).ToLocalChecked()); + return Napi::String::New(env, node_logger_name); } -NAN_METHOD(Log) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value Log(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); std::string name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); - int severity = Nan::To(info[1]).FromJust(); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); + int severity = info[1].As().Int32Value(); std::string message( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[2]->ToString(env).ToLocalChecked())); std::string function_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); - size_t line_number = Nan::To(info[4]).FromJust(); + *Nan::Utf8String(info[3]->ToString(env).ToLocalChecked())); + size_t line_number = info[4].As().Int64Value(); std::string file_name( - *Nan::Utf8String(info[5]->ToString(currentContent).ToLocalChecked())); + *Nan::Utf8String(info[5]->ToString(env).ToLocalChecked())); bool enabled = rcutils_logging_logger_is_enabled_for(name.c_str(), severity); if (enabled) { @@ -1604,29 +1542,34 @@ NAN_METHOD(Log) { message.c_str()); } - info.GetReturnValue().Set(Nan::New(enabled)); + return Napi::Boolean::New(env, enabled); } -NAN_METHOD(IsEnableFor) { - v8::Local currentContent = Nan::GetCurrentContext(); +Napi::Value IsEnableFor(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); std::string name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); - int severity = Nan::To(info[1]).FromJust(); + *Nan::Utf8String(info[0]->ToString(env).ToLocalChecked())); + int severity = info[1].As().Int32Value(); bool enabled = rcutils_logging_logger_is_enabled_for(name.c_str(), severity); - info.GetReturnValue().Set(Nan::New(enabled)); + return Napi::Boolean::New(env, enabled); } -NAN_METHOD(CreateContext) { +Napi::Value CreateContext(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); rcl_context_t* context = reinterpret_cast(malloc(sizeof(rcl_context_t))); *context = rcl_get_zero_initialized_context(); - auto js_obj = RclHandle::NewInstance(context, nullptr, [](void* ptr) { + auto js_obj = RclHandle::NewInstance(env, context, nullptr, [](void* ptr) { rcl_context_t* context = reinterpret_cast(ptr); rcl_ret_t ret = DestroyContext(context); free(ptr); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); }); + return js_obj; +} + +Napi::Value IsContextValid(const Napi::CallbackInfo& info) { info.GetReturnValue().Set(js_obj); } diff --git a/src/rcl_bindings.hpp b/src/rcl_bindings.hpp index 8c8476f0..deaa8e92 100644 --- a/src/rcl_bindings.hpp +++ b/src/rcl_bindings.hpp @@ -15,7 +15,7 @@ #ifndef SRC_RCL_BINDINGS_HPP_ #define SRC_RCL_BINDINGS_HPP_ -#include +#include #include #include @@ -25,7 +25,7 @@ namespace rclnodejs { -typedef void (*JsCFuntcion)(const Nan::FunctionCallbackInfo&); +typedef void (*JsCFuntcion)(const Napi::CallbackInfo& info); typedef struct { const char* name; diff --git a/src/rcl_handle.cpp b/src/rcl_handle.cpp index 6f6c0ae8..9bd75234 100644 --- a/src/rcl_handle.cpp +++ b/src/rcl_handle.cpp @@ -12,14 +12,44 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rcl_handle.hpp" +#include #include #include namespace rclnodejs { -Nan::Persistent RclHandle::constructor; +class RclHandle : public Napi::ObjectWrap { + public: + static void Init(Napi::Env env, Napi::Object exports); + void New(const Napi::CallbackInfo& info); + void SyncProperties(const Napi::CallbackInfo& info); + Napi::Value PropertiesGetter(const Napi::CallbackInfo& info); + void Release(const Napi::CallbackInfo& info); + void Dismiss(const Napi::CallbackInfo& info); + static Napi::Object NewInstance(Napi::Env env, Napi::Value arg); + + private: + explicit RclHandle(); + ~RclHandle(); + + void Reset(); + void* ptr() const { return pointer_; } + void set_ptr(void* ptr) { pointer_ = ptr; } + void set_deleter(std::function deleter) { deleter_ = deleter; } + void set_parent(RclHandle* parent) { parent_ = parent; } + void AddChild(RclHandle* child) { children_.insert(child); } + void RemoveChild(RclHandle* child) { children_.erase(child); } + + void* pointer_; + RclHandle* parent_; + std::function deleter_; + std::set children_; + Napi::ObjectReference properties_obj_; + std::map properties_; +}; + +Napi::FunctionReference RclHandle::constructor; RclHandle::RclHandle() : pointer_(nullptr), parent_(nullptr) {} @@ -27,24 +57,19 @@ RclHandle::~RclHandle() { if (pointer_) Reset(); } -void RclHandle::Init(v8::Local exports) { - v8::Local tpl = Nan::New(New); - tpl->SetClassName(Nan::New("RclHandle").ToLocalChecked()); - tpl->InstanceTemplate()->SetInternalFieldCount(1); +void RclHandle::Init(Napi::Env env, Napi::Object exports) { + Napi::Function func = DefineClass(env, "RclHandle", { + InstanceAccessor("properties", &RclHandle::PropertiesGetter, nullptr), + InstanceMethod("release", &RclHandle::Release), + InstanceMethod("dismiss", &RclHandle::Dismiss) + }); - Nan::SetAccessor(tpl->InstanceTemplate(), - Nan::New("properties").ToLocalChecked(), PropertiesGetter); - Nan::SetPrototypeMethod(tpl, "release", Release); - Nan::SetPrototypeMethod(tpl, "dismiss", Dismiss); - - v8::Local context = exports->GetIsolate()->GetCurrentContext(); - - constructor.Reset(tpl->GetFunction(context).ToLocalChecked()); - Nan::Set(exports, Nan::New("RclHandle").ToLocalChecked(), - tpl->GetFunction(context).ToLocalChecked()); + constructor = Napi::Persistent(func); + constructor.SuppressDestruct(); + exports.Set("RclHandle", func); } -void RclHandle::New(const Nan::FunctionCallbackInfo& info) { +void RclHandle::New(const Napi::CallbackInfo& info) { if (info.IsConstructCall()) { RclHandle* obj = new RclHandle(); obj->Wrap(info.This()); @@ -52,57 +77,48 @@ void RclHandle::New(const Nan::FunctionCallbackInfo& info) { } } -void RclHandle::SyncProperties() { - auto obj = v8::Object::New(v8::Isolate::GetCurrent()); +void RclHandle::SyncProperties(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + Napi::Object obj = Napi::Object::New(env); for (auto it = properties_.begin(); it != properties_.end(); it++) { - Nan::Set(obj, Nan::New(it->first).ToLocalChecked(), Nan::New(it->second)); + obj.Set(it->first, it->second); } - properties_obj_ = obj; + properties_obj_ = Napi::Persistent(obj); } -NAN_GETTER(RclHandle::PropertiesGetter) { - auto* me = RclHandle::Unwrap(info.Holder()); +Napi::Value RclHandle::PropertiesGetter(const Napi::CallbackInfo& info) { + RclHandle* me = RclHandle::Unwrap(info.Holder()); if (!me->properties_obj_.IsEmpty()) - info.GetReturnValue().Set(me->properties_obj_); + return me->properties_obj_.Value(); else - info.GetReturnValue().Set(Nan::Undefined()); + return info.Env().Undefined(); } -NAN_METHOD(RclHandle::Release) { - auto* me = Nan::ObjectWrap::Unwrap(info.Holder()); +Napi::Value RclHandle::Release(const Napi::CallbackInfo& info) { + RclHandle* me = RclHandle::Unwrap(info.Holder()); if (me->ptr()) me->Reset(); - info.GetReturnValue().Set(Nan::Undefined()); + return info.Env().Undefined(); } -NAN_METHOD(RclHandle::Dismiss) { - auto* me = Nan::ObjectWrap::Unwrap(info.Holder()); +Napi::Value RclHandle::Dismiss(const Napi::CallbackInfo& info) { + RclHandle* me = RclHandle::Unwrap(info.Holder()); if (me) me->set_ptr(nullptr); - info.GetReturnValue().Set(Nan::Undefined()); + return info.Env().Undefined(); } -v8::Local RclHandle::NewInstance( - void* handle, RclHandle* parent, std::function deleter) { - Nan::EscapableHandleScope scope; +Napi::Object RclHandle::NewInstance(Napi::Env env, Napi::Value arg) { + Napi::EscapableHandleScope scope(env); - v8::Local cons = Nan::New(constructor); - v8::Local context = - v8::Isolate::GetCurrent()->GetCurrentContext(); + Napi::Object instance = constructor.New({}); - v8::Local instance = - cons->NewInstance(context, 0, nullptr).ToLocalChecked(); - - auto* rcl_handle = Nan::ObjectWrap::Unwrap(instance); - rcl_handle->set_ptr(handle); - rcl_handle->set_deleter(deleter); - if (parent) { - rcl_handle->set_parent(parent); - parent->AddChild(rcl_handle); - } + RclHandle* rcl_handle = Napi::ObjectWrap::Unwrap(instance); + rcl_handle->set_ptr(arg.As>().Data()); + rcl_handle->set_deleter([](void* ptr) { /* custom deleter logic */ }); return scope.Escape(instance); } diff --git a/src/shadow_node.hpp b/src/shadow_node.hpp index e1b7f456..49f81bc7 100644 --- a/src/shadow_node.hpp +++ b/src/shadow_node.hpp @@ -15,7 +15,7 @@ #ifndef SRC_SHADOW_NODE_HPP_ #define SRC_SHADOW_NODE_HPP_ -#include +#include #include #include @@ -28,9 +28,9 @@ namespace rclnodejs { class HandleManager; class Executor; -class ShadowNode : public Nan::ObjectWrap, public Executor::Delegate { +class ShadowNode : public Napi::ObjectWrap, public Executor::Delegate { public: - static void Init(v8::Local exports); + static void Init(Napi::Env env, Napi::Object exports); void StartRunning(rcl_context_t* context, int32_t timeout); void StopRunning(); void RunOnce(rcl_context_t* context, int32_t timeout); @@ -45,17 +45,18 @@ class ShadowNode : public Nan::ObjectWrap, public Executor::Delegate { ShadowNode(); ~ShadowNode(); - static void New(const Nan::FunctionCallbackInfo& info); - static Nan::Persistent constructor; - static NAN_METHOD(Stop); - static NAN_METHOD(Start); - static NAN_METHOD(SyncHandles); - static NAN_METHOD(SpinOnce); - static NAN_GETTER(HandleGetter); - static NAN_SETTER(HandleSetter); + static void New(const Napi::CallbackInfo& info); + static Napi::FunctionReference constructor; + static Napi::Value Stop(const Napi::CallbackInfo& info); + static Napi::Value Start(const Napi::CallbackInfo& info); + static Napi::Value SyncHandles(const Napi::CallbackInfo& info); + static Napi::Value SpinOnce(const Napi::CallbackInfo& info); + static Napi::Value HandleGetter(const Napi::CallbackInfo& info); + static void HandleSetter(const Napi::CallbackInfo& info, const Napi::Value& value); std::unique_ptr handle_manager_; std::unique_ptr executor_; + Napi::FunctionReference callback_; }; } // namespace rclnodejs