diff --git a/src/tiago_nav_bt_client_alg_node.cpp b/src/tiago_nav_bt_client_alg_node.cpp index 22bbb5911cb00a442ebc19d1bc29d5e51c3462be..8b430d757c655c358c288d64d1413e63cda78c8f 100644 --- a/src/tiago_nav_bt_client_alg_node.cpp +++ b/src/tiago_nav_bt_client_alg_node.cpp @@ -20,7 +20,7 @@ TiagoNavModuleBtClientAlgNode::TiagoNavModuleBtClientAlgNode(void) : this->tiago_nav_module_bt.init(this->factory); // Init local functions - BT::PortsList async_go_to_pose_inputs_ports = {BT::OutputPort<double>("x"), BT::OutputPort<double>("y"), BT::OutputPort<double>("yaw"), BT::OutputPort<double>("heading_tol"), BT::OutputPort<double>("x_y_pos_tol"), BT::BidirectionalPort<bool>("new_goal")}; + BT::PortsList async_go_to_pose_inputs_ports = {BT::OutputPort<double>("x"), BT::OutputPort<double>("y"), BT::OutputPort<double>("yaw"), BT::OutputPort<double>("heading_tol"), BT::OutputPort<double>("x_y_pos_tol"), BT::OutputPort<bool>("new_goal")}; BT::PortsList set_goal_frame_inputs_ports = {BT::OutputPort<std::string>("frame_id")}; this->factory.registerIriAsyncAction("set_tiago_nav_go_to_pose_inputs", std::bind(&TiagoNavModuleBtClientAlgNode::set_tiago_nav_go_to_pose_inputs, this, std::placeholders::_1), async_go_to_pose_inputs_ports);