// ROS_ERROR("CTiagoArmModuleBT::sync_tiago_arm_move_to_joints-> Incorrect or missing input. It needs the following input ports: joint_names(std::vector<std::string>), joint_positions(std::vector<double>) and [Optional] joint_tol(double)");
ROS_ERROR("CTiagoArmModuleBT::sync_tiago_arm_move_to_joints-> Incorrect or missing input. It needs the following input ports: target_joints(sensor_msgs::JointState) and [Optional] joint_tol(double)");
@@ -185,16 +175,12 @@ BT::NodeStatus CTiagoArmModuleBT::async_tiago_arm_move_to_joints(BT::TreeNode& s
{
sensor_msgs::JointStatetarget_joints_goal;
doublejoint_tol_goal;
// if (!joint_names || !joint_positions)
if(!target_joints)
{
// ROS_ERROR("CTiagoArmModuleBT::sync_tiago_arm_move_to_joints-> Incorrect or missing input. It needs the following input ports: joint_names(std::vector<std::string>), joint_positions(std::vector<double>) and [Optional] joint_tol(double)");
ROS_ERROR("CTiagoArmModuleBT::sync_tiago_arm_move_to_joints-> Incorrect or missing input. It needs the following input ports: target_joints(sensor_msgs::JointState) and [Optional] joint_tol(double)");