Skip to content
Snippets Groups Projects
Commit 89e1ea8a authored by Alejandro Lopez Gestoso's avatar Alejandro Lopez Gestoso
Browse files

Fixed init set_move_to_pose variable to false

parent 2218efba
No related branches found
No related tags found
No related merge requests found
......@@ -17,12 +17,13 @@ TiagoArmModuleBtClientAlgNode::TiagoArmModuleBtClientAlgNode(void) :
// [init action clients]
this->set_move_to_joints = false;
this->set_move_to_pose = false;
this->tiago_arm_module_bt.init(this->factory);
// Init local functions
BT::PortsList set_tiago_arm_move_to_joints_input_ports = {BT::OutputPort<sensor_msgs::JointState>("target_joints"), BT::OutputPort<double>("joint_tol"), BT::OutputPort<bool>("new_goal")};
BT::PortsList set_tiago_arm_move_to_pose_input_ports = {BT::InputPort<geometry_msgs::PoseStamped>("pose"), BT::InputPort<double>("position_tol"), BT::InputPort<double>("orientation_tol"), BT::BidirectionalPort<bool>("new_goal")};
BT::PortsList set_tiago_arm_move_to_pose_input_ports = {BT::OutputPort<geometry_msgs::PoseStamped>("pose"), BT::OutputPort<double>("position_tol"), BT::OutputPort<double>("orientation_tol"), BT::OutputPort<bool>("new_goal")};
this->factory.registerIriAsyncAction("set_tiago_arm_move_to_joints_input", std::bind(&TiagoArmModuleBtClientAlgNode::set_tiago_arm_move_to_joints_input, this, std::placeholders::_1), set_tiago_arm_move_to_joints_input_ports);
this->factory.registerIriAsyncAction("set_tiago_arm_move_to_pose_input", std::bind(&TiagoArmModuleBtClientAlgNode::set_tiago_arm_move_to_pose_input, this, std::placeholders::_1), set_tiago_arm_move_to_pose_input_ports);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment