Skip to content

Commit 33bebaf

Browse files
committed
Merge branch 'humble-devel' of https://github.com/CoreSenseEU/CoreSense4Home into humble-devel
2 parents aa28974 + 74e5bf3 commit 33bebaf

2 files changed

Lines changed: 33 additions & 5 deletions

File tree

bt_nodes/hri/src/hri/dialog/Query.cpp

Lines changed: 27 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -96,14 +96,37 @@ BT::NodeStatus Query::on_success()
9696
return BT::NodeStatus::FAILURE;
9797
}
9898

99-
json response = json::parse(result_.result->response.text);
100-
std::string value_ = response["intention"];
101-
fprintf(stderr, "%s\n", value_.c_str());
99+
json response;
100+
try{
101+
response = json::parse(result_.result->response.text);
102+
}
103+
catch (json::parse_error& e) {
104+
RCLCPP_ERROR(node_->get_logger(), "Failed to parse JSON response: %s", e.what());
105+
return BT::NodeStatus::FAILURE;
106+
}
102107

108+
auto get_string_field = [&](const std::string & key) -> std::string {
109+
auto it = response.find(key);
110+
if (it == response.end() || it->is_null() || !it->is_string()) {
111+
return "";
112+
}
113+
return it->get<std::string>();
114+
};
115+
116+
std::string value_ = get_string_field("intention");
103117
if (value_.empty()) {
104-
return BT::NodeStatus::FAILURE;
118+
value_ = get_string_field(intention_);
119+
}
120+
121+
if (value_.empty()) {
122+
value_= get_string_field("value");
123+
}
124+
125+
if(value_.empty()) {
126+
value_ = "unknown";
105127
}
106128

129+
RCLCPP_INFO(node_->get_logger(), "Extracted intention: %s", value_.c_str());
107130
setOutput("intention_value", value_);
108131

109132
return BT::NodeStatus::SUCCESS;

robocup_bringup/launch/dialog.launch.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,12 @@ def generate_launch_description():
3939
description='Hugging Face model repo')
4040

4141
declare_model_filename_cmd = DeclareLaunchArgument(
42-
'model_filename', default_value='ggml-large-v3-q5_0.bin',
42+
'model_filename', default_value='ggml-small.en.bin',
4343
description='Hugging Face model filename')
44+
45+
declare_min_silence_ms_cmd = DeclareLaunchArgument(
46+
'min_silence_ms', default_value='500',
47+
description='Minimum silence duration in milliseconds for segmenting audio')
4448

4549
# Actions
4650
llama_cmd = create_llama_launch(
@@ -121,6 +125,7 @@ def generate_launch_description():
121125
ld = LaunchDescription()
122126
ld.add_action(declare_model_repo_cmd)
123127
ld.add_action(declare_model_filename_cmd)
128+
ld.add_action(declare_min_silence_ms_cmd)
124129
ld.add_action(whisper_cmd)
125130
ld.add_action(llava_cmd)
126131
ld.add_action(audio_common_tts_node)

0 commit comments

Comments
 (0)