diff --git a/binding.gyp b/binding.gyp index dbc64670..31ad4e37 100644 --- a/binding.gyp +++ b/binding.gyp @@ -30,8 +30,8 @@ ], 'include_dirs': [ '.', - "= 4) { + this._info.functionName = '(anonymous)'; + this._info.fileName = path.basename(altMatch[1]); + this._info.lineNumber = altMatch[2]; + } } } @@ -156,7 +173,7 @@ class Logging { severity, message, caller.functionName, - caller.lineNumber, + parseInt(caller.lineNumber, 10), caller.fileName ); } diff --git a/package.json b/package.json index 6d4a0eaa..9067252d 100644 --- a/package.json +++ b/package.json @@ -26,7 +26,7 @@ "docs": "cd docs && make", "test": "nyc node --expose-gc ./scripts/run_test.js && tsd", "lint": "eslint && node ./scripts/cpplint.js", - "format": "clang-format -i -style=file ./src/*.cpp ./src/*.hpp && npx --yes prettier --write \"{lib,rosidl_gen,rostsd_gen,rosidl_parser,types,example,test,scripts,benchmark,rostsd_gen}/**/*.{js,md,ts}\" ./*.{js,md,ts}", + "format": "clang-format -i -style=file ./src/*.cpp ./src/*.h && npx --yes prettier --write \"{lib,rosidl_gen,rostsd_gen,rosidl_parser,types,example,test,scripts,benchmark,rostsd_gen}/**/*.{js,md,ts}\" ./*.{js,md,ts}", "prepare": "husky", "coverage": "cat ./coverage/lcov.info | ./node_modules/coveralls/bin/coveralls.js" }, @@ -79,9 +79,9 @@ "fs-extra": "^11.2.0", "is-close": "^1.3.3", "json-bigint": "^1.0.0", - "nan": "^2.22.0", "terser": "^5.39.0", - "walk": "^2.3.15" + "walk": "^2.3.15", + "node-addon-api": "^8.3.1" }, "husky": { "hooks": { diff --git a/src/addon.cpp b/src/addon.cpp index b29d75cb..2478c439 100644 --- a/src/addon.cpp +++ b/src/addon.cpp @@ -12,29 +12,25 @@ // 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" -#include "rcl_bindings.hpp" -#include "rcl_handle.hpp" -#include "rcl_lifecycle_bindings.hpp" -#include "rcutils/logging.h" -#include "rcutils/macros.h" -#include "shadow_node.hpp" +#include "macros.h" +#include "rcl_action_bindings.h" +#include "rcl_bindings.h" +#include "rcl_handle.h" +#include "rcl_lifecycle_bindings.h" +#include "rcl_utilities.h" +#include "shadow_node.h" -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(const Napi::Env& env) { + Napi::Object global = env.Global(); + Napi::Object process = global.Get("process").As(); + Napi::Value processType = process.Get("type"); + return processType.StrictEquals(Napi::String::New(env, "renderer")); } -void InitModule(v8::Local exports) { +Napi::Object InitModule(Napi::Env env, Napi::Object exports) { // workaround process name mangling by chromium // // rcl logging uses `program_invocation_name` to determine the log file, @@ -43,7 +39,7 @@ void InitModule(v8::Local exports) { // 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,44 +47,21 @@ void InitModule(v8::Local exports) { } #endif - v8::Local context = exports->GetIsolate()->GetCurrentContext(); - - 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()); - } - - 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()); - } - - 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()); - } - - rclnodejs::ShadowNode::Init(exports); - rclnodejs::RclHandle::Init(exports); + // Init the C++ bindings. + rclnodejs::StoreEnv(env); + rclnodejs::InitBindings(env, exports); + rclnodejs::InitAction(env, exports); + rclnodejs::InitLifecycle(env, exports); + rclnodejs::ShadowNode::Init(env, exports); + rclnodejs::RclHandle::Init(env, exports); #ifdef DEBUG_ON int result = rcutils_logging_set_logger_level(PACKAGE_NAME, RCUTILS_LOG_SEVERITY_DEBUG); RCUTILS_UNUSED(result); #endif + + return exports; } -NODE_MODULE(rclnodejs, InitModule); +NODE_API_MODULE(rclnodejs, InitModule) diff --git a/src/executor.cpp b/src/executor.cpp index 38c70295..2f964d7c 100644 --- a/src/executor.cpp +++ b/src/executor.cpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "executor.hpp" +#include "executor.h" #include #include #include -#include "handle_manager.hpp" -#include "macros.hpp" -#include "rcl_bindings.hpp" +#include "handle_manager.h" +#include "macros.h" +#include "rcl_bindings.h" #ifdef WIN32 #define UNUSED @@ -41,12 +41,14 @@ struct RclResult { std::string error_msg; }; -Executor::Executor(HandleManager* handle_manager, Delegate* delegate) +Executor::Executor(Napi::Env env, HandleManager* handle_manager, + Delegate* delegate) : async_(nullptr), main_thread_(uv_thread_self()), handle_manager_(handle_manager), delegate_(delegate), - context_(nullptr) { + context_(nullptr), + env_(env) { running_.store(false); } @@ -74,12 +76,19 @@ void Executor::SpinOnce(rcl_context_t* context, int32_t time_out) { rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 0, 0, context, rcl_get_default_allocator()); - if (ret != RCL_RET_OK) Nan::ThrowError(rcl_get_error_string().str); + if (ret != RCL_RET_OK) { + Napi::Error::New(env_, rcl_get_error_string().str) + .ThrowAsJavaScriptException(); + return; + } RclResult wait_result = WaitForReadyCallbacks(&wait_set, time_out); - if (wait_result.ret != RCL_RET_OK) - Nan::ThrowError(wait_result.error_msg.c_str()); + if (wait_result.ret != RCL_RET_OK) { + Napi::Error::New(env_, wait_result.error_msg.c_str()) + .ThrowAsJavaScriptException(); + return; + } if (handle_manager_->ready_handles_count() > 0) ExecuteReadyHandles(); @@ -87,7 +96,7 @@ void Executor::SpinOnce(rcl_context_t* context, int32_t time_out) { std::string error_message = std::string("Failed to destroy guard waitset:") + std::string(rcl_get_error_string().str); - Nan::ThrowError(error_message.c_str()); + Napi::Error::New(env_, error_message.c_str()).ThrowAsJavaScriptException(); } } diff --git a/src/executor.hpp b/src/executor.h similarity index 89% rename from src/executor.hpp rename to src/executor.h index 5d16bf56..5b5b2a67 100644 --- a/src/executor.hpp +++ b/src/executor.h @@ -12,9 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SRC_EXECUTOR_HPP_ -#define SRC_EXECUTOR_HPP_ +#ifndef SRC_EXECUTOR_H_ +#define SRC_EXECUTOR_H_ +#include #include #include @@ -22,7 +23,7 @@ #include #include -#include "rcl_handle.hpp" +#include "rcl_handle.h" namespace rclnodejs { @@ -37,7 +38,7 @@ class Executor { virtual void CatchException(std::exception_ptr e_ptr) = 0; }; - Executor(HandleManager* handle_manager, Delegate* delegate); + Executor(Napi::Env env, HandleManager* handle_manager, Delegate* delegate); ~Executor(); void Start(rcl_context_t* context, int32_t time_out); @@ -68,10 +69,11 @@ class Executor { Delegate* delegate_; rcl_context_t* context_; int32_t time_out_; + Napi::Env env_; std::atomic_bool running_; }; } // namespace rclnodejs -#endif // SRC_EXECUTOR_HPP_ +#endif // SRC_EXECUTOR_H_ diff --git a/src/handle_manager.cpp b/src/handle_manager.cpp index fb9153f8..ac3e10c8 100644 --- a/src/handle_manager.cpp +++ b/src/handle_manager.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "handle_manager.hpp" +#include "handle_manager.h" #include #include #include -#include "macros.hpp" +#include "macros.h" namespace rclnodejs { @@ -38,22 +38,16 @@ HandleManager::~HandleManager() { uv_sem_destroy(&wait_handle_sem_); } -void HandleManager::SynchronizeHandles(const v8::Local node) { - Nan::HandleScope scope; - Nan::MaybeLocal timers = - Nan::Get(node, Nan::New("_timers").ToLocalChecked()); - Nan::MaybeLocal subscriptions = - Nan::Get(node, Nan::New("_subscriptions").ToLocalChecked()); - Nan::MaybeLocal clients = - Nan::Get(node, Nan::New("_clients").ToLocalChecked()); - Nan::MaybeLocal services = - Nan::Get(node, Nan::New("_services").ToLocalChecked()); - Nan::MaybeLocal guard_conditions = - Nan::Get(node, Nan::New("_guards").ToLocalChecked()); - Nan::MaybeLocal action_clients = - Nan::Get(node, Nan::New("_actionClients").ToLocalChecked()); - Nan::MaybeLocal action_servers = - Nan::Get(node, Nan::New("_actionServers").ToLocalChecked()); +void HandleManager::SynchronizeHandles(const Napi::Object& node) { + Napi::HandleScope scope(node.Env()); + + Napi::Value timers = node.Get("_timers"); + Napi::Value subscriptions = node.Get("_subscriptions"); + Napi::Value clients = node.Get("_clients"); + Napi::Value services = node.Get("_services"); + Napi::Value guard_conditions = node.Get("_guards"); + Napi::Value action_clients = node.Get("_actionClients"); + Napi::Value action_servers = node.Get("_actionServers"); uint32_t sum = 0; is_synchronizing_.store(true); @@ -61,27 +55,17 @@ void HandleManager::SynchronizeHandles(const v8::Local node) { ScopedReadWriteLock scoped_lock(&sync_handles_rwlock_, ScopedReadWriteLock::LockType::kWrite); ClearHandles(); - sum += SynchronizeHandlesByType( - Nan::To(timers.ToLocalChecked()).ToLocalChecked(), - &timers_); - sum += SynchronizeHandlesByType( - Nan::To(subscriptions.ToLocalChecked()).ToLocalChecked(), - &subscriptions_); - sum += SynchronizeHandlesByType( - Nan::To(clients.ToLocalChecked()).ToLocalChecked(), - &clients_); - sum += SynchronizeHandlesByType( - Nan::To(services.ToLocalChecked()).ToLocalChecked(), - &services_); - sum += SynchronizeHandlesByType( - Nan::To(guard_conditions.ToLocalChecked()).ToLocalChecked(), - &guard_conditions_); - sum += SynchronizeHandlesByType( - Nan::To(action_clients.ToLocalChecked()).ToLocalChecked(), - &action_clients_); - sum += SynchronizeHandlesByType( - Nan::To(action_servers.ToLocalChecked()).ToLocalChecked(), - &action_servers_); + sum += SynchronizeHandlesByType(timers.As(), &timers_); + sum += SynchronizeHandlesByType(subscriptions.As(), + &subscriptions_); + sum += SynchronizeHandlesByType(clients.As(), &clients_); + sum += SynchronizeHandlesByType(services.As(), &services_); + sum += SynchronizeHandlesByType(guard_conditions.As(), + &guard_conditions_); + sum += SynchronizeHandlesByType(action_clients.As(), + &action_clients_); + sum += SynchronizeHandlesByType(action_servers.As(), + &action_servers_); } is_synchronizing_.store(false); @@ -265,26 +249,16 @@ uint32_t HandleManager::ready_handles_count() { } uint32_t HandleManager::SynchronizeHandlesByType( - const v8::Local& typeObject, - std::vector* vec) { - Nan::HandleScope scope; - - if (typeObject->IsArray()) { - uint32_t length = - Nan::To( - Nan::Get(typeObject, Nan::New("length").ToLocalChecked()) - .ToLocalChecked()) - .FromJust(); + const Napi::Object& typeObject, std::vector* vec) { + if (typeObject.IsArray()) { + uint32_t length = typeObject.Get("length").As().Uint32Value(); for (uint32_t index = 0; index < length; index++) { - v8::Local obj = - Nan::To(Nan::Get(typeObject, index).ToLocalChecked()) - .ToLocalChecked(); - Nan::MaybeLocal handle = - Nan::Get(obj, Nan::New("_handle").ToLocalChecked()); + Napi::Object obj = typeObject.Get(index).As(); + Napi::Value handle = obj.Get("_handle"); rclnodejs::RclHandle* rcl_handle = - rclnodejs::RclHandle::Unwrap( - Nan::To(handle.ToLocalChecked()).ToLocalChecked()); + Napi::ObjectWrap::Unwrap( + handle.As()); vec->push_back(rcl_handle); } } diff --git a/src/handle_manager.hpp b/src/handle_manager.h similarity index 93% rename from src/handle_manager.hpp rename to src/handle_manager.h index 9605c8a8..0e47a943 100644 --- a/src/handle_manager.hpp +++ b/src/handle_manager.h @@ -12,16 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SRC_HANDLE_MANAGER_HPP_ -#define SRC_HANDLE_MANAGER_HPP_ +#ifndef SRC_HANDLE_MANAGER_H_ +#define SRC_HANDLE_MANAGER_H_ -#include +#include #include +#include #include #include -#include "rcl_handle.hpp" +#include "rcl_handle.h" namespace rclnodejs { @@ -53,7 +54,7 @@ class HandleManager { HandleManager(); ~HandleManager(); - void SynchronizeHandles(const v8::Local node); + void SynchronizeHandles(const Napi::Object& node); void WaitForSynchronizing(); // Waits the handles to be attached from the background thread. @@ -89,7 +90,7 @@ class HandleManager { protected: // Synchronize the handles from `typeObject`. - uint32_t SynchronizeHandlesByType(const v8::Local& typeObject, + uint32_t SynchronizeHandlesByType(const Napi::Object& typeObject, std::vector* vec); template void CollectReadyHandlesByType( @@ -132,4 +133,4 @@ class HandleManager { } // namespace rclnodejs -#endif // SRC_HANDLE_MANAGER_HPP_ +#endif // SRC_HANDLE_MANAGER_H_ diff --git a/src/macros.hpp b/src/macros.h similarity index 88% rename from src/macros.hpp rename to src/macros.h index 399d0fc5..793aa41b 100644 --- a/src/macros.hpp +++ b/src/macros.h @@ -12,17 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SRC_MACROS_HPP_ -#define SRC_MACROS_HPP_ +#ifndef SRC_MACROS_H_ +#define SRC_MACROS_H_ + +#include #include "rcutils/logging_macros.h" #define CHECK_OP_AND_THROW_ERROR_IF_NOT_TRUE(op, lhs, rhs, message) \ { \ if (lhs op rhs) { \ - Nan::ThrowError(message); \ rcl_reset_error(); \ - return; \ + Napi::Error::New(rclnodejs::GetEnv(), message) \ + .ThrowAsJavaScriptException(); \ } \ } @@ -43,4 +45,4 @@ #define RCLNODEJS_DEBUG(...) #endif -#endif // SRC_MACROS_HPP_ +#endif // SRC_MACROS_H_ diff --git a/src/rcl_action_bindings.cpp b/src/rcl_action_bindings.cpp index 4d96901c..b11146a3 100644 --- a/src/rcl_action_bindings.cpp +++ b/src/rcl_action_bindings.cpp @@ -12,8 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rcl_action_bindings.hpp" +#include "rcl_action_bindings.h" +#include #include #include #include @@ -24,24 +25,21 @@ #include #include -#include "handle_manager.hpp" -#include "macros.hpp" -#include "rcl_handle.hpp" -#include "rcl_utilities.hpp" +#include "handle_manager.h" +#include "macros.h" +#include "rcl_handle.h" +#include "rcl_utilities.h" namespace rclnodejs { -NAN_METHOD(ActionCreateClient) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionCreateClient(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 action_name( - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked())); - std::string interface_name( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); - std::string package_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); + std::string action_name = info[1].As().Utf8Value(); + std::string interface_name = info[2].As().Utf8Value(); + std::string package_name = info[3].As().Utf8Value(); const rosidl_action_type_support_t* ts = GetActionTypeSupport(package_name, interface_name); @@ -80,8 +78,8 @@ NAN_METHOD(ActionCreateClient) { rcl_action_client_init(action_client, node, ts, action_name.c_str(), &action_client_ops), RCL_RET_OK, rcl_get_error_string().str); - auto js_obj = - RclHandle::NewInstance(action_client, node_handle, [node](void* ptr) { + auto js_obj = RclHandle::NewInstance( + env, action_client, node_handle, [node](void* ptr) { rcl_action_client_t* action_client = reinterpret_cast(ptr); rcl_ret_t ret = rcl_action_client_fini(action_client, node); @@ -89,27 +87,25 @@ NAN_METHOD(ActionCreateClient) { 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(ActionCreateServer) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionCreateServer(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()); - 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); @@ -151,8 +147,8 @@ NAN_METHOD(ActionCreateServer) { rcl_action_server_init(action_server, node, clock, ts, action_name.c_str(), &action_server_ops), RCL_RET_OK, rcl_get_error_string().str); - auto js_obj = - RclHandle::NewInstance(action_server, node_handle, [node](void* ptr) { + auto js_obj = RclHandle::NewInstance( + env, action_server, node_handle, [node](void* ptr) { rcl_action_server_t* action_server = reinterpret_cast(ptr); rcl_ret_t ret = rcl_action_server_fini(action_server, node); @@ -160,18 +156,21 @@ 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()); +Napi::Value ActionServerIsAvailable(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()); - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()); + RclHandle* action_client_handle = + RclHandle::Unwrap(info[1].As()); rcl_action_client_t* action_client = reinterpret_cast(action_client_handle->ptr()); @@ -181,76 +180,74 @@ NAN_METHOD(ActionServerIsAvailable) { rcl_action_server_is_available(node, action_client, &is_available), rcl_get_error_string().str); - v8::Local result = Nan::New(is_available); - info.GetReturnValue().Set(result); + return Napi::Boolean::New(env, is_available); } -NAN_METHOD(ActionSendGoalRequest) { - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionSendGoalRequest(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* action_client_handle = + RclHandle::Unwrap(info[0].As()); rcl_action_client_t* action_client = reinterpret_cast(action_client_handle->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* buffer = info[1].As>().Data(); int64_t sequence_number; THROW_ERROR_IF_NOT_EQUAL( rcl_action_send_goal_request(action_client, buffer, &sequence_number), RCL_RET_OK, rcl_get_error_string().str); - v8::Local result = - Nan::New(static_cast(sequence_number)); - info.GetReturnValue().Set(result); + return Napi::Number::New(env, static_cast(sequence_number)); } -NAN_METHOD(ActionTakeGoalRequest) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionTakeGoalRequest(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()); rmw_request_id_t* header = reinterpret_cast(malloc(sizeof(rmw_request_id_t))); - void* taken_request = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* taken_request = info[1].As>().Data(); rcl_ret_t ret = rcl_action_take_goal_request(action_server, header, taken_request); if (ret != RCL_RET_ACTION_SERVER_TAKE_FAILED) { - auto js_obj = - RclHandle::NewInstance(header, nullptr, [](void* ptr) { free(ptr); }); - info.GetReturnValue().Set(js_obj); - return; + auto js_obj = RclHandle::NewInstance(env, header, nullptr, + [](void* ptr) { free(ptr); }); + return js_obj; } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionSendGoalResponse) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionSendGoalResponse(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()); rmw_request_id_t* header = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()) - ->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[2]).ToLocalChecked()); + RclHandle::Unwrap(info[1].As())->ptr()); + void* buffer = info[2].As>().Data(); THROW_ERROR_IF_NOT_EQUAL( rcl_action_send_goal_response(action_server, header, buffer), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionTakeGoalResponse) { - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionTakeGoalResponse(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* action_client_handle = + RclHandle::Unwrap(info[0].As()); rcl_action_client_t* action_client = reinterpret_cast(action_client_handle->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* buffer = info[1].As>().Data(); rmw_request_id_t* header = reinterpret_cast(malloc(sizeof(rmw_request_id_t))); @@ -259,87 +256,83 @@ NAN_METHOD(ActionTakeGoalResponse) { free(header); if (ret != RCL_RET_OK && ret != RCL_RET_ACTION_CLIENT_TAKE_FAILED) { - Nan::ThrowError(rcl_get_error_string().str); rcl_reset_error(); - info.GetReturnValue().Set(Nan::Undefined()); - return; + Napi::Error::New(env, rcl_get_error_string().str) + .ThrowAsJavaScriptException(); + return env.Undefined(); } if (ret != RCL_RET_ACTION_CLIENT_TAKE_FAILED) { - v8::Local result = - Nan::New(static_cast(sequence_number)); - info.GetReturnValue().Set(result); - return; + return Napi::Number::New(env, static_cast(sequence_number)); } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionSendCancelRequest) { - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionSendCancelRequest(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* action_client_handle = + RclHandle::Unwrap(info[0].As()); rcl_action_client_t* action_client = reinterpret_cast(action_client_handle->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* buffer = info[1].As>().Data(); int64_t sequence_number; THROW_ERROR_IF_NOT_EQUAL( rcl_action_send_cancel_request(action_client, buffer, &sequence_number), RCL_RET_OK, rcl_get_error_string().str); - v8::Local result = - Nan::New(static_cast(sequence_number)); - info.GetReturnValue().Set(result); + return Napi::Number::New(env, static_cast(sequence_number)); } -NAN_METHOD(ActionTakeCancelRequest) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionTakeCancelRequest(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()); rmw_request_id_t* header = reinterpret_cast(malloc(sizeof(rmw_request_id_t))); - void* taken_request = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* taken_request = info[1].As>().Data(); rcl_ret_t ret = rcl_action_take_cancel_request(action_server, header, taken_request); if (ret != RCL_RET_ACTION_SERVER_TAKE_FAILED) { - auto js_obj = - RclHandle::NewInstance(header, nullptr, [](void* ptr) { free(ptr); }); - info.GetReturnValue().Set(js_obj); - return; + auto js_obj = RclHandle::NewInstance(env, header, nullptr, + [](void* ptr) { free(ptr); }); + return js_obj; } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionSendCancelResponse) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionSendCancelResponse(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()); rmw_request_id_t* header = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()) - ->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[2]).ToLocalChecked()); + RclHandle::Unwrap(info[1].As())->ptr()); + void* buffer = info[2].As>().Data(); THROW_ERROR_IF_NOT_EQUAL( rcl_action_send_cancel_response(action_server, header, buffer), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionTakeCancelResponse) { - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionTakeCancelResponse(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* action_client_handle = + RclHandle::Unwrap(info[0].As()); rcl_action_client_t* action_client = reinterpret_cast(action_client_handle->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* buffer = info[1].As>().Data(); rmw_request_id_t* header = reinterpret_cast(malloc(sizeof(rmw_request_id_t))); @@ -349,88 +342,84 @@ NAN_METHOD(ActionTakeCancelResponse) { free(header); if (ret != RCL_RET_OK && ret != RCL_RET_ACTION_CLIENT_TAKE_FAILED) { - Nan::ThrowError(rcl_get_error_string().str); rcl_reset_error(); - info.GetReturnValue().Set(Nan::Undefined()); - return; + Napi::Error::New(env, rcl_get_error_string().str) + .ThrowAsJavaScriptException(); + return env.Undefined(); } if (ret != RCL_RET_ACTION_CLIENT_TAKE_FAILED) { - v8::Local result = - Nan::New(static_cast(sequence_number)); - info.GetReturnValue().Set(result); - return; + return Napi::Number::New(env, static_cast(sequence_number)); } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionSendResultRequest) { - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionSendResultRequest(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* action_client_handle = + RclHandle::Unwrap(info[0].As()); rcl_action_client_t* action_client = reinterpret_cast(action_client_handle->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* buffer = info[1].As>().Data(); int64_t sequence_number; THROW_ERROR_IF_NOT_EQUAL( rcl_action_send_result_request(action_client, buffer, &sequence_number), RCL_RET_OK, rcl_get_error_string().str); - v8::Local result = - Nan::New(static_cast(sequence_number)); - info.GetReturnValue().Set(result); + return Napi::Number::New(env, static_cast(sequence_number)); } -NAN_METHOD(ActionTakeResultRequest) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionTakeResultRequest(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()); rmw_request_id_t* header = reinterpret_cast(malloc(sizeof(rmw_request_id_t))); - void* taken_request = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* taken_request = info[1].As>().Data(); rcl_ret_t ret = rcl_action_take_result_request(action_server, header, taken_request); if (ret != RCL_RET_ACTION_SERVER_TAKE_FAILED) { - auto js_obj = - RclHandle::NewInstance(header, nullptr, [](void* ptr) { free(ptr); }); - info.GetReturnValue().Set(js_obj); - return; + auto js_obj = RclHandle::NewInstance(env, header, nullptr, + [](void* ptr) { free(ptr); }); + return js_obj; } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionSendResultResponse) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionSendResultResponse(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()); rmw_request_id_t* header = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()) - ->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[2]).ToLocalChecked()); + RclHandle::Unwrap(info[1].As())->ptr()); + void* buffer = info[2].As>().Data(); THROW_ERROR_IF_NOT_EQUAL( rcl_action_send_result_response(action_server, header, buffer), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionTakeResultResponse) { - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionTakeResultResponse(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* action_client_handle = + RclHandle::Unwrap(info[0].As()); rcl_action_client_t* action_client = reinterpret_cast(action_client_handle->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* buffer = info[1].As>().Data(); rmw_request_id_t* header = reinterpret_cast(malloc(sizeof(rmw_request_id_t))); @@ -440,28 +429,27 @@ NAN_METHOD(ActionTakeResultResponse) { free(header); if (ret != RCL_RET_OK && ret != RCL_RET_ACTION_CLIENT_TAKE_FAILED) { - Nan::ThrowError(rcl_get_error_string().str); rcl_reset_error(); - info.GetReturnValue().Set(Nan::Undefined()); - return; + Napi::Error::New(env, rcl_get_error_string().str) + .ThrowAsJavaScriptException(); + return env.Undefined(); } if (ret != RCL_RET_ACTION_CLIENT_TAKE_FAILED) { - v8::Local result = - Nan::New(static_cast(sequence_number)); - info.GetReturnValue().Set(result); - return; + return Napi::Number::New(env, static_cast(sequence_number)); } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionAcceptNewGoal) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionAcceptNewGoal(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(Nan::To(info[1]).ToLocalChecked())); + info[1].As>().Data()); rcl_action_goal_handle_t* goal_handle = reinterpret_cast( @@ -469,41 +457,44 @@ NAN_METHOD(ActionAcceptNewGoal) { *goal_handle = *rcl_action_accept_new_goal(action_server, buffer); if (!goal_handle) { - 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(); } - auto js_obj = RclHandle::NewInstance(goal_handle, nullptr, [](void* ptr) { - rcl_action_goal_handle_t* goal_handle = - reinterpret_cast(ptr); - rcl_ret_t ret = rcl_action_goal_handle_fini(goal_handle); - free(ptr); - THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); - }); + auto js_obj = + RclHandle::NewInstance(env, goal_handle, nullptr, [](void* ptr) { + rcl_action_goal_handle_t* goal_handle = + reinterpret_cast(ptr); + rcl_ret_t ret = rcl_action_goal_handle_fini(goal_handle); + 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(ActionUpdateGoalState) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* goal_handle_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionUpdateGoalState(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* goal_handle_handle = RclHandle::Unwrap(info[0].As()); rcl_action_goal_handle_t* goal_handle = reinterpret_cast(goal_handle_handle->ptr()); rcl_action_goal_event_t event = static_cast( - info[1]->IntegerValue(currentContent).FromJust()); + info[1].As().Int32Value()); THROW_ERROR_IF_NOT_EQUAL(rcl_action_update_goal_state(goal_handle, event), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionPublishStatus) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionPublishStatus(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()); @@ -518,59 +509,62 @@ NAN_METHOD(ActionPublishStatus) { rcl_action_publish_status(action_server, &status_message), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionTakeStatus) { - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionTakeStatus(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* action_client_handle = + RclHandle::Unwrap(info[0].As()); rcl_action_client_t* action_client = reinterpret_cast(action_client_handle->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* buffer = info[1].As>().Data(); rcl_ret_t ret = rcl_action_take_status(action_client, buffer); if (ret != RCL_RET_OK && ret != RCL_RET_ACTION_CLIENT_TAKE_FAILED) { - Nan::ThrowError(rcl_get_error_string().str); rcl_reset_error(); - info.GetReturnValue().Set(Nan::False()); - return; + Napi::Error::New(env, rcl_get_error_string().str) + .ThrowAsJavaScriptException(); + return Napi::Boolean::New(env, false); } if (ret != RCL_RET_ACTION_CLIENT_TAKE_FAILED) { - info.GetReturnValue().Set(Nan::True()); - return; + return Napi::Boolean::New(env, true); } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionGoalHandleIsActive) { - RclHandle* goal_handle_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionGoalHandleIsActive(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* goal_handle_handle = RclHandle::Unwrap(info[0].As()); rcl_action_goal_handle_t* goal_handle = reinterpret_cast(goal_handle_handle->ptr()); bool is_active = rcl_action_goal_handle_is_active(goal_handle); - v8::Local result = Nan::New(is_active); - info.GetReturnValue().Set(result); + return Napi::Boolean::New(env, is_active); } -NAN_METHOD(ActionNotifyGoalDone) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionNotifyGoalDone(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()); THROW_ERROR_IF_NOT_EQUAL(rcl_action_notify_goal_done(action_server), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionGoalHandleGetStatus) { - RclHandle* goal_handle_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionGoalHandleGetStatus(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* goal_handle_handle = RclHandle::Unwrap(info[0].As()); rcl_action_goal_handle_t* goal_handle = reinterpret_cast(goal_handle_handle->ptr()); @@ -579,59 +573,56 @@ NAN_METHOD(ActionGoalHandleGetStatus) { rcl_action_goal_handle_get_status(goal_handle, &status), RCL_RET_OK, rcl_get_error_string().str); - v8::Local result = - Nan::New(static_cast(status)); - info.GetReturnValue().Set(result); + return Napi::Number::New(env, static_cast(status)); } -NAN_METHOD(ActionPublishFeedback) { +Napi::Value ActionPublishFeedback(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + rcl_action_server_t* action_server = reinterpret_cast( - RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()) - ->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + RclHandle::Unwrap(info[0].As())->ptr()); + void* buffer = info[1].As>().Data(); THROW_ERROR_IF_NOT_EQUAL(rcl_action_publish_feedback(action_server, buffer), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionTakeFeedback) { - RclHandle* action_client_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionTakeFeedback(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* action_client_handle = + RclHandle::Unwrap(info[0].As()); rcl_action_client_t* action_client = reinterpret_cast(action_client_handle->ptr()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* buffer = info[1].As>().Data(); rcl_ret_t ret = rcl_action_take_feedback(action_client, buffer); if (ret != RCL_RET_OK && ret != RCL_RET_ACTION_CLIENT_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 Napi::Boolean::New(env, false); } if (ret != RCL_RET_ACTION_CLIENT_TAKE_FAILED) { - info.GetReturnValue().Set(Nan::True()); - return; + return Napi::Boolean::New(env, true); } - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(ActionProcessCancelRequest) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionProcessCancelRequest(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()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + void* buffer = info[1].As>().Data(); rcl_action_cancel_request_t* cancel_request = reinterpret_cast(buffer); - void* response_buffer = - node::Buffer::Data(Nan::To(info[2]).ToLocalChecked()); + void* response_buffer = info[2].As>().Data(); action_msgs__srv__CancelGoal_Response* response = reinterpret_cast(response_buffer); @@ -656,66 +647,63 @@ NAN_METHOD(ActionProcessCancelRequest) { rcl_reset_error(); } free(cancel_response_ptr); - Nan::ThrowError(cancel_error.str); - info.GetReturnValue().Set(Nan::Undefined()); - return; + Napi::Error::New(env, cancel_error.str).ThrowAsJavaScriptException(); + return env.Undefined(); } *response = cancel_response_ptr->msg; auto js_obj = - RclHandle::NewInstance(cancel_response_ptr, nullptr, [](void* ptr) { + RclHandle::NewInstance(env, cancel_response_ptr, nullptr, [](void* ptr) { rcl_action_cancel_response_t* cancel_response_ptr = reinterpret_cast(ptr); rcl_ret_t ret = rcl_action_cancel_response_fini(cancel_response_ptr); 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(ActionServerGoalExists) { - RclHandle* action_server_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionServerGoalExists(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(Nan::To(info[1]).ToLocalChecked())); + info[1].As>().Data()); bool exists = rcl_action_server_goal_exists(action_server, buffer); - v8::Local result = Nan::New(exists); - info.GetReturnValue().Set(result); + return Napi::Boolean::New(env, exists); } -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())); + info[2].As>().Data()); 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()); - std::string node_namespace = - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked()); + std::string node_name = info[1].As().Utf8Value(); + std::string node_namespace = info[2].As().Utf8Value(); rcl_names_and_types_t names_and_types = rcl_get_zero_initialized_names_and_types(); @@ -726,26 +714,23 @@ 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); + Napi::Array result_list = Napi::Array::New(env, names_and_types.names.size); ExtractNamesAndTypes(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) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionGetServerNamesAndTypesByNode(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()); - std::string node_namespace = - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked()); + std::string node_name = info[1].As().Utf8Value(); + std::string node_namespace = info[2].As().Utf8Value(); rcl_names_and_types_t names_and_types = rcl_get_zero_initialized_names_and_types(); @@ -756,20 +741,20 @@ NAN_METHOD(ActionGetServerNamesAndTypesByNode) { node_namespace.c_str(), &names_and_types), "Failed to action server names and types"); - v8::Local result_list = - Nan::New(names_and_types.names.size); + Napi::Array result_list = Napi::Array::New(env, names_and_types.names.size); ExtractNamesAndTypes(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(ActionGetNamesAndTypes) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ActionGetNamesAndTypes(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()); rcl_names_and_types_t names_and_types = @@ -780,47 +765,77 @@ NAN_METHOD(ActionGetNamesAndTypes) { rcl_action_get_names_and_types(node, &allocator, &names_and_types), "Failed to action server names and types"); - v8::Local result_list = - Nan::New(names_and_types.names.size); + Napi::Array result_list = Napi::Array::New(env, names_and_types.names.size); ExtractNamesAndTypes(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; } -std::vector action_binding_methods = { - {"actionCreateClient", ActionCreateClient}, - {"actionCreateServer", ActionCreateServer}, - {"actionServerIsAvailable", ActionServerIsAvailable}, - {"actionSendGoalRequest", ActionSendGoalRequest}, - {"actionTakeGoalRequest", ActionTakeGoalRequest}, - {"actionSendGoalResponse", ActionSendGoalResponse}, - {"actionTakeGoalResponse", ActionTakeGoalResponse}, - {"actionSendCancelRequest", ActionSendCancelRequest}, - {"actionTakeCancelRequest", ActionTakeCancelRequest}, - {"actionSendCancelResponse", ActionSendCancelResponse}, - {"actionTakeCancelResponse", ActionTakeCancelResponse}, - {"actionSendResultRequest", ActionSendResultRequest}, - {"actionTakeResultRequest", ActionTakeResultRequest}, - {"actionSendResultResponse", ActionSendResultResponse}, - {"actionTakeResultResponse", ActionTakeResultResponse}, - {"actionAcceptNewGoal", ActionAcceptNewGoal}, - {"actionUpdateGoalState", ActionUpdateGoalState}, - {"actionPublishStatus", ActionPublishStatus}, - {"actionTakeStatus", ActionTakeStatus}, - {"actionGoalHandleIsActive", ActionGoalHandleIsActive}, - {"actionNotifyGoalDone", ActionNotifyGoalDone}, - {"actionGoalHandleGetStatus", ActionGoalHandleGetStatus}, - {"actionPublishFeedback", ActionPublishFeedback}, - {"actionTakeFeedback", ActionTakeFeedback}, - {"actionProcessCancelRequest", ActionProcessCancelRequest}, - {"actionServerGoalExists", ActionServerGoalExists}, - {"actionExpireGoals", ActionExpireGoals}, - {"actionGetClientNamesAndTypesByNode", ActionGetClientNamesAndTypesByNode}, - {"actionGetServerNamesAndTypesByNode", ActionGetServerNamesAndTypesByNode}, - {"actionGetNamesAndTypes", ActionGetNamesAndTypes}}; +Napi::Object InitAction(Napi::Env env, Napi::Object exports) { + exports.Set("actionCreateClient", + Napi::Function::New(env, ActionCreateClient)); + exports.Set("actionCreateServer", + Napi::Function::New(env, ActionCreateServer)); + exports.Set("actionServerIsAvailable", + Napi::Function::New(env, ActionServerIsAvailable)); + exports.Set("actionSendGoalRequest", + Napi::Function::New(env, ActionSendGoalRequest)); + exports.Set("actionTakeGoalRequest", + Napi::Function::New(env, ActionTakeGoalRequest)); + exports.Set("actionSendGoalResponse", + Napi::Function::New(env, ActionSendGoalResponse)); + exports.Set("actionTakeGoalResponse", + Napi::Function::New(env, ActionTakeGoalResponse)); + exports.Set("actionSendCancelRequest", + Napi::Function::New(env, ActionSendCancelRequest)); + exports.Set("actionTakeCancelRequest", + Napi::Function::New(env, ActionTakeCancelRequest)); + exports.Set("actionSendCancelResponse", + Napi::Function::New(env, ActionSendCancelResponse)); + exports.Set("actionTakeCancelResponse", + Napi::Function::New(env, ActionTakeCancelResponse)); + exports.Set("actionSendResultRequest", + Napi::Function::New(env, ActionSendResultRequest)); + exports.Set("actionTakeResultRequest", + Napi::Function::New(env, ActionTakeResultRequest)); + exports.Set("actionSendResultResponse", + Napi::Function::New(env, ActionSendResultResponse)); + exports.Set("actionTakeResultResponse", + Napi::Function::New(env, ActionTakeResultResponse)); + exports.Set("actionAcceptNewGoal", + Napi::Function::New(env, ActionAcceptNewGoal)); + exports.Set("actionUpdateGoalState", + Napi::Function::New(env, ActionUpdateGoalState)); + exports.Set("actionPublishStatus", + Napi::Function::New(env, ActionPublishStatus)); + exports.Set("actionTakeStatus", Napi::Function::New(env, ActionTakeStatus)); + exports.Set("actionGoalHandleIsActive", + Napi::Function::New(env, ActionGoalHandleIsActive)); + exports.Set("actionNotifyGoalDone", + Napi::Function::New(env, ActionNotifyGoalDone)); + exports.Set("actionGoalHandleGetStatus", + Napi::Function::New(env, ActionGoalHandleGetStatus)); + exports.Set("actionPublishFeedback", + Napi::Function::New(env, ActionPublishFeedback)); + exports.Set("actionTakeFeedback", + Napi::Function::New(env, ActionTakeFeedback)); + exports.Set("actionProcessCancelRequest", + Napi::Function::New(env, ActionProcessCancelRequest)); + exports.Set("actionServerGoalExists", + Napi::Function::New(env, ActionServerGoalExists)); + exports.Set("actionExpireGoals", Napi::Function::New(env, ActionExpireGoals)); + exports.Set("actionGetClientNamesAndTypesByNode", + Napi::Function::New(env, ActionGetClientNamesAndTypesByNode)); + exports.Set("actionGetServerNamesAndTypesByNode", + Napi::Function::New(env, ActionGetServerNamesAndTypesByNode)); + exports.Set("actionGetNamesAndTypes", + Napi::Function::New(env, ActionGetNamesAndTypes)); + + return exports; +} } // namespace rclnodejs diff --git a/src/rcl_action_bindings.h b/src/rcl_action_bindings.h new file mode 100644 index 00000000..9e7e5c58 --- /dev/null +++ b/src/rcl_action_bindings.h @@ -0,0 +1,64 @@ +// Copyright (c) 2017 Intel Corporation. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SRC_RCL_ACTION_BINDINGS_H_ +#define SRC_RCL_ACTION_BINDINGS_H_ + +#include +#include + +#include +#include +#include + +#include "rcl_bindings.h" + +namespace rclnodejs { + +Napi::Value ActionCreateClient(const Napi::CallbackInfo& info); +Napi::Value ActionCreateServer(const Napi::CallbackInfo& info); +Napi::Value ActionServerIsAvailable(const Napi::CallbackInfo& info); +Napi::Value ActionSendGoalRequest(const Napi::CallbackInfo& info); +Napi::Value ActionTakeGoalRequest(const Napi::CallbackInfo& info); +Napi::Value ActionSendGoalResponse(const Napi::CallbackInfo& info); +Napi::Value ActionTakeGoalResponse(const Napi::CallbackInfo& info); +Napi::Value ActionSendCancelRequest(const Napi::CallbackInfo& info); +Napi::Value ActionTakeCancelRequest(const Napi::CallbackInfo& info); +Napi::Value ActionSendCancelResponse(const Napi::CallbackInfo& info); +Napi::Value ActionTakeCancelResponse(const Napi::CallbackInfo& info); +Napi::Value ActionSendResultRequest(const Napi::CallbackInfo& info); +Napi::Value ActionTakeResultRequest(const Napi::CallbackInfo& info); +Napi::Value ActionSendResultResponse(const Napi::CallbackInfo& info); +Napi::Value ActionTakeResultResponse(const Napi::CallbackInfo& info); +Napi::Value ActionAcceptNewGoal(const Napi::CallbackInfo& info); +Napi::Value ActionUpdateGoalState(const Napi::CallbackInfo& info); +Napi::Value ActionPublishStatus(const Napi::CallbackInfo& info); +Napi::Value ActionTakeStatus(const Napi::CallbackInfo& info); +Napi::Value ActionGoalHandleIsActive(const Napi::CallbackInfo& info); +Napi::Value ActionNotifyGoalDone(const Napi::CallbackInfo& info); +Napi::Value ActionGoalHandleGetStatus(const Napi::CallbackInfo& info); +Napi::Value ActionPublishFeedback(const Napi::CallbackInfo& info); +Napi::Value ActionTakeFeedback(const Napi::CallbackInfo& info); +Napi::Value ActionProcessCancelRequest(const Napi::CallbackInfo& info); +Napi::Value ActionServerGoalExists(const Napi::CallbackInfo& info); +Napi::Value ActionExpireGoals(const Napi::CallbackInfo& info); +Napi::Value ActionGetClientNamesAndTypesByNode(const Napi::CallbackInfo& info); +Napi::Value ActionGetServerNamesAndTypesByNode(const Napi::CallbackInfo& info); +Napi::Value ActionGetNamesAndTypes(const Napi::CallbackInfo& info); + +Napi::Object InitAction(Napi::Env env, Napi::Object exports); + +} // namespace rclnodejs + +#endif // SRC_RCL_ACTION_BINDINGS_H_ diff --git a/src/rcl_action_bindings.hpp b/src/rcl_action_bindings.hpp deleted file mode 100644 index 115816fc..00000000 --- a/src/rcl_action_bindings.hpp +++ /dev/null @@ -1,31 +0,0 @@ -// Copyright (c) 2020 Matt Richard. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef SRC_RCL_ACTION_BINDINGS_HPP_ -#define SRC_RCL_ACTION_BINDINGS_HPP_ - -#include -#include - -#include - -#include "rcl_bindings.hpp" - -namespace rclnodejs { - -extern std::vector action_binding_methods; - -} // namespace rclnodejs - -#endif // SRC_RCL_ACTION_BINDINGS_HPP_ diff --git a/src/rcl_bindings.cpp b/src/rcl_bindings.cpp index 7ee476ec..66d48290 100644 --- a/src/rcl_bindings.cpp +++ b/src/rcl_bindings.cpp @@ -12,8 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rcl_bindings.hpp" +#include "rcl_bindings.h" +#include #include #include #include @@ -30,6 +31,7 @@ #include #include #include + #if ROS_VERSION >= 2006 #include #else @@ -49,41 +51,41 @@ #include #endif -#include "handle_manager.hpp" -#include "macros.hpp" -#include "rcl_handle.hpp" -#include "rcl_utilities.hpp" +#include "handle_manager.h" +#include "macros.h" +#include "rcl_handle.h" +#include "rcl_utilities.h" namespace rclnodejs { -static v8::Local wrapParameters( - rcl_params_t* params); // NOLINT(whitespace/line_length) +static Napi::Object wrapParameters(Napi::Env env, rcl_params_t* params); + +Napi::Value InitRclnodejs(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); -NAN_METHOD(Init) { 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()); + // Preprocess Context + RclHandle* context_handle = RclHandle::Unwrap(info[0].As()); rcl_context_t* context = reinterpret_cast(context_handle->ptr()); - // preprocess argc & argv - v8::Local jsArgv = v8::Local::Cast(info[1]); - int argc = jsArgv->Length(); + // Preprocess argc & argv + Napi::Array jsArgv = info[1].As(); + 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; + std::string arg = jsArgv.Get(i).As().Utf8Value(); + int len = arg.length() + 1; argv[i] = reinterpret_cast(malloc(len * sizeof(char*))); - snprintf(argv[i], len, "%s", *utf8_arg); + snprintf(argv[i], len, "%s", arg.c_str()); } } @@ -100,11 +102,14 @@ NAN_METHOD(Init) { free(argv[i]); } free(argv); + + return env.Undefined(); } -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 +120,13 @@ 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)); + Napi::Object result = wrapParameters(env, params); rcl_yaml_node_struct_fini(params); + return result; } static const int PARAMETER_NOT_SET = 0; @@ -151,25 +156,24 @@ type Node = { parameters = array; */ -static v8::Local wrapParameters(rcl_params_t* parsed_args) { - v8::Local nodes = Nan::New(); +static Napi::Object wrapParameters(Napi::Env env, rcl_params_t* parsed_args) { + Napi::Array nodes = Napi::Array::New(env); // iterate over nodes for (size_t i = 0; i < parsed_args->num_nodes; i++) { - v8::Local node = Nan::New(); - Nan::Set(node, Nan::New("name").ToLocalChecked(), - Nan::New(parsed_args->node_names[i]).ToLocalChecked()); + Napi::Object node = Napi::Object::New(env); + node.Set("name", Napi::String::New(env, parsed_args->node_names[i])); rcl_node_params_t node_parameters = parsed_args->params[i]; // iterate over node.parameters - v8::Local parameters = Nan::New(); + Napi::Array parameters = Napi::Array::New(env); for (size_t j = 0; j < node_parameters.num_params; j++) { - v8::Local parameter = Nan::New(); + Napi::Object parameter = Napi::Object::New(env); - Nan::Set( - parameter, Nan::New("name").ToLocalChecked(), - Nan::New(parsed_args->params[i].parameter_names[j]).ToLocalChecked()); + parameter.Set( + "name", + Napi::String::New(env, parsed_args->params[i].parameter_names[j])); int param_type = PARAMETER_NOT_SET; @@ -177,83 +181,76 @@ static v8::Local wrapParameters(rcl_params_t* parsed_args) { rcl_variant_t value = node_parameters.parameter_values[j]; if (value.bool_value != NULL) { // NOLINT() param_type = PARAMETER_BOOL; - Nan::Set(parameter, Nan::New("value").ToLocalChecked(), - (*value.bool_value ? Nan::True() : Nan::False())); + parameter.Set("value", Napi::Boolean::New(env, *value.bool_value)); } else if (value.integer_value != NULL) { // NOLINT() param_type = PARAMETER_INTEGER; - Nan::Set(parameter, Nan::New("value").ToLocalChecked(), - Nan::New(*value.integer_value)); + parameter.Set("value", Napi::Number::New(env, *value.integer_value)); } else if (value.double_value != NULL) { // NOLINT() param_type = PARAMETER_DOUBLE; - Nan::Set(parameter, Nan::New("value").ToLocalChecked(), - Nan::New(*value.double_value)); + parameter.Set("value", Napi::Number::New(env, *value.double_value)); } else if (value.string_value != NULL) { // NOLINT() param_type = PARAMETER_STRING; - Nan::Set(parameter, Nan::New("value").ToLocalChecked(), - Nan::New(value.string_value).ToLocalChecked()); + parameter.Set("value", Napi::String::New(env, value.string_value)); } else if (value.bool_array_value != NULL) { // NOLINT() param_type = PARAMETER_BOOL_ARRAY; - v8::Local bool_array = Nan::New(); + Napi::Array bool_array = Napi::Array::New(env); for (size_t k = 0; k < value.bool_array_value->size; k++) { - Nan::Set( - bool_array, k, - (value.bool_array_value->values[k] ? Nan::True() : Nan::False())); + bool_array.Set( + k, Napi::Boolean::New(env, value.bool_array_value->values[k])); } - Nan::Set(parameter, Nan::New("value").ToLocalChecked(), bool_array); + parameter.Set("value", bool_array); } else if (value.string_array_value != NULL) { // NOLINT() param_type = PARAMETER_STRING_ARRAY; - v8::Local string_array = Nan::New(); + Napi::Array string_array = Napi::Array::New(env); for (size_t k = 0; k < value.string_array_value->size; k++) { - Nan::Set(string_array, k, - Nan::New(value.string_array_value->data[k]) - .ToLocalChecked()); // NOLINT(whitespace/line_length) + string_array.Set( + k, Napi::String::New(env, value.string_array_value->data[k])); } - Nan::Set(parameter, Nan::New("value").ToLocalChecked(), string_array); + parameter.Set("value", string_array); } else if (value.byte_array_value != NULL) { // NOLINT() param_type = PARAMETER_BYTE_ARRAY; - v8::Local byte_array = Nan::New(); + Napi::Array byte_array = Napi::Array::New(env); for (size_t k = 0; k < value.byte_array_value->size; k++) { - Nan::Set(byte_array, k, Nan::New(value.byte_array_value->values[k])); + byte_array.Set( + k, Napi::Number::New(env, value.byte_array_value->values[k])); } - Nan::Set(parameter, Nan::New("value").ToLocalChecked(), byte_array); + parameter.Set("value", byte_array); } else if (value.integer_array_value != NULL) { // NOLINT() param_type = PARAMETER_INTEGER_ARRAY; - v8::Local int_array = Nan::New(); + Napi::Array int_array = Napi::Array::New(env); for (size_t k = 0; k < value.integer_array_value->size; k++) { - Nan::Set(int_array, k, - Nan::New(value.integer_array_value->values[k])); + int_array.Set( + k, Napi::Number::New(env, value.integer_array_value->values[k])); } - Nan::Set(parameter, Nan::New("value").ToLocalChecked(), int_array); + parameter.Set("value", int_array); } else if (value.double_array_value != NULL) { // NOLINT() param_type = PARAMETER_DOUBLE_ARRAY; - v8::Local dbl_array = Nan::New(); + Napi::Array dbl_array = Napi::Array::New(env); for (size_t k = 0; k < value.double_array_value->size; k++) { - Nan::Set(dbl_array, k, - Nan::New( - value.double_array_value - ->values[k])); // NOLINT(whitespace/line_length) + dbl_array.Set( + k, Napi::Number::New(env, value.double_array_value->values[k])); } - Nan::Set(parameter, Nan::New("value").ToLocalChecked(), dbl_array); + parameter.Set("value", dbl_array); } - Nan::Set(parameter, Nan::New("type").ToLocalChecked(), - Nan::New(param_type)); - Nan::Set(parameters, j, parameter); + parameter.Set("type", Napi::Number::New(env, param_type)); + parameters.Set(j, parameter); } - Nan::Set(node, Nan::New("parameters").ToLocalChecked(), parameters); - Nan::Set(nodes, i, node); + node.Set("parameters", parameters); + nodes.Set(i, node); } 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()); +Napi::Value CreateNode(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + std::string node_name = info[0].As().Utf8Value(); + std::string name_space = info[1].As().Utf8Value(); + RclHandle* context_handle = RclHandle::Unwrap(info[2].As()); rcl_context_t* context = reinterpret_cast(context_handle->ptr()); @@ -267,18 +264,20 @@ NAN_METHOD(CreateNode) { name_space.c_str(), context, &options), rcl_get_error_string().str); - auto handle = RclHandle::NewInstance(node, nullptr, [](void* ptr) { + 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); }); - info.GetReturnValue().Set(handle); + + return 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,39 +292,47 @@ 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; + + if (!info[2].IsBigInt()) { + 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(); + + bool lossless; + int64_t period_nsec = info[2].As().Int64Value(&lossless); rcl_timer_t* timer = reinterpret_cast(malloc(sizeof(rcl_timer_t))); *timer = rcl_get_zero_initialized_timer(); @@ -343,48 +350,57 @@ 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 +408,25 @@ 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; @@ -414,14 +434,13 @@ NAN_METHOD(TimerGetTimeUntilNextCall) { RCL_RET_OK, rcl_timer_get_time_until_next_call(timer, &remaining_time), rcl_get_error_string().str); - v8::Local bigInt = - v8::BigInt::New(v8::Isolate::GetCurrent(), remaining_time); - info.GetReturnValue().Set(bigInt); + return Napi::BigInt::New(env, remaining_time); } -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; @@ -429,71 +448,80 @@ NAN_METHOD(TimerGetTimeSinceLastCall) { RCL_RET_OK, rcl_timer_get_time_since_last_call(timer, &elapsed_time), rcl_get_error_string().str); - v8::Local bigInt = - v8::BigInt::New(v8::Isolate::GetCurrent(), elapsed_time); - info.GetReturnValue().Set(bigInt); + return Napi::BigInt::New(env, elapsed_time); } -NAN_METHOD(CreateTimePoint) { - if (!info[0]->IsBigInt()) { - Nan::ThrowTypeError("Timer period must be a BigInt"); - return; +Napi::Value CreateTimePoint(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + if (!info[0].IsBigInt()) { + 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(); + + bool lossless; + int64_t nanoseconds = info[0].As().Int64Value(&lossless); + uint32_t clock_type = info[1].As().Uint32Value(); rcl_time_point_t* time_point = reinterpret_cast(malloc(sizeof(rcl_time_point_t))); time_point->nanoseconds = nanoseconds; 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); + auto 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 Napi::BigInt::New(env, time_point->nanoseconds); } -NAN_METHOD(CreateDuration) { - if (!info[0]->IsBigInt()) { - Nan::ThrowTypeError("Timer period must be a BigInt"); - return; +Napi::Value CreateDuration(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + if (!info[0].IsBigInt()) { + 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(); + + bool lossless; + int64_t nanoseconds = info[0].As().Int64Value(&lossless); rcl_duration_t* duration = reinterpret_cast(malloc(sizeof(rcl_duration_t))); duration->nanoseconds = nanoseconds; - auto js_obj = - RclHandle::NewInstance(duration, nullptr, [](void* ptr) { free(ptr); }); - info.GetReturnValue().Set(js_obj); + auto 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 Napi::BigInt::New(env, duration->nanoseconds); } -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(); if (enabled) { THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_enable_ros_time_override(clock), @@ -502,39 +530,45 @@ 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,69 +577,64 @@ 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); - })); + return 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); + }); } -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; THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_clock_get_now(clock, &time_point.nanoseconds), rcl_get_error_string().str); - v8::Local bigInt = - v8::BigInt::New(v8::Isolate::GetCurrent(), time_point.nanoseconds); - info.GetReturnValue().Set(bigInt); + + return Napi::BigInt::New(env, time_point.nanoseconds); } -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()); + void* msg_taken = info[1].As>().Data(); 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); rcl_reset_error(); - info.GetReturnValue().Set(Nan::False()); - return; + Napi::Error::New(env, rcl_get_error_string().str) + .ThrowAsJavaScriptException(); + return Napi::Boolean::New(env, false); } 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())); - std::string message_sub_folder( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); - std::string message_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); - std::string topic( - *Nan::Utf8String(info[4]->ToString(currentContent).ToLocalChecked())); - v8::Local options = - info[5]->ToObject(currentContent).ToLocalChecked(); + + std::string package_name = info[1].As().Utf8Value(); + std::string message_sub_folder = info[2].As().Utf8Value(); + std::string message_name = info[3].As().Utf8Value(); + std::string topic = info[4].As().Utf8Value(); + Napi::Object options = info[5].As(); rcl_subscription_t* subscription = reinterpret_cast(malloc(sizeof(rcl_subscription_t))); @@ -614,51 +643,38 @@ NAN_METHOD(CreateSubscription) { rcl_subscription_options_t subscription_ops = rcl_subscription_get_default_options(); - v8::Local qos = - Nan::Get(options, Nan::New("qos").ToLocalChecked()).ToLocalChecked(); + Napi::Value qos = options.Get("qos"); auto qos_profile = GetQoSProfile(qos); if (qos_profile) { subscription_ops.qos = *qos_profile; } #if ROS_VERSION >= 2205 // 2205 => Humble+ - if (Nan::Has(options, Nan::New("contentFilter").ToLocalChecked()) - .FromMaybe(false)) { + if (options.Has("contentFilter")) { // configure content-filter - v8::MaybeLocal contentFilterVal = - Nan::Get(options, Nan::New("contentFilter").ToLocalChecked()); + Napi::Value contentFilterVal = options.Get("contentFilter"); - if (!Nan::Equals(contentFilterVal.ToLocalChecked(), Nan::Undefined()) - .ToChecked()) { - v8::Local contentFilter = contentFilterVal.ToLocalChecked() - ->ToObject(currentContent) - .ToLocalChecked(); + if (!contentFilterVal.IsUndefined()) { + Napi::Object contentFilter = contentFilterVal.As(); // expression property is required - std::string expression(*Nan::Utf8String( - Nan::Get(contentFilter, Nan::New("expression").ToLocalChecked()) - .ToLocalChecked() - ->ToString(currentContent) - .ToLocalChecked())); + std::string expression = + contentFilter.Get("expression").As().Utf8Value(); // parameters property (string[]) is optional int argc = 0; char** argv = nullptr; - if (Nan::Has(contentFilter, Nan::New("parameters").ToLocalChecked()) - .FromMaybe(false)) { - v8::Local jsArgv = v8::Local::Cast( - Nan::Get(contentFilter, Nan::New("parameters").ToLocalChecked()) - .ToLocalChecked()); - argc = jsArgv->Length(); + if (contentFilter.Has("parameters")) { + Napi::Array jsArgv = contentFilter.Get("parameters").As(); + argc = jsArgv.Length(); 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; + std::string arg = jsArgv.Get(i).As().Utf8Value(); + int len = arg.length() + 1; argv[i] = reinterpret_cast(malloc(len * sizeof(char*))); - snprintf(argv[i], len, "%s", *utf8_arg); + snprintf(argv[i], len, "%s", arg.c_str()); } } } @@ -667,8 +683,9 @@ NAN_METHOD(CreateSubscription) { expression.c_str(), argc, (const char**)argv, &subscription_ops); if (ret != RCL_RET_OK) { - Nan::ThrowError(rcl_get_error_string().str); rcl_reset_error(); + Napi::Error::New(env, rcl_get_error_string().str) + .ThrowAsJavaScriptException(); } if (argc) { @@ -679,7 +696,6 @@ NAN_METHOD(CreateSubscription) { } } } - #endif const rosidl_message_type_support_t* ts = @@ -692,74 +708,69 @@ NAN_METHOD(CreateSubscription) { &subscription_ops), rcl_get_error_string().str); - auto js_obj = - RclHandle::NewInstance(subscription, node_handle, [node](void* ptr) { + auto js_obj = 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()) + .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()); + Napi::Env env = info.Env(); + + RclHandle* subscription_handle = + RclHandle::Unwrap(info[0].As()); rcl_subscription_t* subscription = reinterpret_cast(subscription_handle->ptr()); - v8::Local contentFilter = - info[1]->ToObject(currentContext).ToLocalChecked(); + Napi::Object contentFilter = info[1].As(); - 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 = + contentFilter.Get("expression").As().Utf8Value(); // parameters property (string[]) is optional int argc = 0; char** argv = nullptr; - if (Nan::Has(contentFilter, Nan::New("parameters").ToLocalChecked()) - .FromMaybe(false)) { - v8::Local jsArgv = v8::Local::Cast( - Nan::Get(contentFilter, Nan::New("parameters").ToLocalChecked()) - .ToLocalChecked()); - argc = jsArgv->Length(); + if (contentFilter.Has("parameters")) { + Napi::Array jsArgv = contentFilter.Get("parameters").As(); + argc = jsArgv.Length(); 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; + std::string arg = jsArgv.Get(i).As().Utf8Value(); + int len = arg.length() + 1; argv[i] = reinterpret_cast(malloc(len * sizeof(char*))); - snprintf(argv[i], len, "%s", *utf8_arg); + snprintf(argv[i], len, "%s", arg.c_str()); } } } @@ -768,37 +779,35 @@ NAN_METHOD(SetContentFilter) { rcl_subscription_content_filter_options_t options = rcl_get_zero_initialized_subscription_content_filter_options(); - THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, - rcl_subscription_content_filter_options_set( - subscription, - expression, // expression.c_str(), - argc, (const char**)argv, &options), - rcl_get_error_string().str); + THROW_ERROR_IF_NOT_EQUAL( + RCL_RET_OK, + rcl_subscription_content_filter_options_set( + subscription, expression.c_str(), argc, (const char**)argv, &options), + rcl_get_error_string().str); THROW_ERROR_IF_NOT_EQUAL( RCL_RET_OK, rcl_subscription_set_content_filter(subscription, &options), rcl_get_error_string().str); if (argc) { - free(expression); - for (int i = 0; i < argc; i++) { free(argv[i]); } 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,36 +825,29 @@ NAN_METHOD(ClearContentFilter) { RCL_RET_OK, rcl_subscription_set_content_filter(subscription, &options), rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::True()); + return Napi::Boolean::New(env, true); #endif } -NAN_METHOD(CreatePublisher) { - v8::Local currentContent = Nan::GetCurrentContext(); - // Extract arguments - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CreatePublisher(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())); - std::string message_sub_folder( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); - std::string message_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); - std::string topic( - *Nan::Utf8String(info[4]->ToString(currentContent).ToLocalChecked())); - - // Prepare publisher object + + std::string package_name = info[1].As().Utf8Value(); + std::string message_sub_folder = info[2].As().Utf8Value(); + std::string message_name = info[3].As().Utf8Value(); + std::string topic = info[4].As().Utf8Value(); + rcl_publisher_t* publisher = reinterpret_cast(malloc(sizeof(rcl_publisher_t))); *publisher = rcl_get_zero_initialized_publisher(); - // Get type support object dynamically const rosidl_message_type_support_t* ts = GetMessageTypeSupport(package_name, message_sub_folder, message_name); if (ts) { - // Using default options rcl_publisher_options_t publisher_ops = rcl_publisher_get_default_options(); auto qos_profile = GetQoSProfile(info[5]); @@ -853,72 +855,68 @@ NAN_METHOD(CreatePublisher) { publisher_ops.qos = *qos_profile; } - // Initialize the publisher THROW_ERROR_IF_NOT_EQUAL( rcl_publisher_init(publisher, node, ts, topic.c_str(), &publisher_ops), RCL_RET_OK, rcl_get_error_string().str); - // 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); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, ret, rcl_get_error_string().str); }); - // Everything is done - 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(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()); + void* buffer = info[1].As>().Data(); 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())); - std::string interface_name( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); - std::string package_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); + + std::string service_name = info[1].As().Utf8Value(); + std::string interface_name = info[2].As().Utf8Value(); + std::string package_name = info[3].As().Utf8Value(); const rosidl_service_type_support_t* ts = GetServiceTypeSupport(package_name, interface_name); @@ -939,67 +937,63 @@ 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()) + .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()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + RclHandle::Unwrap(info[0].As())->ptr()); + char* buffer = info[1].As>().Data(); 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()); + void* taken_response = info[1].As>().Data(); 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())); - std::string interface_name( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); - std::string package_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); + + std::string service_name = info[1].As().Utf8Value(); + std::string interface_name = info[2].As().Utf8Value(); + std::string package_name = info[3].As().Utf8Value(); const rosidl_service_type_support_t* ts = GetServiceTypeSupport(package_name, interface_name); @@ -1010,83 +1004,75 @@ NAN_METHOD(CreateService) { *service = rcl_get_zero_initialized_service(); rcl_service_options_t service_ops = rcl_service_get_default_options(); auto qos_profile = GetQoSProfile(info[4]); - if (qos_profile) { service_ops.qos = *qos_profile; } - THROW_ERROR_IF_NOT_EQUAL( 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()) + .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()); + void* taken_request = info[2].As>().Data(); 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; + auto js_obj = 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()); - void* buffer = - node::Buffer::Data(Nan::To(info[1]).ToLocalChecked()); + RclHandle::Unwrap(info[0].As())->ptr()); + void* buffer = info[1].As>().Data(); 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()); - - std::string interface_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); - std::string package_name( - *Nan::Utf8String(info[4]->ToString(currentContent).ToLocalChecked())); + RclHandle::Unwrap(info[2].As())->ptr()); + + std::string interface_name = info[3].As().Utf8Value(); + std::string package_name = info[4].As().Utf8Value(); const rosidl_service_type_support_t* ts = GetServiceTypeSupport(package_name, interface_name); @@ -1099,13 +1085,12 @@ NAN_METHOD(ConfigureServiceIntrospection) { rcl_service_introspection_state_t state = static_cast( - Nan::To(info[6]).ToChecked()); + info[6].As().Uint32Value()); - bool configureForService = Nan::To(info[7]).FromJust(); + bool configureForService = info[7].As(); 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 +1100,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 +1111,160 @@ NAN_METHOD(ConfigureServiceIntrospection) { } } else { - Nan::ThrowError(GetErrorMessageAndClear().c_str()); + Napi::Error::New(env, GetErrorMessageAndClear()) + .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())); + std::string topic_name = info[0].As().Utf8Value(); 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); - Nan::Set( - result_list, 0, - Nan::New(std::string(validation_message)).ToLocalChecked()); - Nan::Set(result_list, 1, Nan::New(static_cast(invalid_index))); + Napi::Array result_list = Napi::Array::New(env, 2); + result_list.Set(static_cast(0), + Napi::String::New(env, std::string(validation_message))); + result_list.Set(static_cast(1), + Napi::Number::New(env, 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())); + std::string node_name = info[0].As().Utf8Value(); 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); - Nan::Set( - result_list, 0, - Nan::New(std::string(validation_message)).ToLocalChecked()); - Nan::Set(result_list, 1, Nan::New(static_cast(invalid_index))); + Napi::Array result_list = Napi::Array::New(env, 2); + result_list.Set(static_cast(0), + Napi::String::New(env, std::string(validation_message))); + result_list.Set(static_cast(1), + Napi::Number::New(env, 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())); + std::string topic_name = info[0].As().Utf8Value(); 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); - Nan::Set( - result_list, 0, - Nan::New(std::string(validation_message)).ToLocalChecked()); - Nan::Set(result_list, 1, Nan::New(static_cast(invalid_index))); + Napi::Array result_list = Napi::Array::New(env, 2); + result_list.Set(static_cast(0), + Napi::String::New(env, std::string(validation_message))); + result_list.Set(static_cast(1), + Napi::Number::New(env, 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())); + std::string namespace_name = info[0].As().Utf8Value(); 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); - Nan::Set( - result_list, 0, - Nan::New(std::string(validation_message)).ToLocalChecked()); - Nan::Set(result_list, 1, Nan::New(static_cast(invalid_index))); + Napi::Array result_list = Napi::Array::New(env, 2); + result_list.Set(static_cast(0), + Napi::String::New(env, std::string(validation_message))); + result_list.Set(static_cast(1), + Napi::Number::New(env, static_cast(invalid_index))); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(ExpandTopicName) { - v8::Local currentContent = Nan::GetCurrentContext(); - std::string topic_name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); - std::string node_name( - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked())); - std::string node_namespace( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); +Napi::Value ExpandTopicName(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + std::string topic_name = info[0].As().Utf8Value(); + std::string node_name = info[1].As().Utf8Value(); + std::string node_namespace = info[2].As().Utf8Value(); char* expanded_topic = nullptr; rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -1291,26 +1276,29 @@ 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); + rcl_reset_error(); + 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) { + rcl_reset_error(); + 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); rcutils_reset_error(); + Napi::Error::New(env, rcutils_get_error_string().str) + .ThrowAsJavaScriptException(); } - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } ret = rcl_expand_topic_name(topic_name.c_str(), node_name.c_str(), @@ -1319,52 +1307,52 @@ 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); rcl_reset_error(); - info.GetReturnValue().Set(Nan::Undefined()); - return; + Napi::Error::New(env, rcl_get_error_string().str) + .ThrowAsJavaScriptException(); + 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); } } @@ -1390,59 +1378,51 @@ const rmw_qos_profile_t* GetQoSProfileFromString(const std::string& profile) { } std::unique_ptr GetQosProfileFromObject( - v8::Local object) { + Napi::Object object) { std::unique_ptr qos_profile = std::make_unique(); - auto history = - Nan::Get(object, Nan::New("history").ToLocalChecked()).ToLocalChecked(); - auto depth = - Nan::Get(object, Nan::New("depth").ToLocalChecked()).ToLocalChecked(); - auto reliability = Nan::Get(object, Nan::New("reliability").ToLocalChecked()) - .ToLocalChecked(); - auto durability = Nan::Get(object, Nan::New("durability").ToLocalChecked()) - .ToLocalChecked(); + auto history = object.Get("history"); + auto depth = object.Get("depth"); + auto reliability = object.Get("reliability"); + auto durability = object.Get("durability"); auto avoid_ros_namespace_conventions = - Nan::Get(object, - Nan::New("avoidRosNameSpaceConventions").ToLocalChecked()) - .ToLocalChecked(); + object.Get("avoidRosNameSpaceConventions"); qos_profile->history = static_cast( - Nan::To(history).FromJust()); - qos_profile->depth = Nan::To(depth).FromJust(); + history.As().Uint32Value()); + qos_profile->depth = depth.As().Uint32Value(); qos_profile->reliability = static_cast( - Nan::To(reliability).FromJust()); + reliability.As().Uint32Value()); qos_profile->durability = static_cast( - Nan::To(durability).FromJust()); + durability.As().Uint32Value()); qos_profile->avoid_ros_namespace_conventions = - Nan::To(avoid_ros_namespace_conventions).FromJust(); + avoid_ros_namespace_conventions.As(); return qos_profile; } -std::unique_ptr GetQoSProfile(v8::Local qos) { - v8::Local currentContent = Nan::GetCurrentContext(); +std::unique_ptr GetQoSProfile(Napi::Value qos) { std::unique_ptr qos_profile = std::make_unique(); - if (qos->IsString()) { - *qos_profile = *GetQoSProfileFromString(std::string( - *Nan::Utf8String(qos->ToString(currentContent).ToLocalChecked()))); - } else if (qos->IsObject()) { - qos_profile = - GetQosProfileFromObject(Nan::To(qos).ToLocalChecked()); + if (qos.IsString()) { + *qos_profile = *GetQoSProfileFromString(qos.As().Utf8Value()); + } else if (qos.IsObject()) { + qos_profile = GetQosProfileFromObject(qos.As()); } else { return qos_profile; } return qos_profile; } -int DestroyContext(rcl_context_t* context) { +int DestroyContext(Napi::Env env, rcl_context_t* context) { rcl_ret_t ret = RCL_RET_OK; 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(env, rcl_get_error_string().str) + .ThrowAsJavaScriptException(); } ret = rcl_context_fini(context); } @@ -1450,9 +1430,10 @@ 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 +1441,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) { - void* buffer = - node::Buffer::Data(Nan::To(info[0]).ToLocalChecked()); +Napi::Value InitString(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + void* buffer = info[0].As>().Data(); #if ROS_VERSION >= 2006 rosidl_runtime_c__String* ptr = reinterpret_cast(buffer); @@ -1477,124 +1459,118 @@ 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()); +inline char* GetBufAddr(Napi::Value buf) { + return buf.As>().Data(); } -NAN_METHOD(FreeMemeoryAtOffset) { - v8::Local currentContent = Nan::GetCurrentContext(); - std::string addr_str( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); +Napi::Value FreeMemeoryAtOffset(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + std::string addr_str = info[0].As().Utf8Value(); 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(); - std::string addr_str( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); +Napi::Value CreateArrayBufferFromAddress(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + std::string addr_str = info[0].As().Utf8Value(); 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) // Because V8 sandboxed pointers was enabled since Electron 21, we have to // make a deep copy for Electron 21 and up. // See more details: https://www.electronjs.org/blog/v8-memory-cage - v8::Local array_buffer = - v8::ArrayBuffer::New(v8::Isolate::GetCurrent(), length); - memcpy(array_buffer->Data(), addr, length); + Napi::ArrayBuffer array_buffer = Napi::ArrayBuffer::New(env, length); + memcpy(array_buffer.Data(), addr, length); free(addr); #else - // For nodejs > 12 or electron < 21, we will create a new `BackingStore` and - // take over the ownership of `addr`. - std::unique_ptr backing = v8::ArrayBuffer::NewBackingStore( - addr, length, - [](void* data, size_t length, void* deleter_data) { free(data); }, - nullptr); - auto array_buffer = - v8::ArrayBuffer::New(v8::Isolate::GetCurrent(), std::move(backing)); + // For nodejs > 12 or electron < 21, we will take over the ownership of + // `addr`. + auto array_buffer = Napi::ArrayBuffer::New( + env, addr, length, [](Napi::Env /*env*/, void* data) { free(data); }); #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(); - std::string name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); - int level = Nan::To(info[1]).FromJust(); +Napi::Value setLoggerLevel(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + std::string name = info[0].As().Utf8Value(); + int level = info[1].As().Int64Value(); 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(); - std::string name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); +Napi::Value GetLoggerEffectiveLevel(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + std::string name = info[0].As().Utf8Value(); 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()); -} - -NAN_METHOD(Log) { - v8::Local currentContent = Nan::GetCurrentContext(); - std::string name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); - int severity = Nan::To(info[1]).FromJust(); - std::string message( - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked())); - std::string function_name( - *Nan::Utf8String(info[3]->ToString(currentContent).ToLocalChecked())); - size_t line_number = Nan::To(info[4]).FromJust(); - std::string file_name( - *Nan::Utf8String(info[5]->ToString(currentContent).ToLocalChecked())); + return Napi::String::New(env, node_logger_name); +} + +Napi::Value Log(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + std::string name = info[0].As().Utf8Value(); + int severity = info[1].As().Int64Value(); + std::string message = info[2].As().Utf8Value(); + std::string function_name = info[3].As().Utf8Value(); + size_t line_number = info[4].As().Int64Value(); + std::string file_name = info[5].As().Utf8Value(); bool enabled = rcutils_logging_logger_is_enabled_for(name.c_str(), severity); if (enabled) { @@ -1604,70 +1580,73 @@ 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(); - std::string name( - *Nan::Utf8String(info[0]->ToString(currentContent).ToLocalChecked())); - int severity = Nan::To(info[1]).FromJust(); +Napi::Value IsEnableFor(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + std::string name = info[0].As().Utf8Value(); + int severity = info[1].As().Int64Value(); 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) { - 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); - }); + auto js_obj = + RclHandle::NewInstance(env, context, nullptr, [&env](void* ptr) { + rcl_context_t* context = reinterpret_cast(ptr); + rcl_ret_t ret = DestroyContext(env, context); + 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(IsContextValid) { - RclHandle* context_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value IsContextValid(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()); bool is_valid = rcl_context_is_valid(context); - info.GetReturnValue().Set(Nan::New(is_valid)); + return Napi::Boolean::New(env, is_valid); } void ExtractNamesAndTypes(rcl_names_and_types_t names_and_types, - v8::Local* result_list) { + Napi::Array* result_list) { + Napi::Env env = result_list->Env(); + for (size_t i = 0; i < names_and_types.names.size; ++i) { - auto item = v8::Object::New(v8::Isolate::GetCurrent()); + Napi::Object item = Napi::Object::New(env); std::string topic_name = names_and_types.names.data[i]; - Nan::Set(item, Nan::New("name").ToLocalChecked(), - Nan::New(names_and_types.names.data[i]).ToLocalChecked()); + item.Set("name", Napi::String::New(env, names_and_types.names.data[i])); - v8::Local type_list = - Nan::New(names_and_types.types[i].size); + Napi::Array type_list = + Napi::Array::New(env, names_and_types.types[i].size); for (size_t j = 0; j < names_and_types.types[i].size; ++j) { - Nan::Set(type_list, j, - Nan::New(names_and_types.types[i].data[j]).ToLocalChecked()); + type_list.Set(j, + Napi::String::New(env, names_and_types.types[i].data[j])); } - Nan::Set(item, Nan::New("types").ToLocalChecked(), type_list); - Nan::Set(*result_list, i, item); + item.Set("types", type_list); + result_list->Set(i, item); } } -NAN_METHOD(GetPublisherNamesAndTypesByNode) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetPublisherNamesAndTypesByNode(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()); - std::string node_namespace = - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked()); - bool no_demangle = Nan::To(info[3]).FromJust(); + std::string node_name = info[1].As().Utf8Value(); + std::string node_namespace = info[2].As().Utf8Value(); + bool no_demangle = info[3].As(); rcl_names_and_types_t topic_names_and_types = rcl_get_zero_initialized_names_and_types(); @@ -1678,27 +1657,25 @@ NAN_METHOD(GetPublisherNamesAndTypesByNode) { node_namespace.c_str(), &topic_names_and_types), "Failed to get_publisher_names_and_types."); - v8::Local result_list = - Nan::New(topic_names_and_types.names.size); + Napi::Array result_list = + Napi::Array::New(env, topic_names_and_types.names.size); ExtractNamesAndTypes(topic_names_and_types, &result_list); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_names_and_types_fini(&topic_names_and_types), "Failed to destroy topic_names_and_types"); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(GetSubscriptionNamesAndTypesByNode) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetSubscriptionNamesAndTypesByNode(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()); - std::string node_namespace = - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked()); - bool no_demangle = Nan::To(info[3]).FromJust(); + std::string node_name = info[1].As().Utf8Value(); + std::string node_namespace = info[2].As().Utf8Value(); + bool no_demangle = info[3].As(); rcl_names_and_types_t topic_names_and_types = rcl_get_zero_initialized_names_and_types(); @@ -1709,26 +1686,24 @@ NAN_METHOD(GetSubscriptionNamesAndTypesByNode) { node_namespace.c_str(), &topic_names_and_types), "Failed to get_publisher_names_and_types."); - v8::Local result_list = - Nan::New(topic_names_and_types.names.size); + Napi::Array result_list = + Napi::Array::New(env, topic_names_and_types.names.size); ExtractNamesAndTypes(topic_names_and_types, &result_list); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_names_and_types_fini(&topic_names_and_types), "Failed to destroy topic_names_and_types"); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(GetServiceNamesAndTypesByNode) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetServiceNamesAndTypesByNode(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()); - std::string node_namespace = - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked()); + std::string node_name = info[1].As().Utf8Value(); + std::string node_namespace = info[2].As().Utf8Value(); rcl_names_and_types_t service_names_and_types = rcl_get_zero_initialized_names_and_types(); @@ -1740,26 +1715,24 @@ NAN_METHOD(GetServiceNamesAndTypesByNode) { &service_names_and_types), "Failed to get_service_names_and_types."); - v8::Local result_list = - Nan::New(service_names_and_types.names.size); + Napi::Array result_list = + Napi::Array::New(env, service_names_and_types.names.size); ExtractNamesAndTypes(service_names_and_types, &result_list); THROW_ERROR_IF_NOT_EQUAL( RCL_RET_OK, rcl_names_and_types_fini(&service_names_and_types), "Failed to destroy rcl_get_zero_initialized_names_and_types"); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(GetClientNamesAndTypesByNode) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetClientNamesAndTypesByNode(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()); - std::string node_namespace = - *Nan::Utf8String(info[2]->ToString(currentContent).ToLocalChecked()); + std::string node_name = info[1].As().Utf8Value(); + std::string node_namespace = info[2].As().Utf8Value(); rcl_names_and_types_t client_names_and_types = rcl_get_zero_initialized_names_and_types(); @@ -1770,22 +1743,23 @@ NAN_METHOD(GetClientNamesAndTypesByNode) { node_namespace.c_str(), &client_names_and_types), "Failed to get_client_names_and_types."); - v8::Local result_list = - Nan::New(client_names_and_types.names.size); + Napi::Array result_list = + Napi::Array::New(env, client_names_and_types.names.size); ExtractNamesAndTypes(client_names_and_types, &result_list); THROW_ERROR_IF_NOT_EQUAL( RCL_RET_OK, rcl_names_and_types_fini(&client_names_and_types), "Failed to destroy rcl_get_zero_initialized_names_and_types"); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(GetTopicNamesAndTypes) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetTopicNamesAndTypes(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()); - bool no_demangle = Nan::To(info[1]).FromJust(); + bool no_demangle = info[1].As(); rcl_names_and_types_t topic_names_and_types = rcl_get_zero_initialized_names_and_types(); rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -1796,20 +1770,21 @@ NAN_METHOD(GetTopicNamesAndTypes) { &topic_names_and_types), "Failed to get_publisher_names_and_types."); - v8::Local result_list = - Nan::New(topic_names_and_types.names.size); + Napi::Array result_list = + Napi::Array::New(env, topic_names_and_types.names.size); ExtractNamesAndTypes(topic_names_and_types, &result_list); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_names_and_types_fini(&topic_names_and_types), "Failed to destroy topic_names_and_types"); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(GetServiceNamesAndTypes) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetServiceNamesAndTypes(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()); rcl_names_and_types_t service_names_and_types = rcl_get_zero_initialized_names_and_types(); @@ -1820,20 +1795,21 @@ NAN_METHOD(GetServiceNamesAndTypes) { node, &allocator, &service_names_and_types), "Failed to get_publisher_names_and_types."); - v8::Local result_list = - Nan::New(service_names_and_types.names.size); + Napi::Array result_list = + Napi::Array::New(env, service_names_and_types.names.size); ExtractNamesAndTypes(service_names_and_types, &result_list); THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, rcl_names_and_types_fini(&service_names_and_types), "Failed to destroy topic_names_and_types"); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(GetNodeNames) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetNodeNames(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()); rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array(); @@ -1846,17 +1822,15 @@ NAN_METHOD(GetNodeNames) { rcl_get_node_names(node, allocator, &node_names, &node_namespaces), "Failed to get_node_names."); - v8::Local result_list = Nan::New(node_names.size); + Napi::Array result_list = Napi::Array::New(env, node_names.size); for (size_t i = 0; i < node_names.size; ++i) { - auto item = v8::Object::New(v8::Isolate::GetCurrent()); + Napi::Object item = Napi::Object::New(env); - Nan::Set(item, Nan::New("name").ToLocalChecked(), - Nan::New(node_names.data[i]).ToLocalChecked()); - Nan::Set(item, Nan::New("namespace").ToLocalChecked(), - Nan::New(node_namespaces.data[i]).ToLocalChecked()); + item.Set("name", Napi::String::New(env, node_names.data[i])); + item.Set("namespace", Napi::String::New(env, node_namespaces.data[i])); - Nan::Set(result_list, i, item); + result_list.Set(i, item); } rcutils_ret_t fini_names_ret = rcutils_string_array_fini(&node_names); @@ -1868,51 +1842,45 @@ NAN_METHOD(GetNodeNames) { THROW_ERROR_IF_NOT_EQUAL(RCL_RET_OK, fini_namespaces_ret, "Failed to destroy node_namespaces"); - info.GetReturnValue().Set(result_list); + return result_list; } -NAN_METHOD(CountPublishers) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CountPublishers(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 topic_name = - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked()); + std::string topic_name = info[1].As().Utf8Value(); size_t count = 0; THROW_ERROR_IF_NOT_EQUAL( RCL_RET_OK, rcl_count_publishers(node, topic_name.c_str(), &count), "Failed to count publishers."); - v8::Local result = - Nan::New(static_cast(count)); - info.GetReturnValue().Set(result); + return Napi::Number::New(env, static_cast(count)); } -NAN_METHOD(CountSubscribers) { - v8::Local currentContent = Nan::GetCurrentContext(); - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CountSubscribers(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 topic_name = - *Nan::Utf8String(info[1]->ToString(currentContent).ToLocalChecked()); + std::string topic_name = info[1].As().Utf8Value(); size_t count = 0; THROW_ERROR_IF_NOT_EQUAL( RCL_RET_OK, rcl_count_subscribers(node, topic_name.c_str(), &count), "Failed to count subscribers."); - v8::Local result = - Nan::New(static_cast(count)); - info.GetReturnValue().Set(result); + return Napi::Number::New(env, static_cast(count)); } -NAN_METHOD(ServiceServerIsAvailable) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value ServiceServerIsAvailable(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()); - RclHandle* client_handle = RclHandle::Unwrap( - Nan::To(info[1]).ToLocalChecked()); + RclHandle* client_handle = RclHandle::Unwrap(info[1].As()); rcl_client_t* client = reinterpret_cast(client_handle->ptr()); bool is_available; @@ -1920,34 +1888,34 @@ NAN_METHOD(ServiceServerIsAvailable) { RCL_RET_OK, rcl_service_server_is_available(node, client, &is_available), "Failed to get service state."); - v8::Local result = Nan::New(is_available); - info.GetReturnValue().Set(result); + return Napi::Boolean::New(env, is_available); } -NAN_METHOD(PublishRawMessage) { +Napi::Value PublishRawMessage(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()); - auto object = Nan::To(info[1]).ToLocalChecked(); + auto object = info[1].As>(); rcl_serialized_message_t serialized_msg = rmw_get_zero_initialized_serialized_message(); - serialized_msg.buffer_capacity = node::Buffer::Length(object); + serialized_msg.buffer_capacity = object.Length(); serialized_msg.buffer_length = serialized_msg.buffer_capacity; - serialized_msg.buffer = - reinterpret_cast(node::Buffer::Data(object)); + serialized_msg.buffer = reinterpret_cast(object.Data()); THROW_ERROR_IF_NOT_EQUAL( rcl_publish_serialized_message(publisher, &serialized_msg, nullptr), RCL_RET_OK, rcl_get_error_string().str); - info.GetReturnValue().Set(Nan::Undefined()); + return env.Undefined(); } -NAN_METHOD(RclTakeRaw) { - RclHandle* subscription_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value RclTakeRaw(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()); @@ -1957,128 +1925,154 @@ NAN_METHOD(RclTakeRaw) { if (ret != RCL_RET_OK) { THROW_ERROR_IF_NOT_EQUAL(rmw_serialized_message_fini(&msg), RCL_RET_OK, "Failed to deallocate message buffer."); - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } ret = rcl_take_serialized_message(subscription, &msg, nullptr, nullptr); if (ret != RCL_RET_OK && ret != RCL_RET_SUBSCRIPTION_TAKE_FAILED) { rcl_reset_error(); THROW_ERROR_IF_NOT_EQUAL(rmw_serialized_message_fini(&msg), RCL_RET_OK, "Failed to deallocate message buffer."); - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } if (ret == RCL_RET_SUBSCRIPTION_TAKE_FAILED) { THROW_ERROR_IF_NOT_EQUAL(rmw_serialized_message_fini(&msg), RCL_RET_OK, "Failed to deallocate message buffer."); - info.GetReturnValue().Set(Nan::Undefined()); - return; + return env.Undefined(); } - info.GetReturnValue().Set( - Nan::CopyBuffer(reinterpret_cast(msg.buffer), msg.buffer_length) - .ToLocalChecked()); + Napi::Buffer buffer = Napi::Buffer::Copy( + env, reinterpret_cast(msg.buffer), msg.buffer_length); THROW_ERROR_IF_NOT_EQUAL(rmw_serialized_message_fini(&msg), RCL_RET_OK, "Failed to deallocate message buffer"); + return buffer; } -NAN_METHOD(GetClientServiceName) { +Napi::Value GetClientServiceName(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()); const char* service_name = rcl_client_get_service_name(client); - info.GetReturnValue().Set(Nan::New(service_name).ToLocalChecked()); + return Napi::String::New(env, service_name); } -NAN_METHOD(GetServiceServiceName) { +Napi::Value GetServiceServiceName(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()); const char* service_name = rcl_service_get_service_name(service); - info.GetReturnValue().Set(Nan::New(service_name).ToLocalChecked()); -} - -std::vector binding_methods = { - {"init", Init}, - {"createNode", CreateNode}, - {"getParameterOverrides", GetParameterOverrides}, - {"createGuardCondition", CreateGuardCondition}, - {"triggerGuardCondition", TriggerGuardCondition}, - {"createTimer", CreateTimer}, - {"isTimerReady", IsTimerReady}, - {"callTimer", CallTimer}, - {"cancelTimer", CancelTimer}, - {"isTimerCanceled", IsTimerCanceled}, - {"resetTimer", ResetTimer}, - {"timerGetTimeSinceLastCall", TimerGetTimeSinceLastCall}, - {"timerGetTimeUntilNextCall", TimerGetTimeUntilNextCall}, - {"createClock", CreateClock}, - {"clockGetNow", ClockGetNow}, - {"createTimePoint", CreateTimePoint}, - {"getNanoseconds", GetNanoseconds}, - {"createDuration", CreateDuration}, - {"getDurationNanoseconds", GetDurationNanoseconds}, - {"setRosTimeOverrideIsEnabled", SetRosTimeOverrideIsEnabled}, - {"setRosTimeOverride", SetRosTimeOverride}, - {"getRosTimeOverrideIsEnabled", GetRosTimeOverrideIsEnabled}, - {"rclTake", RclTake}, - {"createSubscription", CreateSubscription}, - {"hasContentFilter", HasContentFilter}, - {"setContentFilter", SetContentFilter}, - {"clearContentFilter", ClearContentFilter}, - {"createPublisher", CreatePublisher}, - {"publish", Publish}, - {"getPublisherTopic", GetPublisherTopic}, - {"getSubscriptionTopic", GetSubscriptionTopic}, - {"createClient", CreateClient}, - {"rclTakeResponse", RclTakeResponse}, - {"sendRequest", SendRequest}, - {"createService", CreateService}, - {"rclTakeRequest", RclTakeRequest}, - {"sendResponse", SendResponse}, - {"shutdown", Shutdown}, - {"validateFullTopicName", ValidateFullTopicName}, - {"validateNodeName", ValidateNodeName}, - {"validateTopicName", ValidateTopicName}, - {"validateNamespace", ValidateNamespace}, - {"expandTopicName", ExpandTopicName}, - {"getNodeName", GetNodeName}, - {"getNamespace", GetNamespace}, - {"initString", InitString}, - {"freeMemeoryAtOffset", FreeMemeoryAtOffset}, - {"createArrayBufferFromAddress", CreateArrayBufferFromAddress}, - {"createArrayBufferCleaner", CreateArrayBufferCleaner}, - {"setLoggerLevel", setLoggerLevel}, - {"getLoggerEffectiveLevel", GetLoggerEffectiveLevel}, - {"getNodeLoggerName", GetNodeLoggerName}, - {"log", Log}, - {"isEnableFor", IsEnableFor}, - {"createContext", CreateContext}, - {"isContextValid", IsContextValid}, - {"getPublisherNamesAndTypesByNode", GetPublisherNamesAndTypesByNode}, - {"getSubscriptionNamesAndTypesByNode", GetSubscriptionNamesAndTypesByNode}, - {"getServiceNamesAndTypesByNode", GetServiceNamesAndTypesByNode}, - {"getClientNamesAndTypesByNode", GetClientNamesAndTypesByNode}, - {"getTopicNamesAndTypes", GetTopicNamesAndTypes}, - {"getServiceNamesAndTypes", GetServiceNamesAndTypes}, - {"getNodeNames", GetNodeNames}, - {"countPublishers", CountPublishers}, - {"countSubscribers", CountSubscribers}, - {"serviceServerIsAvailable", ServiceServerIsAvailable}, - {"publishRawMessage", PublishRawMessage}, - {"rclTakeRaw", RclTakeRaw}, - {"getClientServiceName", GetClientServiceName}, - {"getServiceServiceName", GetServiceServiceName}, - {"", nullptr} + return Napi::String::New(env, service_name); +} + +Napi::Object InitBindings(Napi::Env env, Napi::Object exports) { + exports.Set("init", Napi::Function::New(env, InitRclnodejs)); + exports.Set("createNode", Napi::Function::New(env, CreateNode)); + exports.Set("getParameterOverrides", + Napi::Function::New(env, GetParameterOverrides)); + exports.Set("createGuardCondition", + Napi::Function::New(env, CreateGuardCondition)); + exports.Set("triggerGuardCondition", + Napi::Function::New(env, TriggerGuardCondition)); + exports.Set("createTimer", Napi::Function::New(env, CreateTimer)); + exports.Set("isTimerReady", Napi::Function::New(env, IsTimerReady)); + exports.Set("callTimer", Napi::Function::New(env, CallTimer)); + exports.Set("cancelTimer", Napi::Function::New(env, CancelTimer)); + exports.Set("isTimerCanceled", Napi::Function::New(env, IsTimerCanceled)); + exports.Set("resetTimer", Napi::Function::New(env, ResetTimer)); + exports.Set("timerGetTimeSinceLastCall", + Napi::Function::New(env, TimerGetTimeSinceLastCall)); + exports.Set("timerGetTimeUntilNextCall", + Napi::Function::New(env, TimerGetTimeUntilNextCall)); + exports.Set("createClock", Napi::Function::New(env, CreateClock)); + exports.Set("clockGetNow", Napi::Function::New(env, ClockGetNow)); + exports.Set("createTimePoint", Napi::Function::New(env, CreateTimePoint)); + exports.Set("getNanoseconds", Napi::Function::New(env, GetNanoseconds)); + exports.Set("createDuration", Napi::Function::New(env, CreateDuration)); + exports.Set("getDurationNanoseconds", + Napi::Function::New(env, GetDurationNanoseconds)); + exports.Set("setRosTimeOverrideIsEnabled", + Napi::Function::New(env, SetRosTimeOverrideIsEnabled)); + exports.Set("setRosTimeOverride", + Napi::Function::New(env, SetRosTimeOverride)); + exports.Set("getRosTimeOverrideIsEnabled", + Napi::Function::New(env, GetRosTimeOverrideIsEnabled)); + exports.Set("rclTake", Napi::Function::New(env, RclTake)); + exports.Set("createSubscription", + Napi::Function::New(env, CreateSubscription)); + exports.Set("hasContentFilter", Napi::Function::New(env, HasContentFilter)); + exports.Set("setContentFilter", Napi::Function::New(env, SetContentFilter)); + exports.Set("clearContentFilter", + Napi::Function::New(env, ClearContentFilter)); + exports.Set("createPublisher", Napi::Function::New(env, CreatePublisher)); + exports.Set("publish", Napi::Function::New(env, Publish)); + exports.Set("getPublisherTopic", Napi::Function::New(env, GetPublisherTopic)); + exports.Set("getSubscriptionTopic", + Napi::Function::New(env, GetSubscriptionTopic)); + exports.Set("createClient", Napi::Function::New(env, CreateClient)); + exports.Set("rclTakeResponse", Napi::Function::New(env, RclTakeResponse)); + exports.Set("sendRequest", Napi::Function::New(env, SendRequest)); + exports.Set("createService", Napi::Function::New(env, CreateService)); + exports.Set("rclTakeRequest", Napi::Function::New(env, RclTakeRequest)); + exports.Set("sendResponse", Napi::Function::New(env, SendResponse)); + exports.Set("shutdown", Napi::Function::New(env, Shutdown)); + exports.Set("validateFullTopicName", + Napi::Function::New(env, ValidateFullTopicName)); + exports.Set("validateNodeName", Napi::Function::New(env, ValidateNodeName)); + exports.Set("validateTopicName", Napi::Function::New(env, ValidateTopicName)); + exports.Set("validateNamespace", Napi::Function::New(env, ValidateNamespace)); + exports.Set("expandTopicName", Napi::Function::New(env, ExpandTopicName)); + exports.Set("getNodeName", Napi::Function::New(env, GetNodeName)); + exports.Set("getNamespace", Napi::Function::New(env, GetNamespace)); + exports.Set("initString", Napi::Function::New(env, InitString)); + exports.Set("freeMemeoryAtOffset", + Napi::Function::New(env, FreeMemeoryAtOffset)); + exports.Set("createArrayBufferFromAddress", + Napi::Function::New(env, CreateArrayBufferFromAddress)); + exports.Set("createArrayBufferCleaner", + Napi::Function::New(env, CreateArrayBufferCleaner)); + exports.Set("setLoggerLevel", Napi::Function::New(env, setLoggerLevel)); + exports.Set("getLoggerEffectiveLevel", + Napi::Function::New(env, GetLoggerEffectiveLevel)); + exports.Set("getNodeLoggerName", Napi::Function::New(env, GetNodeLoggerName)); + exports.Set("log", Napi::Function::New(env, Log)); + exports.Set("isEnableFor", Napi::Function::New(env, IsEnableFor)); + exports.Set("createContext", Napi::Function::New(env, CreateContext)); + exports.Set("isContextValid", Napi::Function::New(env, IsContextValid)); + exports.Set("getPublisherNamesAndTypesByNode", + Napi::Function::New(env, GetPublisherNamesAndTypesByNode)); + exports.Set("getSubscriptionNamesAndTypesByNode", + Napi::Function::New(env, GetSubscriptionNamesAndTypesByNode)); + exports.Set("getServiceNamesAndTypesByNode", + Napi::Function::New(env, GetServiceNamesAndTypesByNode)); + exports.Set("getClientNamesAndTypesByNode", + Napi::Function::New(env, GetClientNamesAndTypesByNode)); + exports.Set("getTopicNamesAndTypes", + Napi::Function::New(env, GetTopicNamesAndTypes)); + exports.Set("getServiceNamesAndTypes", + Napi::Function::New(env, GetServiceNamesAndTypes)); + exports.Set("getNodeNames", Napi::Function::New(env, GetNodeNames)); + exports.Set("countPublishers", Napi::Function::New(env, CountPublishers)); + exports.Set("countSubscribers", Napi::Function::New(env, CountSubscribers)); + exports.Set("serviceServerIsAvailable", + Napi::Function::New(env, ServiceServerIsAvailable)); + exports.Set("publishRawMessage", Napi::Function::New(env, PublishRawMessage)); + exports.Set("rclTakeRaw", Napi::Function::New(env, RclTakeRaw)); + exports.Set("getClientServiceName", + Napi::Function::New(env, GetClientServiceName)); + exports.Set("getServiceServiceName", + Napi::Function::New(env, GetServiceServiceName)); #if ROS_VERSION > 2205 // 2205 == Humble - , - {"configureServiceIntrospection", ConfigureServiceIntrospection} + exports.Set("configureServiceIntrospection", + Napi::Function::New(env, ConfigureServiceIntrospection)); #endif -}; + + return exports; +} + +// NODE_API_MODULE(rcl_bindings, Init) } // namespace rclnodejs diff --git a/src/rcl_bindings.hpp b/src/rcl_bindings.h similarity index 62% rename from src/rcl_bindings.hpp rename to src/rcl_bindings.h index 8c8476f0..021ff074 100644 --- a/src/rcl_bindings.hpp +++ b/src/rcl_bindings.h @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SRC_RCL_BINDINGS_HPP_ -#define SRC_RCL_BINDINGS_HPP_ +#ifndef SRC_RCL_BINDINGS_H_ +#define SRC_RCL_BINDINGS_H_ -#include +#include #include #include @@ -25,22 +25,13 @@ namespace rclnodejs { -typedef void (*JsCFuntcion)(const Nan::FunctionCallbackInfo&); - -typedef struct { - const char* name; - JsCFuntcion function; -} BindingMethod; - -extern rcl_guard_condition_t* g_sigint_gc; - void ExtractNamesAndTypes(rcl_names_and_types_t names_and_types, - v8::Local* result_list); + Napi::Array* result_list); -std::unique_ptr GetQoSProfile(v8::Local qos); +std::unique_ptr GetQoSProfile(Napi::Value qos); -extern std::vector binding_methods; +Napi::Object InitBindings(Napi::Env env, Napi::Object exports); } // namespace rclnodejs -#endif // SRC_RCL_BINDINGS_HPP_ +#endif // SRC_RCL_BINDINGS_H_ diff --git a/src/rcl_handle.cpp b/src/rcl_handle.cpp index 6f6c0ae8..e2cdd31e 100644 --- a/src/rcl_handle.cpp +++ b/src/rcl_handle.cpp @@ -12,91 +12,75 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rcl_handle.hpp" +#include "rcl_handle.h" #include #include +#include "rcl_utilities.h" + namespace rclnodejs { -Nan::Persistent RclHandle::constructor; +Napi::FunctionReference RclHandle::constructor; -RclHandle::RclHandle() : pointer_(nullptr), parent_(nullptr) {} +RclHandle::RclHandle(const Napi::CallbackInfo& info) + : Napi::ObjectWrap(info), pointer_(nullptr), parent_(nullptr) {} 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); +Napi::Object RclHandle::Init(Napi::Env env, Napi::Object exports) { + Napi::HandleScope scope(env); - Nan::SetAccessor(tpl->InstanceTemplate(), - Nan::New("properties").ToLocalChecked(), PropertiesGetter); - Nan::SetPrototypeMethod(tpl, "release", Release); - Nan::SetPrototypeMethod(tpl, "dismiss", Dismiss); + Napi::Function func = DefineClass( + env, "RclHandle", + {InstanceMethod("release", &RclHandle::Release), + InstanceMethod("dismiss", &RclHandle::Dismiss), + InstanceAccessor("properties", &RclHandle::PropertiesGetter, nullptr)}); - v8::Local context = exports->GetIsolate()->GetCurrentContext(); + constructor = Napi::Persistent(func); + constructor.SuppressDestruct(); + exports.Set("RclHandle", func); - constructor.Reset(tpl->GetFunction(context).ToLocalChecked()); - Nan::Set(exports, Nan::New("RclHandle").ToLocalChecked(), - tpl->GetFunction(context).ToLocalChecked()); -} - -void RclHandle::New(const Nan::FunctionCallbackInfo& info) { - if (info.IsConstructCall()) { - RclHandle* obj = new RclHandle(); - obj->Wrap(info.This()); - info.GetReturnValue().Set(info.This()); - } + return exports; } void RclHandle::SyncProperties() { - auto obj = v8::Object::New(v8::Isolate::GetCurrent()); - - for (auto it = properties_.begin(); it != properties_.end(); it++) { - Nan::Set(obj, Nan::New(it->first).ToLocalChecked(), Nan::New(it->second)); + Napi::Env env = rclnodejs::GetEnv(); + Napi::HandleScope scope(env); + Napi::Object obj = Napi::Object::New(env); + for (auto& pair : properties_) { + obj.Set(pair.first, Napi::Boolean::New(env, pair.second)); } - - properties_obj_ = obj; + properties_obj_ = Napi::Persistent(obj); } -NAN_GETTER(RclHandle::PropertiesGetter) { - auto* me = RclHandle::Unwrap(info.Holder()); - - if (!me->properties_obj_.IsEmpty()) - info.GetReturnValue().Set(me->properties_obj_); - else - info.GetReturnValue().Set(Nan::Undefined()); +Napi::Value RclHandle::PropertiesGetter(const Napi::CallbackInfo& info) { + return !properties_obj_.IsEmpty() ? properties_obj_.Value() + : info.Env().Undefined(); } -NAN_METHOD(RclHandle::Release) { - auto* me = Nan::ObjectWrap::Unwrap(info.Holder()); - if (me->ptr()) me->Reset(); - - info.GetReturnValue().Set(Nan::Undefined()); +Napi::Value RclHandle::Release(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + if (ptr()) Reset(); + return env.Undefined(); } -NAN_METHOD(RclHandle::Dismiss) { - auto* me = Nan::ObjectWrap::Unwrap(info.Holder()); - if (me) me->set_ptr(nullptr); - - info.GetReturnValue().Set(Nan::Undefined()); +Napi::Value RclHandle::Dismiss(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + set_ptr(nullptr); + return env.Undefined(); } -v8::Local RclHandle::NewInstance( - void* handle, RclHandle* parent, std::function deleter) { - Nan::EscapableHandleScope scope; - - v8::Local cons = Nan::New(constructor); - v8::Local context = - v8::Isolate::GetCurrent()->GetCurrentContext(); +Napi::Object RclHandle::NewInstance(Napi::Env env, void* handle, + RclHandle* parent, + std::function deleter) { + Napi::EscapableHandleScope scope(env); - v8::Local instance = - cons->NewInstance(context, 0, nullptr).ToLocalChecked(); + Napi::Object instance = constructor.New({}); - auto* rcl_handle = Nan::ObjectWrap::Unwrap(instance); + RclHandle* rcl_handle = Napi::ObjectWrap::Unwrap(instance); rcl_handle->set_ptr(handle); rcl_handle->set_deleter(deleter); if (parent) { @@ -104,7 +88,7 @@ v8::Local RclHandle::NewInstance( parent->AddChild(rcl_handle); } - return scope.Escape(instance); + return scope.Escape(instance).As(); } void RclHandle::Reset() { diff --git a/src/rcl_handle.hpp b/src/rcl_handle.h similarity index 67% rename from src/rcl_handle.hpp rename to src/rcl_handle.h index 143009e0..6367de14 100644 --- a/src/rcl_handle.hpp +++ b/src/rcl_handle.h @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SRC_RCL_HANDLE_HPP_ -#define SRC_RCL_HANDLE_HPP_ +#ifndef SRC_RCL_HANDLE_H_ +#define SRC_RCL_HANDLE_H_ -#include +#include #include #include @@ -24,11 +24,15 @@ namespace rclnodejs { -class RclHandle : public Nan::ObjectWrap { +class RclHandle : public Napi::ObjectWrap { public: - static void Init(v8::Local exports); - static v8::Local NewInstance(void* handle, RclHandle* parent, - std::function deleter); + static Napi::Object Init(Napi::Env env, Napi::Object exports); + static Napi::Object NewInstance(Napi::Env env, void* handle, + RclHandle* parent, + std::function deleter); + + explicit RclHandle(const Napi::CallbackInfo& info); + ~RclHandle(); void set_deleter(std::function deleter) { deleter_ = deleter; } @@ -47,25 +51,22 @@ class RclHandle : public Nan::ObjectWrap { void SyncProperties(); private: - RclHandle(); - ~RclHandle(); - - static Nan::Persistent constructor; - static void New(const Nan::FunctionCallbackInfo& info); - static NAN_METHOD(Release); - static NAN_METHOD(Dismiss); - static NAN_GETTER(PropertiesGetter); + Napi::Value Release(const Napi::CallbackInfo& info); + Napi::Value Dismiss(const Napi::CallbackInfo& info); + Napi::Value PropertiesGetter(const Napi::CallbackInfo& info); private: void* pointer_; RclHandle* parent_; std::map properties_; - v8::Local properties_obj_; + Napi::ObjectReference properties_obj_; std::function deleter_; std::set children_; + + static Napi::FunctionReference constructor; }; } // namespace rclnodejs -#endif // SRC_RCL_HANDLE_HPP_ +#endif // SRC_RCL_HANDLE_H_ diff --git a/src/rcl_lifecycle_bindings.cpp b/src/rcl_lifecycle_bindings.cpp index 63ae8148..51fd6f5b 100644 --- a/src/rcl_lifecycle_bindings.cpp +++ b/src/rcl_lifecycle_bindings.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rcl_lifecycle_bindings.hpp" +#include "rcl_lifecycle_bindings.h" #include #include @@ -26,33 +26,32 @@ #include "lifecycle_msgs/srv/get_available_states.h" #include "lifecycle_msgs/srv/get_available_transitions.h" #include "lifecycle_msgs/srv/get_state.h" -#include "macros.hpp" -#include "rcl_handle.hpp" -#include "rcl_utilities.hpp" +#include "macros.h" +#include "rcl_handle.h" +#include "rcl_utilities.h" namespace rclnodejs { -static v8::Local wrapState(const rcl_lifecycle_state_t* state) { - v8::Local jsState = Nan::New(); - Nan::Set(jsState, Nan::New("id").ToLocalChecked(), Nan::New(state->id)); - Nan::Set(jsState, Nan::New("label").ToLocalChecked(), - Nan::New(state->label).ToLocalChecked()); +static Napi::Object wrapState(Napi::Env env, + const rcl_lifecycle_state_t* state) { + Napi::Object jsState = Napi::Object::New(env); + jsState.Set("id", state->id); + jsState.Set("label", state->label); return jsState; } -static v8::Local wrapTransition( - const rcl_lifecycle_transition_t* transition) { - v8::Local jsTransition = Nan::New(); - Nan::Set(jsTransition, Nan::New("id").ToLocalChecked(), - Nan::New(transition->id)); - Nan::Set(jsTransition, Nan::New("label").ToLocalChecked(), - Nan::New(transition->label).ToLocalChecked()); +static Napi::Object wrapTransition( + Napi::Env env, const rcl_lifecycle_transition_t* transition) { + Napi::Object jsTransition = Napi::Object::New(env); + jsTransition.Set("id", transition->id); + jsTransition.Set("label", transition->label); return jsTransition; } -NAN_METHOD(CreateLifecycleStateMachine) { - RclHandle* node_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value CreateLifecycleStateMachine(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()); rcl_lifecycle_state_machine_t* state_machine = @@ -76,7 +75,7 @@ NAN_METHOD(CreateLifecycleStateMachine) { #if ROS_VERSION >= 2105 rcl_lifecycle_state_machine_options_t options = rcl_lifecycle_get_default_state_machine_options(); - options.enable_com_interface = Nan::To(info[1]).FromJust(); + options.enable_com_interface = info[1].As().Value(); THROW_ERROR_IF_NOT_EQUAL( RCL_RET_OK, @@ -84,8 +83,8 @@ NAN_METHOD(CreateLifecycleStateMachine) { gat, gtg, &options), rcl_get_error_string().str); - auto js_obj = - RclHandle::NewInstance(state_machine, node_handle, [node](void* ptr) { + auto js_obj = RclHandle::NewInstance( + env, state_machine, node_handle, [node](void* ptr) { rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast(ptr); rcl_ret_t ret = rcl_lifecycle_state_machine_fini(state_machine, node); @@ -103,7 +102,7 @@ NAN_METHOD(CreateLifecycleStateMachine) { rcl_get_error_string().str); auto js_obj = RclHandle::NewInstance( - state_machine, node_handle, [node, node_options](void* ptr) { + env, state_machine, node_handle, [node, node_options](void* ptr) { rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast(ptr); rcl_ret_t ret = rcl_lifecycle_state_machine_fini( @@ -113,116 +112,122 @@ NAN_METHOD(CreateLifecycleStateMachine) { }); #endif - info.GetReturnValue().Set(js_obj); + return js_obj; } -NAN_METHOD(GetCurrentLifecycleState) { - RclHandle* state_machine_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetCurrentLifecycleState(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* state_machine_handle = + RclHandle::Unwrap(info[0].As()); rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast( state_machine_handle->ptr()); const rcl_lifecycle_state_t* current_state = state_machine->current_state; - info.GetReturnValue().Set(wrapState(current_state)); + return wrapState(env, current_state); } -NAN_METHOD(GetLifecycleTransitionByLabel) { - RclHandle* state_machine_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetLifecycleTransitionByLabel(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* state_machine_handle = + RclHandle::Unwrap(info[0].As()); rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast( state_machine_handle->ptr()); - std::string transition_label(*Nan::Utf8String(info[1])); + std::string transition_label = info[1].As(); auto transition = rcl_lifecycle_get_transition_by_label( state_machine->current_state, transition_label.c_str()); - info.GetReturnValue().Set(transition == nullptr ? Nan::New() - : wrapTransition(transition)); + return transition == nullptr ? Napi::Object::New(env) + : wrapTransition(env, transition); } // return all registered states -NAN_METHOD(GetLifecycleStates) { - RclHandle* state_machine_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetLifecycleStates(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* state_machine_handle = + RclHandle::Unwrap(info[0].As()); rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast( state_machine_handle->ptr()); - v8::Local states = Nan::New(); + Napi::Array states = Napi::Array::New(env); for (uint8_t i = 0; i < state_machine->transition_map.states_size; ++i) { const rcl_lifecycle_state_t state = state_machine->transition_map.states[i]; - v8::Local jsState = wrapState(&state); - Nan::Set(states, i, jsState); + Napi::Object jsState = wrapState(env, &state); + states[i] = jsState; } - info.GetReturnValue().Set(states); + return states; } // return all registered transitions -NAN_METHOD(GetLifecycleTransitions) { - RclHandle* state_machine_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetLifecycleTransitions(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* state_machine_handle = + RclHandle::Unwrap(info[0].As()); rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast( state_machine_handle->ptr()); - v8::Local jsTransitions = Nan::New(); + Napi::Array jsTransitions = Napi::Array::New(env); for (uint8_t i = 0; i < state_machine->transition_map.transitions_size; ++i) { auto transition = state_machine->transition_map.transitions[i]; - v8::Local jsTransitionDesc = Nan::New(); - Nan::Set(jsTransitionDesc, Nan::New("transition").ToLocalChecked(), - wrapTransition(&transition)); - Nan::Set(jsTransitionDesc, Nan::New("start_state").ToLocalChecked(), - wrapState(transition.start)); - Nan::Set(jsTransitionDesc, Nan::New("goal_state").ToLocalChecked(), - wrapState(transition.goal)); - - Nan::Set(jsTransitions, i, jsTransitionDesc); + Napi::Object jsTransitionDesc = Napi::Object::New(env); + jsTransitionDesc.Set("transition", wrapTransition(env, &transition)); + jsTransitionDesc.Set("start_state", wrapState(env, transition.start)); + jsTransitionDesc.Set("goal_state", wrapState(env, transition.goal)); + + jsTransitions[i] = jsTransitionDesc; } - info.GetReturnValue().Set(jsTransitions); + return jsTransitions; } // return the transitions available from the current state -NAN_METHOD(GetAvailableLifecycleTransitions) { - RclHandle* state_machine_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetAvailableLifecycleTransitions(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* state_machine_handle = + RclHandle::Unwrap(info[0].As()); rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast( state_machine_handle->ptr()); - v8::Local jsTransitions = Nan::New(); + Napi::Array jsTransitions = Napi::Array::New(env); for (uint8_t i = 0; i < state_machine->current_state->valid_transition_size; ++i) { auto transition = state_machine->current_state->valid_transitions[i]; - v8::Local jsTransitionDesc = Nan::New(); - Nan::Set(jsTransitionDesc, Nan::New("transition").ToLocalChecked(), - wrapTransition(&transition)); - Nan::Set(jsTransitionDesc, Nan::New("start_state").ToLocalChecked(), - wrapState(transition.start)); - Nan::Set(jsTransitionDesc, Nan::New("goal_state").ToLocalChecked(), - wrapState(transition.goal)); - - Nan::Set(jsTransitions, i, jsTransitionDesc); + Napi::Object jsTransitionDesc = Napi::Object::New(env); + jsTransitionDesc.Set("transition", wrapTransition(env, &transition)); + jsTransitionDesc.Set("start_state", wrapState(env, transition.start)); + jsTransitionDesc.Set("goal_state", wrapState(env, transition.goal)); + + jsTransitions[i] = jsTransitionDesc; } - info.GetReturnValue().Set(jsTransitions); + return jsTransitions; } -NAN_METHOD(GetLifecycleSrvNameAndHandle) { - RclHandle* state_machine_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value GetLifecycleSrvNameAndHandle(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* state_machine_handle = + RclHandle::Unwrap(info[0].As()); rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast( state_machine_handle->ptr()); - std::string lifecycle_srv_field_name(*Nan::Utf8String(info[1])); + std::string lifecycle_srv_field_name = info[1].As(); rcl_service_t* service = nullptr; if (lifecycle_srv_field_name.compare("srv_get_state") == 0) { @@ -242,27 +247,28 @@ NAN_METHOD(GetLifecycleSrvNameAndHandle) { std::string service_name = rcl_service_get_service_name(service); // build result object {name: , handle: } - v8::Local named_srv_obj = Nan::New(); - Nan::Set(named_srv_obj, Nan::New("name").ToLocalChecked(), - Nan::New(service_name).ToLocalChecked()); + Napi::Object named_srv_obj = Napi::Object::New(env); + named_srv_obj.Set("name", service_name); // Note: lifecycle Services are created and managed by their // rcl_lifecycle_state_machine. Thus we must not manually // free the lifecycle_state_machine's service pointers. - auto srv_handle = RclHandle::NewInstance(service, nullptr, nullptr); + auto srv_handle = RclHandle::NewInstance(env, service, nullptr, nullptr); - Nan::Set(named_srv_obj, Nan::New("handle").ToLocalChecked(), srv_handle); - info.GetReturnValue().Set(named_srv_obj); + named_srv_obj.Set("handle", srv_handle); + return named_srv_obj; } // return null if transition exists from current state -NAN_METHOD(TriggerLifecycleTransitionById) { - RclHandle* state_machine_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value TriggerLifecycleTransitionById(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* state_machine_handle = + RclHandle::Unwrap(info[0].As()); rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast( state_machine_handle->ptr()); - int transition_id = Nan::To(info[1]).FromJust(); + int transition_id = info[1].As().Int64Value(); bool publish = true; @@ -272,17 +278,19 @@ NAN_METHOD(TriggerLifecycleTransitionById) { rcl_get_error_string().str); const rcl_lifecycle_state_t* current_state = state_machine->current_state; - info.GetReturnValue().Set(wrapState(current_state)); + return wrapState(env, current_state); } // return null if transition exists from current state -NAN_METHOD(TriggerLifecycleTransitionByLabel) { - RclHandle* state_machine_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); +Napi::Value TriggerLifecycleTransitionByLabel(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + + RclHandle* state_machine_handle = + RclHandle::Unwrap(info[0].As()); rcl_lifecycle_state_machine_t* state_machine = reinterpret_cast( state_machine_handle->ptr()); - std::string transition_label(*Nan::Utf8String(info[1])); + std::string transition_label = info[1].As(); bool publish = true; @@ -293,7 +301,7 @@ NAN_METHOD(TriggerLifecycleTransitionByLabel) { rcl_get_error_string().str); const rcl_lifecycle_state_t* current_state = state_machine->current_state; - info.GetReturnValue().Set(wrapState(current_state)); + return wrapState(env, current_state); } static const char* transitionId2Label(int callback_ret) { @@ -340,29 +348,43 @@ static const char* transitionId2Label(int callback_ret) { return rcl_lifecycle_transition_error_label; } -NAN_METHOD(GetLifecycleTransitionIdToLabel) { - int callback_ret = Nan::To(info[0]).FromJust(); +Napi::Value GetLifecycleTransitionIdToLabel(const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + int callback_ret = info[0].As().Int64Value(); const char* transition_label = transitionId2Label(callback_ret); - info.GetReturnValue().Set(Nan::New(transition_label).ToLocalChecked()); + return Napi::String::New(env, transition_label); } -NAN_METHOD(GetLifecycleShutdownTransitionLabel) { - info.GetReturnValue().Set( - Nan::New(rcl_lifecycle_shutdown_label).ToLocalChecked()); +Napi::Value GetLifecycleShutdownTransitionLabel( + const Napi::CallbackInfo& info) { + Napi::Env env = info.Env(); + return Napi::String::New(env, rcl_lifecycle_shutdown_label); } -std::vector lifecycle_binding_methods = { - {"createLifecycleStateMachine", CreateLifecycleStateMachine}, - {"getCurrentLifecycleState", GetCurrentLifecycleState}, - {"getLifecycleTransitionByLabel", GetLifecycleTransitionByLabel}, - {"getLifecycleStates", GetLifecycleStates}, - {"getLifecycleTransitions", GetLifecycleTransitions}, - {"getAvailableLifecycleTransitions", GetAvailableLifecycleTransitions}, - {"triggerLifecycleTransitionById", TriggerLifecycleTransitionById}, - {"triggerLifecycleTransitionByLabel", TriggerLifecycleTransitionByLabel}, - {"getLifecycleSrvNameAndHandle", GetLifecycleSrvNameAndHandle}, - {"getLifecycleTransitionIdToLabel", GetLifecycleTransitionIdToLabel}, - {"getLifecycleShutdownTransitionLabel", - GetLifecycleShutdownTransitionLabel}}; +Napi::Object InitLifecycle(Napi::Env env, Napi::Object exports) { + exports.Set("createLifecycleStateMachine", + Napi::Function::New(env, CreateLifecycleStateMachine)); + exports.Set("getCurrentLifecycleState", + Napi::Function::New(env, GetCurrentLifecycleState)); + exports.Set("getLifecycleTransitionByLabel", + Napi::Function::New(env, GetLifecycleTransitionByLabel)); + exports.Set("getLifecycleStates", + Napi::Function::New(env, GetLifecycleStates)); + exports.Set("getLifecycleTransitions", + Napi::Function::New(env, GetLifecycleTransitions)); + exports.Set("getAvailableLifecycleTransitions", + Napi::Function::New(env, GetAvailableLifecycleTransitions)); + exports.Set("triggerLifecycleTransitionById", + Napi::Function::New(env, TriggerLifecycleTransitionById)); + exports.Set("triggerLifecycleTransitionByLabel", + Napi::Function::New(env, TriggerLifecycleTransitionByLabel)); + exports.Set("getLifecycleSrvNameAndHandle", + Napi::Function::New(env, GetLifecycleSrvNameAndHandle)); + exports.Set("getLifecycleTransitionIdToLabel", + Napi::Function::New(env, GetLifecycleTransitionIdToLabel)); + exports.Set("getLifecycleShutdownTransitionLabel", + Napi::Function::New(env, GetLifecycleShutdownTransitionLabel)); + return exports; +} } // namespace rclnodejs diff --git a/src/rcl_lifecycle_bindings.hpp b/src/rcl_lifecycle_bindings.h similarity index 75% rename from src/rcl_lifecycle_bindings.hpp rename to src/rcl_lifecycle_bindings.h index a7c75155..e82e8e16 100644 --- a/src/rcl_lifecycle_bindings.hpp +++ b/src/rcl_lifecycle_bindings.h @@ -12,17 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SRC_RCL_LIFECYCLE_BINDINGS_HPP_ -#define SRC_RCL_LIFECYCLE_BINDINGS_HPP_ +#ifndef SRC_RCL_LIFECYCLE_BINDINGS_H_ +#define SRC_RCL_LIFECYCLE_BINDINGS_H_ + +#include #include -#include "rcl_bindings.hpp" +#include "rcl_bindings.h" namespace rclnodejs { -extern std::vector lifecycle_binding_methods; +Napi::Object InitLifecycle(Napi::Env env, Napi::Object exports); } // namespace rclnodejs -#endif // SRC_RCL_LIFECYCLE_BINDINGS_HPP_ +#endif // SRC_RCL_LIFECYCLE_BINDINGS_H_ diff --git a/src/rcl_utilities.cpp b/src/rcl_utilities.cpp index db7d09ea..cd793600 100644 --- a/src/rcl_utilities.cpp +++ b/src/rcl_utilities.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rcl_utilities.hpp" +#include "rcl_utilities.h" #include #include @@ -21,7 +21,10 @@ #include namespace { + uv_lib_t g_lib; +Napi::Env g_env = nullptr; + } // namespace namespace rclnodejs { @@ -95,4 +98,8 @@ std::string GetErrorMessageAndClear() { return std::string(uv_dlerror(&g_lib)); } +Napi::Env& GetEnv() { return g_env; } + +void StoreEnv(Napi::Env current_env) { g_env = current_env; } + } // namespace rclnodejs diff --git a/src/rcl_utilities.hpp b/src/rcl_utilities.h similarity index 83% rename from src/rcl_utilities.hpp rename to src/rcl_utilities.h index 300b6ae0..03457075 100644 --- a/src/rcl_utilities.hpp +++ b/src/rcl_utilities.h @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SRC_RCL_UTILITIES_HPP_ -#define SRC_RCL_UTILITIES_HPP_ +#ifndef SRC_RCL_UTILITIES_H_ +#define SRC_RCL_UTILITIES_H_ + +#include #include @@ -35,6 +37,10 @@ const rosidl_action_type_support_t* GetActionTypeSupport( std::string GetErrorMessageAndClear(); +// Store a reference to the environment that can be used for error reporting. +Napi::Env& GetEnv(); +void StoreEnv(Napi::Env current_env); + } // namespace rclnodejs -#endif // SRC_RCL_UTILITIES_HPP_ +#endif // SRC_RCL_UTILITIES_H_ diff --git a/src/shadow_node.cpp b/src/shadow_node.cpp index 55d3639b..aeae6afc 100644 --- a/src/shadow_node.cpp +++ b/src/shadow_node.cpp @@ -12,47 +12,43 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "shadow_node.hpp" +#include "shadow_node.h" #include #include -#include "executor.hpp" -#include "handle_manager.hpp" -#include "rcl_handle.hpp" +#include "executor.h" +#include "handle_manager.h" +#include "rcl_handle.h" namespace rclnodejs { -Nan::Persistent ShadowNode::constructor; +Napi::FunctionReference ShadowNode::constructor; -ShadowNode::ShadowNode() : handle_manager_(std::make_unique()) { - executor_ = std::make_unique(handle_manager_.get(), this); +ShadowNode::ShadowNode(const Napi::CallbackInfo& info) + : Napi::ObjectWrap(info), + handle_manager_(std::make_unique()) { + executor_ = + std::make_unique(info.Env(), handle_manager_.get(), this); } -ShadowNode::~ShadowNode() { - Nan::HandleScope scope; +ShadowNode::~ShadowNode() { StopRunning(); } - StopRunning(); -} - -void ShadowNode::Init(v8::Local exports) { - Nan::HandleScope scope; - - // Prepare constructor template - v8::Local tpl = Nan::New(New); - tpl->SetClassName(Nan::New("ShadowNode").ToLocalChecked()); - tpl->InstanceTemplate()->SetInternalFieldCount(1); +void ShadowNode::Init(Napi::Env env, Napi::Object exports) { + Napi::HandleScope scope(env); - Nan::SetPrototypeMethod(tpl, "start", Start); - Nan::SetPrototypeMethod(tpl, "stop", Stop); - Nan::SetPrototypeMethod(tpl, "syncHandles", SyncHandles); - Nan::SetPrototypeMethod(tpl, "spinOnce", SpinOnce); + Napi::Function func = + DefineClass(env, "ShadowNode", + { + InstanceMethod("start", &ShadowNode::Start), + InstanceMethod("stop", &ShadowNode::Stop), + InstanceMethod("syncHandles", &ShadowNode::SyncHandles), + InstanceMethod("spinOnce", &ShadowNode::SpinOnce), + }); - v8::Local context = exports->GetIsolate()->GetCurrentContext(); - - constructor.Reset(tpl->GetFunction(context).ToLocalChecked()); - Nan::Set(exports, Nan::New("ShadowNode").ToLocalChecked(), - tpl->GetFunction(context).ToLocalChecked()); + constructor = Napi::Persistent(func); + constructor.SuppressDestruct(); + exports.Set("ShadowNode", func); } void ShadowNode::StopRunning() { @@ -61,82 +57,67 @@ void ShadowNode::StopRunning() { } void ShadowNode::StartRunning(rcl_context_t* context, int32_t timeout) { - handle_manager_->SynchronizeHandles(this->handle()); + handle_manager_->SynchronizeHandles(this->Value()); executor_->Start(context, timeout); } void ShadowNode::RunOnce(rcl_context_t* context, int32_t timeout) { - handle_manager_->SynchronizeHandles(this->handle()); + handle_manager_->SynchronizeHandles(this->Value()); executor_->SpinOnce(context, timeout); } -NAN_METHOD(ShadowNode::Start) { - auto* me = Nan::ObjectWrap::Unwrap(info.Holder()); - RclHandle* context_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); - auto timeout = Nan::To(info[1]).FromJust(); - rcl_context_t* context = - reinterpret_cast(context_handle->ptr()); - if (me) me->StartRunning(context, timeout); +Napi::Value ShadowNode::Start(const Napi::CallbackInfo& info) { + Napi::Object context_handle = info[0].As(); + RclHandle* handle = RclHandle::Unwrap(context_handle); + int32_t timeout = info[1].As().Int32Value(); - info.GetReturnValue().Set(Nan::Undefined()); -} + rcl_context_t* context = reinterpret_cast(handle->ptr()); + StartRunning(context, timeout); -NAN_METHOD(ShadowNode::Stop) { - auto* me = Nan::ObjectWrap::Unwrap(info.Holder()); - if (me) me->StopRunning(); + return info.Env().Undefined(); +} - info.GetReturnValue().Set(Nan::Undefined()); +Napi::Value ShadowNode::Stop(const Napi::CallbackInfo& info) { + StopRunning(); + return info.Env().Undefined(); } -NAN_METHOD(ShadowNode::SpinOnce) { - auto* me = Nan::ObjectWrap::Unwrap(info.Holder()); - RclHandle* context_handle = RclHandle::Unwrap( - Nan::To(info[0]).ToLocalChecked()); - auto timeout = Nan::To(info[1]).FromJust(); - rcl_context_t* context = - reinterpret_cast(context_handle->ptr()); - if (me) me->RunOnce(context, timeout); +Napi::Value ShadowNode::SpinOnce(const Napi::CallbackInfo& info) { + Napi::Object context_handle = info[0].As(); + RclHandle* handle = RclHandle::Unwrap(context_handle); + int32_t timeout = info[1].As().Int32Value(); + + rcl_context_t* context = reinterpret_cast(handle->ptr()); + RunOnce(context, timeout); - info.GetReturnValue().Set(Nan::Undefined()); + return info.Env().Undefined(); } -NAN_METHOD(ShadowNode::SyncHandles) { - auto* me = Nan::ObjectWrap::Unwrap(info.Holder()); - if (me) { - me->handle_manager()->SynchronizeHandles(me->handle()); - } +Napi::Value ShadowNode::SyncHandles(const Napi::CallbackInfo& info) { + handle_manager()->SynchronizeHandles(this->Value()); + return info.Env().Undefined(); } void ShadowNode::Execute(const std::vector& handles) { - Nan::HandleScope scope; - Nan::AsyncResource res("shadow_node"); + Napi::Env env = Env(); + Napi::HandleScope scope(env); - v8::Local results = Nan::New(handles.size()); + Napi::Array results = Napi::Array::New(env, handles.size()); for (size_t i = 0; i < handles.size(); ++i) { handles[i]->SyncProperties(); - Nan::Set(results, i, handles[i]->handle()); + results[i] = handles[i]->Value(); } - v8::Local argv[] = {results}; - - res.runInAsyncScope(Nan::New(this->persistent()), "execute", 1, argv); + Napi::Function execute = + Value().As().Get("execute").As(); + execute.Call(Value(), {results}); } void ShadowNode::CatchException(std::exception_ptr e_ptr) { try { std::rethrow_exception(e_ptr); } catch (const std::exception& e) { - Nan::ThrowError(e.what()); - } -} - -void ShadowNode::New(const Nan::FunctionCallbackInfo& info) { - if (info.IsConstructCall()) { - // Invoked as constructor: `new ShadowNode(...)` - ShadowNode* obj = new ShadowNode(); - obj->Wrap(info.This()); - info.GetReturnValue().Set(info.This()); + Napi::Error::New(Env(), e.what()).ThrowAsJavaScriptException(); } } diff --git a/src/shadow_node.hpp b/src/shadow_node.h similarity index 63% rename from src/shadow_node.hpp rename to src/shadow_node.h index e1b7f456..5c76f007 100644 --- a/src/shadow_node.hpp +++ b/src/shadow_node.h @@ -12,25 +12,26 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SRC_SHADOW_NODE_HPP_ -#define SRC_SHADOW_NODE_HPP_ +#ifndef SRC_SHADOW_NODE_H_ +#define SRC_SHADOW_NODE_H_ -#include +#include #include #include #include -#include "executor.hpp" +#include "executor.h" 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); @@ -41,18 +42,18 @@ class ShadowNode : public Nan::ObjectWrap, public Executor::Delegate { void Execute(const std::vector& handles) override; void CatchException(std::exception_ptr e_ptr) override; - private: - ShadowNode(); + explicit ShadowNode(const Napi::CallbackInfo& info); ~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); + private: + static Napi::FunctionReference constructor; + + Napi::Value Stop(const Napi::CallbackInfo& info); + Napi::Value Start(const Napi::CallbackInfo& info); + Napi::Value SyncHandles(const Napi::CallbackInfo& info); + Napi::Value SpinOnce(const Napi::CallbackInfo& info); + Napi::Value HandleGetter(const Napi::CallbackInfo& info); + void HandleSetter(const Napi::CallbackInfo& info, const Napi::Value& value); std::unique_ptr handle_manager_; std::unique_ptr executor_; @@ -60,4 +61,4 @@ class ShadowNode : public Nan::ObjectWrap, public Executor::Delegate { } // namespace rclnodejs -#endif // SRC_SHADOW_NODE_HPP_ +#endif // SRC_SHADOW_NODE_H_