@@ -38,6 +38,7 @@ import rclpy
3838from rclpy .callback_groups import ReentrantCallbackGroup
3939from rclpy .clock import Clock , ClockType
4040from rclpy .node import Node
41+ from rclpy .qos import qos_profile_parameters
4142
4243from rosapi import glob_helper , objectutils , params , proxy
4344from rosapi_msgs .msg import TypeDef
@@ -129,25 +130,39 @@ class Rosapi(Node):
129130 self .get_service_response_details ,
130131 )
131132 self .create_service (
132- SetParam , "~/set_param" , self .set_param , callback_group = ReentrantCallbackGroup ()
133+ SetParam ,
134+ "~/set_param" ,
135+ self .set_param ,
136+ callback_group = ReentrantCallbackGroup (),
137+ qos_profile = qos_profile_parameters ,
133138 )
134139 self .create_service (
135- GetParam , "~/get_param" , self .get_param , callback_group = ReentrantCallbackGroup ()
140+ GetParam ,
141+ "~/get_param" ,
142+ self .get_param ,
143+ callback_group = ReentrantCallbackGroup (),
144+ qos_profile = qos_profile_parameters ,
136145 )
137146 self .create_service (
138- HasParam , "~/has_param" , self .has_param , callback_group = ReentrantCallbackGroup ()
147+ HasParam ,
148+ "~/has_param" ,
149+ self .has_param ,
150+ callback_group = ReentrantCallbackGroup (),
151+ qos_profile = qos_profile_parameters ,
139152 )
140153 self .create_service (
141154 DeleteParam ,
142155 "~/delete_param" ,
143156 self .delete_param ,
144157 callback_group = ReentrantCallbackGroup (),
158+ qos_profile = qos_profile_parameters ,
145159 )
146160 self .create_service (
147161 GetParamNames ,
148162 "~/get_param_names" ,
149163 self .get_param_names ,
150164 callback_group = ReentrantCallbackGroup (),
165+ qos_profile = qos_profile_parameters ,
151166 )
152167 self .create_service (GetTime , "~/get_time" , self .get_time )
153168 self .create_service (GetROSVersion , "~/get_ros_version" , self .get_ros_version )
0 commit comments