rhino_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2021, Rein Appeldoorn
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  */
17 
18 #include <picovoice_msgs/GetIntentAction.h>
19 #include <ros/init.h>
20 
21 #include "./rhino_recognizer.h"
22 #include "./recognizer_node.h"
23 
24 namespace picovoice_driver
25 {
26 using namespace picovoice_msgs;
27 class RhinoNode : public RecognizerNode<RhinoRecognizerData, RhinoRecognizer, GetIntentAction>
28 {
29 public:
30  RhinoNode(const RhinoRecognizerData::Parameters& parameters, const std::string& contexts_directory_url)
31  : RecognizerNode("rhino", "get_intent", parameters), contexts_directory_url_(contexts_directory_url)
32  {
33  }
34 
35 private:
36  void updateParameters(const GetIntentGoal& goal, RhinoRecognizerData::Parameters& parameters) override
37  {
38  parameters.context_path_ = pathFromUrl(goal.context_url, ".rhn", contexts_directory_url_);
39  parameters.require_endpoint_ = goal.require_endpoint;
40  parameters.intents_ = goal.intents;
41  }
42 
43  void updateResult(const RhinoRecognizerData::Result& result, GetIntentResult& action_result) override
44  {
45  action_result.is_understood = result.is_understood_;
46  action_result.intent = result.intent_;
47  for (const auto& slot : result.slots_)
48  {
49  picovoice_msgs::KeyValue kv;
50  kv.key = slot.key_;
51  kv.value = slot.value_;
52  action_result.slots.push_back(kv);
53  }
54  }
55 
57 };
58 } // namespace picovoice_driver
59 
60 int main(int argc, char** argv)
61 {
62  using namespace picovoice_driver;
63 
64  ros::init(argc, argv, "rhino");
65 
66  ros::NodeHandle local_nh("~");
67  auto model_url = local_nh.param("model_url", defaultResourceUrl() + "/models/rhino_params.pv");
68  auto contexts_directory_url = local_nh.param("contexts_directory_url", defaultResourceUrl() + "/contexts");
69 
70  try
71  {
73  parameters.model_path_ = pathFromUrl(model_url);
74 
75  RhinoNode node(parameters, pathFromUrl(contexts_directory_url));
76  ros::spin();
77  }
78  catch (const std::exception& e)
79  {
80  ROS_FATAL("RhinoNode exception: %s", e.what());
81  return 1;
82  }
83  return 0;
84 }
picovoice_driver::RhinoRecognizerData::Result
Definition: rhino_recognizer.h:57
picovoice_driver::RhinoNode::updateParameters
void updateParameters(const GetIntentGoal &goal, RhinoRecognizerData::Parameters &parameters) override
Definition: rhino_node.cpp:36
picovoice_driver::RecognizerNode
Definition: recognizer_node.h:33
rhino_recognizer.h
picovoice_driver::pathFromUrl
std::string pathFromUrl(const std::string &url, const std::string &extension, const std::string &directory)
pathFromUrl Get a file path from an url
Definition: ros_util.cpp:49
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
picovoice_driver::RhinoNode::updateResult
void updateResult(const RhinoRecognizerData::Result &result, GetIntentResult &action_result) override
Definition: rhino_node.cpp:43
init.h
picovoice_driver::RhinoRecognizerData::Parameters::require_endpoint_
bool require_endpoint_
require_endpoint_ If true, Rhino requires an endpoint (chunk of silence) before finishing inference.
Definition: rhino_recognizer.h:49
recognizer_node.h
picovoice_driver::RecognizerData::Parameters::model_path_
std::string model_path_
model_path_ Path to the Picovoice model parameters
Definition: recognizer.h:38
main
int main(int argc, char **argv)
Definition: rhino_node.cpp:60
picovoice_driver::RhinoNode::contexts_directory_url_
std::string contexts_directory_url_
Definition: rhino_node.cpp:56
picovoice_driver::RhinoRecognizerData::Parameters
Definition: rhino_recognizer.h:34
picovoice_driver
Definition: porcupine_node.cpp:24
ROS_FATAL
#define ROS_FATAL(...)
picovoice_driver::RhinoRecognizerData::Result::slots_
std::vector< KeyValue > slots_
slots_ The recognized intent slots
Definition: rhino_recognizer.h:80
picovoice_driver::RhinoRecognizerData::Result::is_understood_
bool is_understood_
is_understood_ Whether the recognizer understood an intent
Definition: rhino_recognizer.h:62
picovoice_driver::defaultResourceUrl
std::string defaultResourceUrl()
defaultResourcePath Get the default resource path
Definition: ros_util.cpp:27
picovoice_driver::RhinoNode::RhinoNode
RhinoNode(const RhinoRecognizerData::Parameters &parameters, const std::string &contexts_directory_url)
Definition: rhino_node.cpp:30
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
python.test_porcupine.argv
argv
Definition: test_porcupine.py:158
picovoice_driver::RhinoNode
Definition: rhino_node.cpp:27
ros::spin
ROSCPP_DECL void spin()
picovoice_driver::RhinoRecognizerData::Parameters::context_path_
std::string context_path_
context_path_ Path to the Picovoice Rhino context.rhn
Definition: rhino_recognizer.h:39
picovoice_driver::RhinoRecognizerData::Result::intent_
std::string intent_
intent_ The recognized intent
Definition: rhino_recognizer.h:67
picovoice_driver::RhinoRecognizerData::Parameters::intents_
std::vector< std::string > intents_
intents_ Indent candidates, if empty, all returned intents will be considered valid
Definition: rhino_recognizer.h:44
ros::NodeHandle


picovoice_driver
Author(s):
autogenerated on Fri Apr 1 2022 02:14:50