You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I have a node that is launched with some parameters which are considered global, hence, every node can access it through a service call with the default services get_parameters and set_parameters. While I can successfully read the parameters, I'm not able to SET them, i.e. to change their values.
Here the code for the node which is in charge of setting the parameter.
import rclpy
from rclpy.node import Node
from rcl_interfaces.srv import GetParameters, SetParameters
from rcl_interfaces.msg import ParameterDescriptor
from rclpy.node import Node
from rcl_interfaces.msg import Parameter
from std_msgs.msg import String
class MinimalSubscriber(Node):
def __init__(self):
super().__init__('minimal_subscriber',
allow_undeclared_parameters=False,
automatically_declare_parameters_from_overrides=False,
)
# self.publisher_ = self.create_publisher(String, 'topic', 10)
timer_period = 1 # seconds
self.timer = self.create_timer(timer_period, self.on_timer)
self.i = 0
self.set_param_client = self.create_client(SetParameters,
'/global_parameter_server/set_parameters')
self.set_param_service_ready = False
self.param_received = False
def on_timer(self):
if self.set_param_service_ready:
if self.param_received:
# self.get_logger().info('Param received')
pass
else:
if self.result.done():
self.get_logger().info(
f'{self.result.result()}')
self.param_received = True
else:
self.get_logger().info('Request non finished')
else:
if self.set_param_client.service_is_ready():
request = SetParameters.Request()
param = Parameter()
param.name = 'zr30_yolo_detection_flag'
request.parameters = [param]
# Call request
self.result = self.set_param_client.call_async(request)
self.set_param_service_ready = True
else:
# Check if the service is ready
self.get_logger().info('Service is not ready')
def main(args=None):
rclpy.init(args=args)
minimal_publisher = MinimalSubscriber()
rclpy.spin(minimal_publisher)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
The service call is completed, however, it is never successfull since it always gives this reason 'Static parameter cannot be undeclared
[INFO] [launch]: All log files can be found below /home/aut/.ros/log/2023-09-22-12-47-20-725281-aut-7996
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [global_parameter_server-1]: process started with pid [7997]
[INFO] [minimal_subscriber-2]: process started with pid [7999]
[global_parameter_server-1] [INFO] [1695379641.193061411] [global_parameter_server]: GlobalParameterServer started
[global_parameter_server-1] [INFO] [1695379641.194204782] [global_parameter_server]: False
[minimal_subscriber-2] [INFO] [1695379643.236667722] [minimal_subscriber]: rcl_interfaces.srv.SetParameters_Response(results=[rcl_interfaces.msg.SetParametersResult(successful=False, reason='Static parameter cannot be undeclared')])
The text was updated successfully, but these errors were encountered:
value is not set to service call, that will try to set Parameter.Type.NOT_SET. and this is supposed to fail because type is unknow for static typed parameter to set. this is expected behavior.
i think if you set the compatible typed vale in the above request, it should pass.
I have a node that is launched with some parameters which are considered global, hence, every node can access it through a service call with the default services
get_parameters
andset_parameters
. While I can successfully read the parameters, I'm not able to SET them, i.e. to change their values.Here the code for the node which is in charge of setting the parameter.
The service call is completed, however, it is never successfull since it always gives this reason
'Static parameter cannot be undeclared
The text was updated successfully, but these errors were encountered: