.. _configuring_gen_srv: Generated ROS Service Plugin ############################ Source code generated by :docsite:`cx_ros_comm_gen`. Given the *package* (e.g., ``std_srvs``) and *srv_name* (e.g., ``SetBool``), this document uses the following abbreviations: - **PkgCamel**: CamelCase of *package* (e.g., ``StdSrvs``) - **SrvCamel**: CamelCase of *srv_name* (e.g., ``SetBool``) - **pkg-kebab**: kebab-case of *package* (e.g., ``std-srvs``) - **srv-kebab**: kebab-case of *srv_name* (e.g., ``set-bool``) .. admonition:: Plugin Class cx::CX\ **PkgCamelSrvCamel**\ Plugin (e.g., cx::CXStdSrvsSetBoolPlugin) Configuration ************* This plugin has no specific configuration. Features ******** Facts ~~~~~ .. code-block:: lisp ; Asserted by the respective creat-client function. ; Retracted by the respective destroy-client function. (--client (service ?service-name-string)) ; Asserted by the respective create-service function. ; Retracted by the respective destroy-service function. (--service (name ?service-name-string)) ; Asserted by the callback of a client once a response arrives. ; Process the response and then call response-destroy before retracting! (--response (service ?service-name-string) (msg-ptr ?msg-ptr)) Functions ~~~~~~~~~ .. code-block:: lisp ; Create and destroy clients and services. ; After creating a service, a user-defined function is called whenever a request arrives (--create-service ?service-name) (--destroy-service ?service-name) (--create-client ?service-name) (--destroy-client ?service-name) ; Send a request to a service provider ; Requires the client to be created first using create-client. ; Callback will assert a response fact once received. (--send-request ?msg-ptr ?topic-name) ; Creating, destroying and processing of requests (bind ?msg-ptr (--request-create)) (--request-destroy ?msg-ptr) (--request-set-field ?msg-ptr ?field-name ?field-value) (--request-get-field ?msg-ptr ?field-name) ; Creating, destroying and processing of responses (bind ?msg-ptr (--response-create)) (--response-destroy ?msg-ptr) (--response-set-field ?msg-ptr ?field-name ?field-value) (--response-get-field ?msg-ptr ?field-name) Functions Defined by User ~~~~~~~~~~~~~~~~~~~~~~~~~ The following function is called in the callback of each generated service (if it is defined). Hence, in order to respond to callbacks just define the function and populate it with your callback logic. .. code-block:: lisp ; Define this to react to service calls. ; Read the request and populate the response using appropriate functions above. ; Do not destroy request or response within this function, they are cleaned up upon exiting the function. (--service-callback ?service-name ?const-request-ptr ?response-ptr) Usage Example ************* A minimal working example is provided by the :docsite:`cx_bringup` package. Run it via: .. code-block:: bash ros2 launch cx_bringup cx_launch.py manager_config:=plugin_examples/set_bool_srv.yaml It creates a ``std_srvs/srv/SetBool`` service ``/ros_cx_srv``. The services answers by giving the requested value in success. A simple service call can be made using the ROS CLI tool: .. code-block:: bash ros2 service call /ros_cx_srv std_srvs/srv/SetBool "{data: false}" Additionally, if ``true`` was requested, the example makes a new request with data ``true`` to a service called ``/ros_cx_srv_client``. To start a simple server accepting the request, simply run the following command: .. code-block:: bash ros2 run cx_bringup test_service.py Configuration ~~~~~~~~~~~~~ File :source-master:`cx_bringup/params/plugin_examples/set_bool_srv.yaml`. .. code-block:: yaml clips_manager: ros__parameters: environments: ["cx_set_bool_srvs"] cx_set_bool_srvs: plugins: ["executive", "set_bool", "files"] watch: ["facts", "rules"] executive: plugin: "cx::ExecutivePlugin" publish_on_refresh: false assert_time: true refresh_rate: 10 set_bool: plugin: "cx::CXStdSrvsSetBoolPlugin" files: plugin: "cx::FileLoadPlugin" pkg_share_dirs: ["cx_bringup"] load: [ "clips/plugin_examples/set-bool-srv.clp"] Code ~~~~ File :source-master:`cx_bringup/clips/plugin_examples/set-bool-srv.clp`. .. code-block:: lisp ; this function needs to be defined in order to respond to messages (deffunction std-srvs-set-bool-service-callback (?service-name ?request ?response) (bind ?req-data (std-srvs-set-bool-request-get-field ?request "data")) (printout info "Received request on " ?service-name ". Data: " ?req-data crlf) (printout info "Received " ?req-data ", responding with same value" crlf) (if ?req-data then (std-srvs-set-bool-response-set-field ?response "success" TRUE) (std-srvs-set-bool-response-set-field ?response "message" (str-cat "Received the request: " ?req-data)) (assert (send-request)) else (std-srvs-set-bool-response-set-field ?response "success" FALSE) (std-srvs-set-bool-response-set-field ?response "message" (str-cat "Received the request: " ?req-data)) ) ) (defrule set-bool-client-service-init " Create a simple client and service using the generated bindings. " (not (std-srvs-set-bool-client (service "ros_cx_client"))) (not (std-srvs-set-bool-service (name "ros_cx_srv"))) => (std-srvs-set-bool-create-client "ros_cx_client") (printout info "Created client for /ros_cx_client" crlf) (std-srvs-set-bool-create-service "ros_cx_srv") (printout info "Created service for /ros_cx_srv" crlf) ) (defrule std-srvs-send-out-request-to-outbound ?sr <- (send-request) => ;example usage of sending a request (printout info "Additionally, request as client with data: True" crlf) (bind ?new-req (std-srvs-set-bool-request-create)) (std-srvs-set-bool-request-set-field ?new-req "data" TRUE) (std-srvs-set-bool-send-request ?new-req "ros_cx_client") (std-srvs-set-bool-request-destroy ?new-req) (retract ?sr) ) (defrule set-bool-client-response-received " Create a simple client and service using the generated bindings. " ?msg-fact <- (std-srvs-set-bool-response (service ?service) (msg-ptr ?ptr)) => (bind ?succ (std-srvs-set-bool-response-get-field ?ptr "success")) (bind ?msg (std-srvs-set-bool-response-get-field ?ptr "message")) (printout green "Received response from " ?service " with: " ?succ " (" ?msg ")" crlf) (std-srvs-set-bool-response-destroy ?ptr) (retract ?msg-fact) )