@@ -57,20 +57,60 @@ bool ConfigurationManager::is_node_available(const std::string & node_name) {
5757ParameterResult ConfigurationManager::list_parameters (const std::string & node_name) {
5858 ParameterResult result;
5959
60+ RCLCPP_DEBUG (node_->get_logger (), " list_parameters called for node: '%s'" , node_name.c_str ());
61+
62+ // Cache default values on first access to this node
63+ cache_default_values (node_name);
64+
6065 try {
6166 auto client = get_param_client (node_name);
6267
68+ RCLCPP_DEBUG (node_->get_logger (), " Got param client for node: '%s'" , node_name.c_str ());
69+
6370 if (!client->wait_for_service (2s)) {
6471 result.success = false ;
6572 result.error_message = " Parameter service not available for node: " + node_name;
73+ RCLCPP_WARN (node_->get_logger (), " Parameter service not available for node: '%s'" , node_name.c_str ());
6674 return result;
6775 }
6876
77+ RCLCPP_DEBUG (node_->get_logger (), " Service ready for node: '%s'" , node_name.c_str ());
78+
6979 // List all parameter names
7080 auto param_names = client->list_parameters ({}, 0 );
7181
72- // Get all parameter values
73- auto parameters = client->get_parameters (param_names.names );
82+ RCLCPP_DEBUG (node_->get_logger (), " Got %zu parameter names for node: '%s'" ,
83+ param_names.names .size (), node_name.c_str ());
84+
85+ // Log first few parameter names for debugging
86+ for (size_t i = 0 ; i < std::min (param_names.names .size (), static_cast <size_t >(5 )); ++i) {
87+ RCLCPP_DEBUG (node_->get_logger (), " param[%zu]: '%s'" , i, param_names.names [i].c_str ());
88+ }
89+
90+ // Get all parameter values - try in smaller batches if needed
91+ std::vector<rclcpp::Parameter> parameters;
92+
93+ // First try getting all at once
94+ parameters = client->get_parameters (param_names.names );
95+
96+ if (parameters.empty () && !param_names.names .empty ()) {
97+ RCLCPP_WARN (node_->get_logger (), " get_parameters returned empty, trying one by one for node: '%s'" ,
98+ node_name.c_str ());
99+ // Try getting parameters one by one
100+ for (const auto & name : param_names.names ) {
101+ try {
102+ auto single_params = client->get_parameters ({name});
103+ if (!single_params.empty ()) {
104+ parameters.push_back (single_params[0 ]);
105+ }
106+ } catch (const std::exception & e) {
107+ RCLCPP_DEBUG (node_->get_logger (), " Failed to get param '%s': %s" , name.c_str (), e.what ());
108+ }
109+ }
110+ }
111+
112+ RCLCPP_DEBUG (node_->get_logger (), " Got %zu parameter values for node: '%s'" ,
113+ parameters.size (), node_name.c_str ());
74114
75115 json params_array = json::array ();
76116 for (const auto & param : parameters) {
@@ -86,6 +126,8 @@ ParameterResult ConfigurationManager::list_parameters(const std::string & node_n
86126 } catch (const std::exception & e) {
87127 result.success = false ;
88128 result.error_message = std::string (" Failed to list parameters: " ) + e.what ();
129+ RCLCPP_ERROR (node_->get_logger (), " Exception in list_parameters for node '%s': %s" ,
130+ node_name.c_str (), e.what ());
89131 }
90132
91133 return result;
@@ -407,4 +449,192 @@ rclcpp::ParameterValue ConfigurationManager::json_to_parameter_value(const json
407449 return rclcpp::ParameterValue (value.dump ());
408450}
409451
452+ void ConfigurationManager::cache_default_values (const std::string & node_name) {
453+ std::lock_guard<std::mutex> lock (defaults_mutex_);
454+
455+ // Check if already cached
456+ if (default_values_.find (node_name) != default_values_.end ()) {
457+ return ;
458+ }
459+
460+ RCLCPP_DEBUG (node_->get_logger (), " Caching default values for node: '%s'" , node_name.c_str ());
461+
462+ try {
463+ auto client = get_param_client (node_name);
464+
465+ if (!client->wait_for_service (2s)) {
466+ RCLCPP_WARN (node_->get_logger (), " Cannot cache defaults - service not available for node: '%s'" , node_name.c_str ());
467+ return ;
468+ }
469+
470+ // List all parameter names
471+ auto param_names = client->list_parameters ({}, 0 );
472+
473+ // Get all parameter values
474+ std::vector<rclcpp::Parameter> parameters;
475+ parameters = client->get_parameters (param_names.names );
476+
477+ // Fallback to one-by-one if batch fails
478+ if (parameters.empty () && !param_names.names .empty ()) {
479+ for (const auto & name : param_names.names ) {
480+ try {
481+ auto single_params = client->get_parameters ({name});
482+ if (!single_params.empty ()) {
483+ parameters.push_back (single_params[0 ]);
484+ }
485+ } catch (const std::exception &) {
486+ // Skip failed parameters
487+ }
488+ }
489+ }
490+
491+ // Store as defaults
492+ std::map<std::string, rclcpp::Parameter> node_defaults;
493+ for (const auto & param : parameters) {
494+ node_defaults[param.get_name ()] = param;
495+ }
496+ default_values_[node_name] = std::move (node_defaults);
497+
498+ RCLCPP_DEBUG (node_->get_logger (), " Cached %zu default values for node: '%s'" ,
499+ default_values_[node_name].size (), node_name.c_str ());
500+ } catch (const std::exception & e) {
501+ RCLCPP_ERROR (node_->get_logger (), " Failed to cache defaults for node '%s': %s" , node_name.c_str (), e.what ());
502+ }
503+ }
504+
505+ ParameterResult ConfigurationManager::reset_parameter (const std::string & node_name, const std::string & param_name) {
506+ ParameterResult result;
507+
508+ try {
509+ // Ensure defaults are cached
510+ cache_default_values (node_name);
511+
512+ // Look up default value
513+ std::lock_guard<std::mutex> lock (defaults_mutex_);
514+ auto node_it = default_values_.find (node_name);
515+ if (node_it == default_values_.end ()) {
516+ result.success = false ;
517+ result.error_message = " No default values cached for node: " + node_name;
518+ return result;
519+ }
520+
521+ auto param_it = node_it->second .find (param_name);
522+ if (param_it == node_it->second .end ()) {
523+ result.success = false ;
524+ result.error_message = " No default value for parameter: " + param_name;
525+ return result;
526+ }
527+
528+ const auto & default_param = param_it->second ;
529+
530+ // Set parameter back to default value
531+ auto client = get_param_client (node_name);
532+ if (!client->wait_for_service (2s)) {
533+ result.success = false ;
534+ result.error_message = " Parameter service not available for node: " + node_name;
535+ return result;
536+ }
537+
538+ auto results = client->set_parameters ({default_param});
539+ if (results.empty () || !results[0 ].successful ) {
540+ result.success = false ;
541+ result.error_message = results.empty () ? " Failed to reset parameter" : results[0 ].reason ;
542+ return result;
543+ }
544+
545+ // Return the reset value
546+ json param_obj;
547+ param_obj[" name" ] = param_name;
548+ param_obj[" value" ] = parameter_value_to_json (default_param.get_parameter_value ());
549+ param_obj[" type" ] = parameter_type_to_string (default_param.get_type ());
550+ param_obj[" reset_to_default" ] = true ;
551+
552+ result.success = true ;
553+ result.data = param_obj;
554+
555+ RCLCPP_INFO (node_->get_logger (), " Reset parameter '%s' on node '%s' to default value" ,
556+ param_name.c_str (), node_name.c_str ());
557+ } catch (const std::exception & e) {
558+ result.success = false ;
559+ result.error_message = std::string (" Failed to reset parameter: " ) + e.what ();
560+ }
561+
562+ return result;
563+ }
564+
565+ ParameterResult ConfigurationManager::reset_all_parameters (const std::string & node_name) {
566+ ParameterResult result;
567+
568+ try {
569+ // Ensure defaults are cached
570+ cache_default_values (node_name);
571+
572+ // Look up default values
573+ std::lock_guard<std::mutex> lock (defaults_mutex_);
574+ auto node_it = default_values_.find (node_name);
575+ if (node_it == default_values_.end ()) {
576+ result.success = false ;
577+ result.error_message = " No default values cached for node: " + node_name;
578+ return result;
579+ }
580+
581+ auto client = get_param_client (node_name);
582+ if (!client->wait_for_service (2s)) {
583+ result.success = false ;
584+ result.error_message = " Parameter service not available for node: " + node_name;
585+ return result;
586+ }
587+
588+ // Collect all default parameters
589+ std::vector<rclcpp::Parameter> params_to_reset;
590+ for (const auto & [name, param] : node_it->second ) {
591+ params_to_reset.push_back (param);
592+ }
593+
594+ // Reset all parameters
595+ size_t reset_count = 0 ;
596+ size_t failed_count = 0 ;
597+ json failed_params = json::array ();
598+
599+ // Set parameters one by one to handle partial failures
600+ for (const auto & param : params_to_reset) {
601+ try {
602+ auto results = client->set_parameters ({param});
603+ if (!results.empty () && results[0 ].successful ) {
604+ reset_count++;
605+ } else {
606+ failed_count++;
607+ failed_params.push_back (param.get_name ());
608+ }
609+ } catch (const std::exception &) {
610+ failed_count++;
611+ failed_params.push_back (param.get_name ());
612+ }
613+ }
614+
615+ json response;
616+ response[" node_name" ] = node_name;
617+ response[" reset_count" ] = reset_count;
618+ response[" failed_count" ] = failed_count;
619+ if (!failed_params.empty ()) {
620+ response[" failed_parameters" ] = failed_params;
621+ }
622+
623+ result.success = (failed_count == 0 );
624+ result.data = response;
625+
626+ if (failed_count > 0 ) {
627+ result.error_message = " Some parameters could not be reset" ;
628+ }
629+
630+ RCLCPP_INFO (node_->get_logger (), " Reset %zu parameters on node '%s' (%zu failed)" ,
631+ reset_count, node_name.c_str (), failed_count);
632+ } catch (const std::exception & e) {
633+ result.success = false ;
634+ result.error_message = std::string (" Failed to reset parameters: " ) + e.what ();
635+ }
636+
637+ return result;
638+ }
639+
410640} // namespace ros2_medkit_gateway
0 commit comments