Skip to content

Commit be0483f

Browse files
committed
Guard publishFeedback and execute for valid goal states (#1466)
Guard `publishFeedback()` to only publish when the goal is in EXECUTING state; log a warning and return early otherwise. Guard `execute()` to return early if the goal is already executing or no longer active, preventing invalid state transitions that crash rcl. Ported from rclpy commit f76729cf ("publish_feedback should effect only on executing state", ros2/rclpy#1639). **Modified: `lib/action/server_goal_handle.js`** — `publishFeedback()` now checks `this.status !== STATUS_EXECUTING` and warns + returns if not executing. `execute()` now returns early if already executing or if the goal handle is no longer active (terminal state). **Modified: `test/test-action-server.js`** — Added 4 tests: publishFeedback on accepted goal is ignored, publishFeedback on executing goal works normally, publishFeedback after succeed is ignored, and duplicate execute() is a no-op. Fix: #1465
1 parent d8bad5a commit be0483f

3 files changed

Lines changed: 183 additions & 2 deletions

File tree

.github/workflows/linux-x64-build-and-test.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ jobs:
8080
# Install any remaining runtime dependencies using rosdep
8181
rosdep init || true
8282
rosdep update
83-
rosdep install --rosdistro rolling --from-paths /opt/ros/rolling/share --ignore-src -y --skip-keys "cyclonedds fastcdr fastdds iceoryx_binding_c rmw_connextdds rti-connext-dds-7.3.0 urdfdom_headers"
83+
rosdep install --rosdistro rolling --from-paths /opt/ros/rolling/share --ignore-src -y --skip-keys "cyclonedds fastcdr fastdds iceoryx_binding_c rmw_connextdds rti-connext-dds-7.3.0 urdfdom_headers python3-pyqt6.qtsvg"
8484
8585
- name: Install test-msgs and mrpt_msgs on Linux
8686
if: ${{ matrix.ros_distribution != 'rolling' }}

lib/action/server_goal_handle.js

Lines changed: 26 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,11 +82,26 @@ class ServerGoalHandle {
8282
}
8383

8484
/**
85-
* Updates the goal handle with the execute status and begins exection.
85+
* Transitions the goal to the executing state and begins execution.
86+
* Has no effect if the goal is already executing, no longer active, or destroyed.
8687
* @param {function} callback - An optional callback to use instead of the one provided to the action server.
8788
* @returns {undefined}
8889
*/
8990
execute(callback) {
91+
if (this._destroyed) {
92+
return;
93+
}
94+
95+
// Guard: already executing — no-op
96+
if (this.status === ActionInterfaces.GoalStatus.STATUS_EXECUTING) {
97+
return;
98+
}
99+
100+
// Guard: only transition if goal is still active
101+
if (!this.isActive) {
102+
return;
103+
}
104+
90105
if (!this.isCancelRequested) {
91106
this._updateState(GoalEvent.EXECUTE);
92107
}
@@ -105,6 +120,16 @@ class ServerGoalHandle {
105120
return;
106121
}
107122

123+
if (this.status !== ActionInterfaces.GoalStatus.STATUS_EXECUTING) {
124+
this._actionServer._node
125+
.getLogger()
126+
.warn(
127+
`publishFeedback() called on goal ${this.goalId.uuid} ` +
128+
`in status ${this.status}, not executing; ignoring`
129+
);
130+
return;
131+
}
132+
108133
let feedbackMessage =
109134
new this._actionServer.typeClass.impl.FeedbackMessage();
110135
feedbackMessage['goal_id'] = this.goalId;

test/test-action-server.js

Lines changed: 156 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -773,4 +773,160 @@ describe('rclnodejs action server', function () {
773773
ServiceIntrospectionStates.CONTENTS
774774
);
775775
});
776+
777+
it('publishFeedback on accepted (not executing) goal should be ignored', async function () {
778+
let serverGoalHandle;
779+
780+
function handleAcceptedCallback(goalHandle) {
781+
serverGoalHandle = goalHandle;
782+
}
783+
784+
let server = new rclnodejs.ActionServer(
785+
node,
786+
fibonacci,
787+
'fibonacci',
788+
(goalHandle) => {
789+
goalHandle.succeed();
790+
return new Fibonacci.Result();
791+
},
792+
null,
793+
handleAcceptedCallback
794+
);
795+
796+
let goal = new Fibonacci.Goal();
797+
await client.waitForServer(1000);
798+
799+
let feedbackReceived = false;
800+
const handle = await client.sendGoal(goal, () => {
801+
feedbackReceived = true;
802+
});
803+
assert.ok(handle.accepted);
804+
assert.strictEqual(serverGoalHandle.status, GoalStatus.STATUS_ACCEPTED);
805+
806+
// publishFeedback on accepted goal should not publish
807+
const feedback = new Fibonacci.Feedback();
808+
feedback.sequence = [1, 1, 2, 3];
809+
serverGoalHandle.publishFeedback(feedback);
810+
811+
await assertUtils.createDelay(50);
812+
assert.strictEqual(feedbackReceived, false);
813+
814+
// Clean up: execute and succeed
815+
serverGoalHandle.execute();
816+
await handle.getResult();
817+
server.destroy();
818+
});
819+
820+
it('publishFeedback on executing goal should publish normally', async function () {
821+
const sequence = [1, 1, 2, 3];
822+
823+
function executeFeedbackCallback(goalHandle) {
824+
assert.strictEqual(goalHandle.status, GoalStatus.STATUS_EXECUTING);
825+
826+
const feedback = new Fibonacci.Feedback();
827+
feedback.sequence = sequence;
828+
goalHandle.publishFeedback(feedback);
829+
goalHandle.succeed();
830+
831+
return new Fibonacci.Result();
832+
}
833+
834+
let server = new rclnodejs.ActionServer(
835+
node,
836+
fibonacci,
837+
'fibonacci',
838+
executeFeedbackCallback
839+
);
840+
841+
let goal = new Fibonacci.Goal();
842+
await client.waitForServer(1000);
843+
844+
let feedbackMessage;
845+
const handle = await client.sendGoal(
846+
goal,
847+
(feedback) => (feedbackMessage = feedback)
848+
);
849+
assert.ok(handle.accepted);
850+
851+
await assertUtils.createDelay(50);
852+
assert.ok(feedbackMessage);
853+
assert.ok(deepEqual(Int32Array.from(sequence), feedbackMessage.sequence));
854+
855+
server.destroy();
856+
});
857+
858+
it('publishFeedback after succeed should be ignored', async function () {
859+
let serverGoalHandle;
860+
861+
function executeCallback(goalHandle) {
862+
serverGoalHandle = goalHandle;
863+
goalHandle.succeed();
864+
return new Fibonacci.Result();
865+
}
866+
867+
let server = new rclnodejs.ActionServer(
868+
node,
869+
fibonacci,
870+
'fibonacci',
871+
executeCallback
872+
);
873+
874+
let goal = new Fibonacci.Goal();
875+
await client.waitForServer(1000);
876+
877+
let feedbackCount = 0;
878+
const handle = await client.sendGoal(goal, () => {
879+
feedbackCount++;
880+
});
881+
assert.ok(handle.accepted);
882+
883+
await handle.getResult();
884+
assert.strictEqual(serverGoalHandle.status, GoalStatus.STATUS_SUCCEEDED);
885+
886+
// publishFeedback after terminal state should not publish
887+
const feedback = new Fibonacci.Feedback();
888+
feedback.sequence = [1, 1, 2, 3];
889+
serverGoalHandle.publishFeedback(feedback);
890+
891+
await assertUtils.createDelay(50);
892+
assert.strictEqual(feedbackCount, 0);
893+
894+
server.destroy();
895+
});
896+
897+
it('execute() on already executing goal should be a no-op', async function () {
898+
let executeCalled = 0;
899+
900+
function handleAcceptedCallback(goalHandle) {
901+
goalHandle.execute();
902+
// Call execute again — should be a no-op
903+
goalHandle.execute();
904+
}
905+
906+
function executeCallback(goalHandle) {
907+
executeCalled++;
908+
goalHandle.succeed();
909+
return new Fibonacci.Result();
910+
}
911+
912+
let server = new rclnodejs.ActionServer(
913+
node,
914+
fibonacci,
915+
'fibonacci',
916+
executeCallback,
917+
null,
918+
handleAcceptedCallback
919+
);
920+
921+
let goal = new Fibonacci.Goal();
922+
await client.waitForServer(1000);
923+
924+
const handle = await client.sendGoal(goal);
925+
assert.ok(handle.accepted);
926+
927+
await handle.getResult();
928+
assert.strictEqual(executeCalled, 1);
929+
930+
server.destroy();
931+
});
776932
});

0 commit comments

Comments
 (0)