.. index:: ask .. _skill-ask: Skill ``ask`` ----------------------------------------------------------- - **Version**: 1.0.0 - **Default path**: ``/skill/ask`` - **Datatype**: :action:`communication_skills/action/Ask` - **Definition source**: ``package.xml`` in `ros4hri/communication_skills `_ A specialization of the :skill:`chat` where the role is predefined and the dialogue is always initiated by the robot. See :ref:`dialogue_management` for details. Input parameters ~~~~~~~~~~~~~~~~ - **question** ``string``, *required* The question to be asked to the user. It is used to generate the initial utterance of the dialogue. - **answers_schema** ``string``, *required* The serialized JSON object of pieces of information to be retrieved through the chat. The keys correspond to the info required, while the values follow the `JSON schema format for object properties `_. For example, if the required information is the person age, the dictionary could be the following: .. code:: json {"age": {"type": "integer", "minimum": 0}} For a simple yes/no question, you could have instead: .. code:: json {"response": {"type": "boolean"}} - **person_id** ``string``, default: ``""`` If targeting a specific person, the ID of the person. - **group_id** ``string``, default: ``""`` If targeting a group of people, the ID of the group *(currently not supported)*. - **meta.priority** ``integer``, default: ``128`` Between 0 and 255. Higher value means that this skill invokation will have higher priority. Output fields ~~~~~~~~~~~~~ - **answers** ``object`` The serialized JSON object containing the pieces retrieved from the chat, depending on the answers_schema. For *age* example above, the result might be: .. code:: json {"age": 42} Quick snippets ~~~~~~~~~~~~~~ .. tabs:: .. tab:: Command-line Call the skill from the command-line .. code-block:: sh $ ros2 action send_goal /skill/ask communication_skills/action/Ask # then press Tab to complete the message prototype .. tab:: ROS 2 action (Python) Call the action from a Python script: .. code-block:: python #!/usr/bin/env python import rclpy from rclpy.action import ActionClient from rclpy.node import Node from communication_skills.action import class AskActionClient(Node): def __init__(self): super().__init__('ask_client') self._action_client = ActionClient(self, , '/skill/ask') def send_goal(self, a, b): goal_msg = .Goal() # TODO: adapt to the action's parameters # check the AskGoal message # definition for the possible goal parameters # goal_msg.a = a # goal_msg.b = b self._action_client.wait_for_server() return self._action_client.send_goal_async(goal_msg) if __name__ == '__main__': rclpy.init(args=args) action_client = ActionClient() # TODO: adapt to your action's parameters future = action_client.send_goal(a, b) rclpy.spin_until_future_complete(action_client, future) rclpy.shutdown() .. tab:: ROS 2 action (C++) Call the action from a C++ program: .. code-block:: cpp #include #include #include #include #include #include #include "communication_skills/action/.hpp" #include "rclcpp/rclcpp.hpp" #include "rclcpp_action/rclcpp_hpp" #include "rclcpp_components/register_node_macro.hpp" using namespace std::chrono_literals; using namespace std; class AskActionClient : public rclcpp::Node { public: using = communication_skills::action::; using GoalHandle = rclcpp_action::ClientGoalHandle<>; explicit AskActionClient(const rclcpp::NodeOptions & options) : Node("ask_action_client", options) { this->client_ptr_ = rclcpp_action::create_client<>( this, ""); this->timer_ = this->create_wall_timer( 500ms, bind(&AskActionClient::send_goal, this)); } void send_goal() { using namespace std::placeholders; this->timer_->cancel(); if (!this->client_ptr_->wait_for_action_server()) { RCLCPP_ERROR(this->get_logger(), "Action server not available after waiting"); rclcpp::shutdown(); } auto goal_msg = ::Goal(); // check the AskGoal message // definition for the possible goal parameters // goal_msg.... = ...; RCLCPP_INFO(this->get_logger(), "Sending goal"); auto send_goal_options = rclcpp_action::Client<>::SendGoalOptions(); send_goal_options.goal_response_callback = bind(&AskActionClient::goal_response_callback, this, _1); send_goal_options.feedback_callback = bind(&AskActionClient::feedback_callback, this, _1, _2); send_goal_options.result_callback = bind(&AskActionClient::result_callback, this, _1); this->client_ptr_->async_send_goal(goal_msg, send_goal_options); } private: rclcpp_action::Client<>::SharedPtr client_ptr_; rclcpp::TimerBase::SharedPtr timer_; void goal_response_callback(const GoalHandle::SharedPtr & goal_handle) { if (!goal_handle) { RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server"); } else { RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result"); } } void feedback_callback( GoalHandle::SharedPtr, const shared_ptr feedback) { stringstream ss; ss << "Next number in sequence received: "; for (auto number : feedback->partial_sequence) { ss << number << " "; } RCLCPP_INFO(this->get_logger(), ss.str().c_str()); } void result_callback(const GoalHandle::WrappedResult & result) { switch (result.code) { case rclcpp_action::ResultCode::SUCCEEDED: break; case rclcpp_action::ResultCode::ABORTED: RCLCPP_ERROR(this->get_logger(), "Goal was aborted"); return; case rclcpp_action::ResultCode::CANCELED: RCLCPP_ERROR(this->get_logger(), "Goal was canceled"); return; default: RCLCPP_ERROR(this->get_logger(), "Unknown result code"); return; } stringstream ss; ss << "Result received: "; for (auto number : result.result->sequence) { ss << number << " "; } RCLCPP_INFO(this->get_logger(), ss.str().c_str()); rclcpp::shutdown(); } }; // class AskActionClient RCLCPP_COMPONENTS_REGISTER_NODE(AskActionClient) .. tab:: QML You can call this skill from QML using the following code snippet. See :ref:`ros_qml_plugin` to learn more. .. code-block:: qml import Ros 2.0 // ... AskSkill { id: mySkill onResult: { console.log("Skill result: " + result); } onFeedback: { console.log("Skill feedback: " + feedback); } } // Call the skill mySkill.ask(); See also ~~~~~~~~ * List of other :ref:`communication_skills` skills