Skip to content
Merged
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
11 changes: 11 additions & 0 deletions packages/roslib/src/core/Action.ts
Original file line number Diff line number Diff line change
Expand Up @@ -134,6 +134,17 @@ export default class Action<
});
}

/**
* Cancels all action goals.
*/
cancelAllGoals() {
this.ros.callOnConnection({
op: "call_service",
service: `${this.name}/_action/cancel_goal`,
args: {},
});
}

/**
* Advertise the action. This turns the Action object from a client
* into a server. The callback will be called with every goal sent to this action.
Expand Down
208 changes: 147 additions & 61 deletions packages/roslib/test/examples/fibonacci.example.ts
Original file line number Diff line number Diff line change
@@ -1,65 +1,151 @@
import { describe, it, expect } from "vitest";
import * as ROSLIB from "../../src/RosLib.ts";

// Noetic is the only version of ROS 1 we support, so we skip based on distro name
// instead of adding extra plumbing for ROS_VERSION.
describe.skipIf(process.env["ROS_DISTRO"] !== "noetic")(
"ROS 1 Fibonacci Example",
function () {
it(
"Fibonacci",
() =>
new Promise<void>((done) => {
const ros = new ROSLIB.Ros({
url: "ws://localhost:9090",
});
/*
* The ActionClient
* ----------------
*/

const fibonacciClient = new ROSLIB.ActionClient({
ros: ros,
serverName: "/fibonacci",
actionName: "actionlib_tutorials/FibonacciAction",
});

// Create a goal.
const goal = new ROSLIB.Goal({
actionClient: fibonacciClient,
goalMessage: {
order: 7,
},
});

// Print out their output into the terminal.
const items = [
{ sequence: [0, 1, 1] },
{ sequence: [0, 1, 1, 2] },
{ sequence: [0, 1, 1, 2, 3] },
{ sequence: [0, 1, 1, 2, 3, 5] },
{ sequence: [0, 1, 1, 2, 3, 5, 8] },
{ sequence: [0, 1, 1, 2, 3, 5, 8, 13] },
{ sequence: [0, 1, 1, 2, 3, 5, 8, 13, 21] },
];
goal.on("feedback", function (feedback) {
expect(feedback).to.eql(items.shift());
});
goal.on("result", function (result) {
expect(result).to.eql({ sequence: [0, 1, 1, 2, 3, 5, 8, 13, 21] });
const fibonacciItems = [
{ sequence: [0, 1, 1] },
{ sequence: [0, 1, 1, 2] },
{ sequence: [0, 1, 1, 2, 3] },
{ sequence: [0, 1, 1, 2, 3, 5] },
{ sequence: [0, 1, 1, 2, 3, 5, 8] },
{ sequence: [0, 1, 1, 2, 3, 5, 8, 13] },
{ sequence: [0, 1, 1, 2, 3, 5, 8, 13, 21] },
];

describe("Fibonacci Example", function () {
// Noetic is the only version of ROS 1 we support, so we skip based on distro name
// instead of adding extra plumbing for ROS_VERSION.
it.skipIf(process.env["ROS_DISTRO"] !== "noetic")(
"Fibonacci ROS 1",
() =>
new Promise<void>((done) => {
const ros = new ROSLIB.Ros({
url: "ws://localhost:9090",
});
/*
* The ActionClient
* ----------------
*/

const fibonacciClient = new ROSLIB.ActionClient({
ros: ros,
serverName: "/fibonacci",
actionName: "actionlib_tutorials/FibonacciAction",
});

// Create a goal.
const goal = new ROSLIB.Goal({
actionClient: fibonacciClient,
goalMessage: {
order: 7,
},
});

goal.on("feedback", function (feedback) {
expect(feedback).to.eql(fibonacciItems.shift());
});
goal.on("result", function (result) {
expect(result).to.eql({ sequence: [0, 1, 1, 2, 3, 5, 8, 13, 21] });
done();
});

/*
* Send the goal to the action server.
* The timeout is to allow rosbridge to properly subscribe all the
* Action topics - otherwise, the first feedback message might get lost
*/
setTimeout(function () {
goal.send();
}, 100);
}),
8000,
);

it.skipIf(process.env["ROS_DISTRO"] !== "humble")(
"Fibonacci ROS 2",
() =>
new Promise<void>((done) => {
const ros = new ROSLIB.Ros({
url: "ws://localhost:9090",
});
/*
* The Action
* ----------------
*/

const fibonacciAction = new ROSLIB.Action({
ros,
name: "/fibonacci",
actionType: "action_tutorials_interfaces/action/Fibonacci",
});

const goal = { order: 8 };

/*
* Send the goal to the action server.
*/
fibonacciAction.sendGoal(
goal,
(result) => {
expect(result).to.eql({
sequence: [0, 1, 1, 2, 3, 5, 8, 13, 21],
});
done();
});

/*
* Send the goal to the action server.
* The timeout is to allow rosbridge to properly subscribe all the
* Action topics - otherwise, the first feedback message might get lost
*/
setTimeout(function () {
goal.send();
}, 100);
}),
8000,
);
},
);
},
(feedback) => {
expect(feedback).to.eql(fibonacciItems.shift());
},
);
}),
8000,
);

it.skipIf(process.env["ROS_DISTRO"] !== "humble")(
"Fibonacci ROS 2, cancel all goals",
async () => {
const ros = new ROSLIB.Ros();
await ros.connect("ws://localhost:9090");

let resultCalled = false;
let failedCalled = false;

/*
* The Action
* ----------------
*/
const fibonacciAction = new ROSLIB.Action({
ros,
name: "/fibonacci",
actionType: "action_tutorials_interfaces/action/Fibonacci",
});

const goal = { order: 8 };

/*
* Send the goal to the action server.
*/
fibonacciAction.sendGoal(
goal,
// result callback.
() => {
resultCalled = true;
},
// feedback callback.
undefined,
// failed callback
() => {
failedCalled = true;
},
);

/*
* Cancel all goals.
*/
fibonacciAction.cancelAllGoals();

setTimeout(() => {
expect(failedCalled).toBe(true);
expect(resultCalled).toBe(false);
}, 500); // wait 500ms to be sure the server handled the cancel request.
},
);
});