Skip to content

support node 14 #723

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Closed
wants to merge 5 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions .circleci/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ jobs:
- run: wget -qO- https://github.com/raw/nvm-sh/nvm/v0.37.0/install.sh | bash
- run: echo "source $HOME/.bashrc" >> ~/.bash_profile
- run: cat ~/.bash_profile
- run: nvm install v12.20.0
- run: nvm alias default v12.20.0
- run: nvm install 14
- run: nvm alias default 14
- run: node --version && npm --version && rm -rf ./node_modules/
- run: source ~/ros2_install/ros2-osx/local_setup.bash && git submodule init && git submodule update && npm install --python=python2.7
- run: export PATH="/usr/local/opt/python@2/libexec/bin:$PATH" && npm run lint
Expand Down
2 changes: 1 addition & 1 deletion Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ RUN rosdep install --from-paths $ROS2_WS/ros2-linux/share --ignore-src --rosdist
RUN echo "source $ROS2_WS/ros2-linux/local_setup.bash" >> $HOME/.bashrc

# Install nvm, Node.js and node-gyp
ENV NODE_VERSION v12.20.0
ENV NODE_VERSION 14
RUN wget -qO- https://github.com/raw/nvm-sh/nvm/v0.37.0/install.sh | bash

ENV PATH /bin/versions/node/$NODE_VERSION/bin:$PATH
2 changes: 1 addition & 1 deletion appveyor.yml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ branches:
image: Visual Studio 2019

environment:
nodejs_version: "12"
nodejs_version: "14"
PYTHON3: "c:\\Python37-x64"
PYTHON2: "c:\\Python27"

Expand Down
18 changes: 9 additions & 9 deletions benchmark/rclcpp/service/client-stress-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,10 @@
#include "utilities.hpp"

void ShowUsage(const std::string name) {
std::cerr << "Usage: " << name << " [options]\n"
<< "\nOptions:\n"
<< "\n--run <n> \tHow many times to run\n"
<< "--help \toutput usage information"
<< std::endl;
std::cerr << "Usage: " << name << " [options]\n"
<< "\nOptions:\n"
<< "\n--run <n> \tHow many times to run\n"
<< "--help \toutput usage information" << std::endl;
}

