diff --git a/jupyros/ros_widgets.py b/jupyros/ros_widgets.py index 95521ee..617f695 100644 --- a/jupyros/ros_widgets.py +++ b/jupyros/ros_widgets.py @@ -287,4 +287,42 @@ def step_clk(arg): btm_box = widgets.VBox([bgpath_box, options_hbox, duration_box, start_box, que_box, factor_box, delay_box, buttons_hbox, out_box]) widget_list.append(btm_box) vbox = widgets.VBox(children=widget_list) + return vbox + + +def client(srv_name, srv_type): + """ + Create a form widget for message type srv_type. + This function analyzes the fields of srv_type and creates + an appropriate widget. + + @param srv_type The service message type + @param srv_name The service name to call + + @return jupyter widget for display + """ + rospy.wait_for_service(srv_name, timeout=5) + + widget_list = [] + widget_dict = {} + + add_widgets(srv_type._request_class(), widget_dict, widget_list) + call_btn = widgets.Button(description="Call Service") + + def call_srv(arg): + msg_to_send = srv_type._request_class() + widget_dict_to_msg(msg_to_send, widget_dict) + + + try: + service = rospy.ServiceProxy(srv_name, srv_type) + return service(msg_to_send) + except rospy.ServiceException as e: + print("Service call failed: %s" % e) + + call_btn.on_click(call_srv) + + widget_list.append(call_btn) + vbox = widgets.VBox(children=widget_list) + return vbox \ No newline at end of file diff --git a/notebooks/ROS Service.ipynb b/notebooks/ROS Service.ipynb new file mode 100644 index 0000000..97baa93 --- /dev/null +++ b/notebooks/ROS Service.ipynb @@ -0,0 +1,105 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": null, + "id": "3b12ee9d", + "metadata": {}, + "outputs": [], + "source": [ + "%load_ext autoreload\n", + "%autoreload 2\n", + "\n", + "import rospy\n", + "from rospy_tutorials.srv import AddTwoInts, AddTwoIntsResponse\n", + "import jupyros\n", + "from turtlesim.srv import Spawn" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e2d89970", + "metadata": {}, + "outputs": [], + "source": [ + "rospy.init_node(\"adder\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "8725d5f8", + "metadata": {}, + "outputs": [], + "source": [ + "def handle_add_two_ints(req):\n", + " print(\"Returning [%s + %s = %s]\"%(req.a, req.b, (req.a + req.b)))\n", + " return AddTwoIntsResponse(req.a + req.b)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "f218a9a6", + "metadata": {}, + "outputs": [], + "source": [ + "%%thread_cell\n", + "\n", + "srv = rospy.Service('add_two_ints', AddTwoInts, handle_add_two_ints)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "cc3df77b", + "metadata": {}, + "outputs": [], + "source": [ + "jupyros.client('add_two_ints', AddTwoInts)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "0b94e2ad", + "metadata": {}, + "outputs": [], + "source": [ + "# !rosrun turtlesim turtlesim_node" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "539a6cac", + "metadata": {}, + "outputs": [], + "source": [ + "jupyros.client('spawn', Spawn)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.9.12" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +}