23#ifndef WHISPER_SERVER_NODE_HPP
24#define WHISPER_SERVER_NODE_HPP
26#include <condition_variable>
30#include <rclcpp_action/rclcpp_action.hpp>
31#include <std_msgs/msg/float32_multi_array.hpp>
32#include <std_srvs/srv/set_bool.hpp>
34#include "whisper_msgs/action/stt.hpp"
35#include "whisper_msgs/msg/transcription.hpp"
42 using STT = whisper_msgs::action::STT;
60 rclcpp::Subscription<std_msgs::msg::Float32MultiArray>::SharedPtr
65 void vad_callback(
const std_msgs::msg::Float32MultiArray::SharedPtr msg);
66 void execute(
const std::shared_ptr<GoalHandleSTT> goal_handle);
67 rclcpp_action::GoalResponse
69 std::shared_ptr<const STT::Goal> goal);
70 rclcpp_action::CancelResponse
71 handle_cancel(
const std::shared_ptr<GoalHandleSTT> goal_handle);
Definition whisper_base_node.hpp:38
Definition whisper_server_node.hpp:40
rclcpp_action::CancelResponse handle_cancel(const std::shared_ptr< GoalHandleSTT > goal_handle)
Definition whisper_server_node.cpp:96
rclcpp_action::Server< STT >::SharedPtr action_server_
Definition whisper_server_node.hpp:63
void deactivate_ros_interfaces()
Definition whisper_server_node.cpp:52
rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID &uuid, std::shared_ptr< const STT::Goal > goal)
Definition whisper_server_node.cpp:84
void handle_accepted(const std::shared_ptr< GoalHandleSTT > goal_handle)
Definition whisper_server_node.cpp:107
whisper_msgs::msg::Transcription transcription_msg
Definition whisper_server_node.hpp:55
void enable_silero(bool enable)
Definition whisper_server_node.cpp:64
whisper_msgs::action::STT STT
Definition whisper_server_node.hpp:42
void execute(const std::shared_ptr< GoalHandleSTT > goal_handle)
Definition whisper_server_node.cpp:114
void vad_callback(const std_msgs::msg::Float32MultiArray::SharedPtr msg)
Definition whisper_server_node.cpp:73
std::mutex transcription_mutex
Definition whisper_server_node.hpp:56
rclcpp_action::ServerGoalHandle< STT > GoalHandleSTT
Definition whisper_server_node.hpp:43
std::shared_ptr< GoalHandleSTT > goal_handle_
Definition whisper_server_node.hpp:59
std::condition_variable transcription_cond
Definition whisper_server_node.hpp:57
rclcpp::Subscription< std_msgs::msg::Float32MultiArray >::SharedPtr subscription_
Definition whisper_server_node.hpp:61
rclcpp::Client< std_srvs::srv::SetBool >::SharedPtr enable_silero_client_
Definition whisper_server_node.hpp:62
WhisperServerNode()
Definition whisper_server_node.cpp:33
void activate_ros_interfaces()
Definition whisper_server_node.cpp:37
Definition whisper.hpp:45