Skip to content
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

fix tests in foxy/ubuntu-20.04 #749

Draft
wants to merge 8 commits into
base: develop
Choose a base branch
from
Draft
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
2 changes: 1 addition & 1 deletion .circleci/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ jobs:
- ./node_modules
# Test
- run: npm install istanbul coveralls
- run: source ~/ros2_install/ros2-osx/local_setup.bash && export OPENSSL_ROOT_DIR="/usr/local/opt/openssl" && node scripts/compile_tests.js && node --expose-gc ./node_modules/.bin/istanbul cover ./scripts/run_test.js --report lcovonly && cat ./coverage/lcov.info | ./node_modules/coveralls/bin/coveralls.js && rm -rf ./coverage
- run: source ~/ros2_install/ros2-osx/local_setup.bash && export OPENSSL_ROOT_DIR="/usr/local/opt/openssl" && node scripts/compile_tests.js && . install/setup.bash && node --expose-gc ./node_modules/.bin/istanbul cover ./scripts/run_test.js --report lcovonly && cat ./coverage/lcov.info | ./node_modules/coveralls/bin/coveralls.js && rm -rf ./coverage
# Teardown
- run: find $HOME/Library/Developer/Xcode/DerivedData -name '*.xcactivitylog' -exec cp {} $CIRCLE_ARTIFACTS/xcactivitylog \; || true
# Save test results
Expand Down
20 changes: 10 additions & 10 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 All @@ -60,7 +60,7 @@ int main(int argc, char* argv[]) {
} else {
auto result_future = client->async_send_request(request);
if (rclcpp::spin_until_future_complete(node, result_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS) {
rclcpp::FutureReturnCode::SUCCESS) {
RCLCPP_ERROR(node->get_logger(), "service call failed.");
return 1;
}
Expand Down
2 changes: 1 addition & 1 deletion package.json
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
"scripts": {
"install": "node-gyp rebuild",
"docs": "cd docs && make",
"test": "node ./scripts/compile_tests.js && node --expose-gc ./scripts/run_test.js && npm run dtslint",
"test": "node ./scripts/compile_tests.js && node ./scripts/test.js && npm run dtslint",
"dtslint": "node ./scripts/generate_tsd.js && dtslint test/types",
"lint": "eslint --max-warnings=0 --ext js,ts index.js types scripts lib example rosidl_gen rosidl_parser test benchmark/rclnodejs && node ./scripts/cpplint.js",
"postinstall": "node scripts/generate_messages.js",
Expand Down
109 changes: 9 additions & 100 deletions scripts/compile_tests.js
Original file line number Diff line number Diff line change
Expand Up @@ -14,111 +14,20 @@

'use strict';

/* eslint-disable */
const fs = require('fs-extra');
const os = require('os');
const path = require('path');
const child = require('child_process');

var rootDir = path.dirname(__dirname);
var testCppDir = path.join(rootDir, 'test', 'cpp');

function getExecutable(input) {
if (os.platform() === 'win32') return input + '.exe';

return input;
}

var publisher = getExecutable('publisher_msg');
var subscription = getExecutable('subscription_msg');
var listener = getExecutable('listener');
var client = getExecutable('add_two_ints_client');

function getExecutablePath(input) {
var releaseDir = '';
if (os.platform() === 'win32') releaseDir = 'Release';

return path.join(rootDir, 'build', 'cpp_nodes', releaseDir, input);
}

var publisherPath = getExecutablePath(publisher);
var subscriptionPath = getExecutablePath(subscription);
var listenerPath = getExecutablePath(listener);
var clientPath = getExecutablePath(client);

function copyFile(platform, srcFile, destFile) {
if (!fs.existsSync(destFile)) {
if (os.platform() === 'win32') {
child.spawn('cmd.exe', ['/c', `copy ${srcFile} ${destFile}`]);
} else {
child.spawn('sh', ['-c', `cp ${srcFile} ${destFile}`]);
}
}
}

function copyAll(fileList, dest) {
fileList.forEach((file) => {
copyFile(os.platform(), file, path.join(dest, path.basename(file)));
console.log(`cpp executables ${file} is copied to test/cpp.`);
});
}

function copyPkgToRos2(pkgName) {
let srcDir = path.join(rootDir, 'install', pkgName);
let destDir = process.env.COLCON_PREFIX_PATH;
if (os.platform() === 'win32') {
child.spawn('cmd.exe', ['/c', `xcopy ${srcDir} ${destDir} /O /X /E /K`]);
} else {
child.spawn('sh', ['-c ', '"' + `cp -fr ${srcDir}/. ${destDir}` + '"'], {
shell: true,
});
}
}

var subProcess = child.spawn('colcon', [
'build',
'--event-handlers',
'console_cohesion+',
'--base-paths',
const basePaths = [
path.join(rootDir, 'test', 'rclnodejs_test_msgs'),
]);
subProcess.on('close', (code) => {
copyPkgToRos2('rclnodejs_test_msgs');
testCppDir,
];

// foxy has a bug where fastRTPS can't be found, a workaround is to add
// AMENT_PREFIX_PATH to CMAKE_PREFIX_PATH
process.env.CMAKE_PREFIX_PATH = `${process.env.CMAKE_PREFIX_PATH}:${process.env.AMENT_PREFIX_PATH}`;
child.spawnSync('colcon', ['build', '--base-paths', ...basePaths], {
stdio: 'inherit',
});
subProcess.stdout.on('data', (data) => {
console.log(`${data}`);
});
subProcess.stderr.on('data', (data) => {
console.log(`${data}`);
});

if (
!fs.existsSync(publisherPath) &&
!fs.existsSync(subscriptionPath) &&
!fs.existsSync(listenerPath) &&
!fs.existsSync(clientPath)
) {
var compileProcess = child.spawn('colcon', [
'build',
'--base-paths',
testCppDir,
]);
compileProcess.on('close', (code) => {
copyAll(
[publisherPath, subscriptionPath, listenerPath, clientPath],
testCppDir
);
});
compileProcess.stdout.on('data', (data) => {
console.log(`${data}`);
});
compileProcess.stderr.on('data', (data) => {
console.log(`${data}`);
});
} else {
copyAll(
[publisherPath, subscriptionPath, , listenerPath, clientPath],
testCppDir
);
}
/* eslint-enable */
8 changes: 0 additions & 8 deletions scripts/run_test.js
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,6 @@ const Mocha = require('mocha');
const os = require('os');
const path = require('path');

let rootDir = path.dirname(__dirname);
let actionPath = path.join(rootDir, 'test', 'ros1_actions');
process.env.AMENT_PREFIX_PATH =
process.env.AMENT_PREFIX_PATH + path.delimiter + actionPath;
let msgPath = path.join(rootDir, 'test', 'rclnodejs_test_msgs');
process.env.AMENT_PREFIX_PATH =
process.env.AMENT_PREFIX_PATH + path.delimiter + msgPath;

fs.remove(path.join(path.dirname(__dirname), 'generated'), (err) => {
if (!err) {
let mocha = new Mocha();
Expand Down
36 changes: 36 additions & 0 deletions scripts/test.js
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
/*
* Copyright (C) 2020 Open Source Robotics Foundation
*
* 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.
*
*/

'use strict';

const os = require('os');
const childprocess = require('child_process');
const path = require('path');

const rootDir = path.dirname(__dirname);

if (os.platform() === 'win32') {
childprocess.execSync(
`call ${rootDir}\\install\\setup.bat && node --expose-gc ${rootDir}\\scripts\\run_test.js`,
{ stdio: 'inherit' }
);
} else {
childprocess.execSync(
`. ${rootDir}/install/setup.bash && node --expose-gc ${rootDir}/scripts/run_test.js`,
{ stdio: 'inherit', shell: 'bash' }
);
}
41 changes: 20 additions & 21 deletions test/cpp/add_two_ints_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,47 +17,45 @@
#include <memory>
#include <string>

#include "example_interfaces/srv/add_two_ints.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rcutils/cmdline_parser.h"

#include "std_msgs/msg/int8.hpp"
#include "example_interfaces/srv/add_two_ints.hpp"

using namespace std::chrono_literals;

rclcpp::Publisher<std_msgs::msg::Int8>::SharedPtr publisher = nullptr;

void print_usage()
{
void print_usage() {
printf("Usage for add_two_ints_client app:\n");
printf("add_two_ints_client [-t topic_name] [-h]\n");
printf("options:\n");
printf("-h : Print this help function.\n");
printf("-s service_name : Specify the service name for this client. Defaults to add_two_ints.\n");
printf(
"-s service_name : Specify the service name for this client. Defaults to "
"add_two_ints.\n");
}

// TODO(wjwwood): make this into a method of rclcpp::client::Client.
example_interfaces::srv::AddTwoInts_Response::SharedPtr send_request(
rclcpp::Node::SharedPtr node,
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client,
example_interfaces::srv::AddTwoInts_Request::SharedPtr request)
{
rclcpp::Node::SharedPtr node,
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client,
example_interfaces::srv::AddTwoInts_Request::SharedPtr request) {
auto result = client->async_send_request(request);
// Wait for the result.
if (rclcpp::spin_until_future_complete(node, result) ==
rclcpp::executor::FutureReturnCode::SUCCESS)
{
rclcpp::FutureReturnCode::SUCCESS) {
return result.get();
} else {
return NULL;
}
}

int main(int argc, char ** argv)
{
int main(int argc, char** argv) {
rclcpp::init(argc, argv);

auto node = rclcpp::Node::make_shared("add_two_ints_client", rclcpp::NodeOptions());
auto node =
rclcpp::Node::make_shared("add_two_ints_client", rclcpp::NodeOptions());

if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
print_usage();
Expand All @@ -70,35 +68,36 @@ int main(int argc, char ** argv)
}
auto client = node->create_client<example_interfaces::srv::AddTwoInts>(topic);

auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
auto request =
std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = 2;
request->b = 3;

while (!client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
printf("add_two_ints_client was interrupted while waiting for the service. Exiting.\n");
printf(
"add_two_ints_client was interrupted while waiting for the service. "
"Exiting.\n");
return 0;
}
printf("service not available, waiting again...\n");
}

auto msg = std::make_shared<std_msgs::msg::Int8>();
publisher = node->create_publisher<std_msgs::msg::Int8>(
std::string("back_") + topic, 7);

std::string("back_") + topic, 7);

auto future_result = client->async_send_request(request);

// Wait for the result.
if (rclcpp::spin_until_future_complete(node, future_result) ==
rclcpp::executor::FutureReturnCode::SUCCESS)
{
rclcpp::FutureReturnCode::SUCCESS) {
// printf("Result of add_two_ints: %zd\n", future_result.get()->sum);
msg->data = future_result.get()->sum;
publisher->publish(*msg);
} else {
printf("add_two_ints_client_async was interrupted. Exiting.\n");
}
}

rclcpp::spin(node);
return 0;
Expand Down