ActionClient¶
An action client can be used to send goals to an ActionServer. One ActionClient has to have a single type of action but can send multiple goals simultaneously. Process can be tracked using either a goal handle manually or using callbacks.
An ActionClient can be created using the Ros2 Singleton as follows:
Item {
// ...
property var fibonacciClient: Ros2.createActionClient("fibonacci", "action_tutorials_interfaces/action/Fibonacci")
// ...
}
In this example an action client is created using the action_tutorials_interfaces/action/Fibonacci
action
(it is important to use the complete action type here, not any part like the ActionGoal) using the name
fibonacci on which an ActionServer should be registered (You can use the action tutorials fibonacci_server).
To send a goal, you can use the sendGoalAsync function:
if (!fibonacciClient.ready) {
Ros2.error("Action client not ready yet!")
return
}
goal_handle = fibonacciClient.sendGoalAsync({ order: numberInput.value }, {
// These callbacks are optional
onGoalResponse(goal_handle) {
if (!goal_handle) {
// Goal was rejected
return
}
// Handle goal accepted
},
onFeedback(goal_hamdle, feedback) {
// Handle feedback from action server
},
onResult(result) {
// Handle result from action server
let goalId = result.goalId
if (result.code == ActionGoalStatus.Succeeded) {
// Handle success
let goalResult = result.result
} else if (result.code == ActionGoalStatus.Canceled) {
// Handle canceled
} else if (result.code == ActionGoalStatus.Aborted) {
// Handle aborted
}
}
})
The sendGoalAsync
function takes 2 parameters: the goal and an optional options object with optional
callbacks for onGoalResponse, onFeedback and onResult.
Both callbacks are optional. It returns a GoalHandle which can be used query to state of the goal or
to cancel the goal. The goal_handle passed to the callbacks and the one returned are the same.
API¶
-
class ActionClient : public QObjectRos2¶
Public Functions
-
QObject *sendGoalAsync(const QVariantMap &goal, QJSValue options = QJSValue())¶
Sends a goal to the action server if it is connected.
- Parameters:
goal – The goal that is sent to the action server.
options – An object with optional callback members for:
goal_response: onGoalResponse(goal_handle) goal_handle will be null if goal was rejected
feedback: onFeedback(goal_handle, feedback_message)
result: onResult(wrapped_result) where wrapped_result has a goalId, result code and result message.
- Returns:
null if the action server is not connected, otherwise a GoalHandle keeping track of the state of the goal.
-
void cancelAllGoals()¶
Cancels all goals that are currently tracked by this client.
-
void cancelGoalsBefore(const qml_ros2_plugin::Time &time)¶
Cancels all goals that were sent at and before the given ROS time by this client. Use Time.now() to obtain the current ROS time which can differ from the actual time.
-
void cancelGoalsBefore(const QDateTime &time)¶
Cancels all goals that were sent at and before the given ROS time by this client. Use Time.now() to obtain the current ROS time which can differ from the actual time.
Signals
-
void serverReadyChanged()¶
Emitted when the connected status changes, e.g., when the client connected to the server.
Properties
- bool ready
True if the ActionClient is connected to the ActionServer, false otherwise.
- QString actionType
The type of the action. Example: action_tutorials_interfaces/action/Fibonacci.
-
QObject *sendGoalAsync(const QVariantMap &goal, QJSValue options = QJSValue())¶
-
class GoalHandle : public QObjectRos2¶
Public Functions
-
void cancel()¶
Sends a cancellation request to the ActionServer.
Properties
- qml_ros2_plugin::action_goal_status::GoalStatus status
The goal status in form of an action_goal_status enum value: Aborted, Accepted, Canceled, Canceling, Executing, Succeeded, Unknown
-
void cancel()¶