int main(int argc, char* argv[]) {
Expand All @@ -36,15 +35,16 @@ int main(int argc, char* argv[]) {
for (int i = 1; i < argc; i++) {
std::string arg = argv[i];
if ((arg == "-h") || (arg == "--help")) {
ShowUsage(argv[0]);
return 0;
ShowUsage(argv[0]);
return 0;
} else if (arg.find("--run=") != std::string::npos) {
total_times = std::stoi(arg.substr(arg.find("=") + 1));
total_times = std::stoi(arg.substr(arg.find("=") + 1));
}
}
printf(
"The client will send a GetMap request continuously until receiving "
"response %d times.\n", total_times);
"response %d times.\n",
total_times);

auto start = std::chrono::high_resolution_clock::now();
auto node = rclcpp::Node::make_shared("stress_client_rclcpp");
Expand Down
36 changes: 18 additions & 18 deletions benchmark/rclcpp/topic/publisher-stress-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,28 +23,27 @@
#include "utilities.hpp"

void ShowUsage(const std::string name) {
std::cerr << "Usage: " << name << " [options]\n"
<< "\nOptions:\n"
<< "\n--size=[size_kb]\tThe block size\n"
<< "--run=<n> \tHow many times to run\n"
<< "--help \toutput usage information"
<< std::endl;
std::cerr << "Usage: " << name << " [options]\n"
<< "\nOptions:\n"
<< "\n--size=[size_kb]\tThe block size\n"
<< "--run=<n> \tHow many times to run\n"
<< "--help \toutput usage information" << std::endl;
}

int main(int argc, char* argv[]) {
auto total_times = 0;
auto amount = 0;

for (int i = 1; i < argc; i++) {
std::string arg = argv[i];
if ((arg == "-h") || (arg == "--help")) {
ShowUsage(argv[0]);
return 0;
} else if (arg.find("--size=") != std::string::npos) {
amount = std::stoi(arg.substr(arg.find("=") + 1));
} else if (arg.find("--run=") != std::string::npos) {
total_times = std::stoi(arg.substr(arg.find("=") + 1));
}
std::string arg = argv[i];
if ((arg == "-h") || (arg == "--help")) {
ShowUsage(argv[0]);
return 0;
} else if (arg.find("--size=") != std::string::npos) {
amount = std::stoi(arg.substr(arg.find("=") + 1));
} else if (arg.find("--run=") != std::string::npos) {
total_times = std::stoi(arg.substr(arg.find("=") + 1));
}
}

rclcpp::init(argc, argv);
Expand Down Expand Up @@ -74,12 +73,13 @@ int main(int argc, char* argv[]) {

printf(
"The publisher will publish a UInt8MultiArray topic(contains a size of "
"%dKB array) %d times.\n", amount, total_times);
"%dKB array) %d times.\n",
amount, total_times);

auto start = std::chrono::high_resolution_clock::now();
auto node = rclcpp::Node::make_shared("stress_publisher_rclcpp");
auto publisher =
node->create_publisher<std_msgs::msg::UInt8MultiArray>("stress_topic", 10);
auto publisher = node->create_publisher<std_msgs::msg::UInt8MultiArray>(
"stress_topic", 10);
auto sent_times = 0;

while (rclcpp::ok()) {
Expand Down
3 changes: 1 addition & 2 deletions benchmark/rclcpp/topic/subscription-stress-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,7 @@ int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("stress_subscription_rclcpp");
auto sub = node->create_subscription<std_msgs::msg::UInt8MultiArray>(
"stress_topic",
10,
"stress_topic", 10,
[](std_msgs::msg::UInt8MultiArray::SharedPtr msg) { (void)msg; });
rclcpp::spin(node);

Expand Down
6 changes: 0 additions & 6 deletions rosidl_gen/deallocator.js
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,6 @@
const rclnodejs = require('bindings')('rclnodejs');

let deallocator = {
delayFreeStructMember(refObj, type, name) {
return rclnodejs.createArrayBufferCleaner(
refObj.ref(),
type.fields[name].offset
);
},
freeStructMember(refObj, type, name) {
rclnodejs.freeMemeoryAtOffset(refObj.ref(), type.fields[name].offset);
},
Expand Down
3 changes: 1 addition & 2 deletions rosidl_gen/templates/message.dot
Original file line number Diff line number Diff line change
Expand Up @@ -750,8 +750,7 @@ class {{=arrayWrapper}} {
{{? usePlainTypedArray}}
const byteLen = refObject.size * ref.types.{{=currentTypedArrayElementType}}.size;
// An ArrayBuffer object that doesn't hold the ownership of the address
const arrayBuffer = rclnodejs.createArrayBufferFromAddress(refObject.data, byteLen);
this._wrappers = new {{=currentTypedArray}}(arrayBuffer);
this._wrappers = new {{=currentTypedArray}}(refObject.data.buffer, refObject.data.byteOffset, refObject.size);
{{?? true}}
let refObjectArray = this._refObject.data;
refObjectArray.length = this._refObject.size;
Expand Down
3 changes: 1 addition & 2 deletions src/rcl_bindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -909,6 +909,7 @@ NAN_METHOD(RclTakeRequest) {
return;
}

free(header);
info.GetReturnValue().Set(Nan::Undefined());
}

Expand Down Expand Up @@ -1794,8 +1795,6 @@ std::vector<BindingMethod> binding_methods = {
{"getNamespace", GetNamespace},
{"initString", InitString},
{"freeMemeoryAtOffset", FreeMemeoryAtOffset},
{"createArrayBufferFromAddress", CreateArrayBufferFromAddress},
{"createArrayBufferCleaner", CreateArrayBufferCleaner},
{"setLoggerLevel", setLoggerLevel},
{"getLoggerEffectiveLevel", GetLoggerEffectiveLevel},
{"getNodeLoggerName", GetNodeLoggerName},
Expand Down