Skip to content

Commit

Permalink
last try fix format
Browse files Browse the repository at this point in the history
  • Loading branch information
igonzf committed Apr 11, 2024
1 parent 503a71d commit 9f205c0
Showing 1 changed file with 25 additions and 25 deletions.
50 changes: 25 additions & 25 deletions bt_nodes/hri/src/hri/dialog/Speak.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,47 +27,47 @@ using namespace std::chrono_literals;
using namespace std::placeholders;

Speak::Speak(
const std::string & xml_tag_name,
const std::string & action_name,
const BT::NodeConfiguration & conf)
: dialog::BtActionNode<audio_common_msgs::action::TTS>(xml_tag_name, action_name, conf)
const std::string & xml_tag_name,
const std::string & action_name,
const BT::NodeConfiguration & conf)
: dialog::BtActionNode<audio_common_msgs::action::TTS>(xml_tag_name, action_name, conf)
{
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
this->publisher_ = node_->create_publisher<std_msgs::msg::String>("say_text", 10);
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
this->publisher_ = node_->create_publisher<std_msgs::msg::String>("say_text", 10);
}

void
Speak::on_tick()
{
RCLCPP_DEBUG(node_->get_logger(), "Speak ticked");
std::string text_;
RCLCPP_DEBUG(node_->get_logger(), "Speak ticked");
std::string text_;

getInput("say_text", text_);
std::string param_;
getInput("say_text", text_);
std::string param_;

getInput("param", param_);
getInput("param", param_);

if (param_.length() > 0) {
goal_.text = text_ + " " + param_ + "?";
} else {
goal_.text = text_;
}
if (param_.length() > 0) {
goal_.text = text_ + " " + param_ + "?";
} else {
goal_.text = text_;
}

auto msg = std_msgs::msg::String();
auto msg = std_msgs::msg::String();

msg.data = goal_.text;
this->publisher_->publish(msg);
msg.data = goal_.text;
this->publisher_->publish(msg);
}

BT::NodeStatus Speak::on_success(){ return BT::NodeStatus::SUCCESS; }
BT::NodeStatus Speak::on_success() {return BT::NodeStatus::SUCCESS;}
} // namespace dialog
#include "behaviortree_cpp_v3/bt_factory.h"
BT_REGISTER_NODES(factory)
{
BT::NodeBuilder builder = [](const std::string & name,
const BT::NodeConfiguration & config){
return std::make_unique<dialog::Speak>(name, "/say", config);
};
BT::NodeBuilder builder = [](const std::string & name,
const BT::NodeConfiguration & config) {
return std::make_unique<dialog::Speak>(name, "/say", config);
};

factory.registerBuilder<dialog::Speak>("Speak", builder);
factory.registerBuilder<dialog::Speak>("Speak", builder);
}

0 comments on commit 9f205c0

Please sign in to comment.