diff --git a/include/grasp_util.h b/include/grasp_util.h index aaa7e2f517d636eec4ce3739a70d959d08d6a57f..1403f64d74fe93f9fcc654c2b81814167aec4b14 100644 --- a/include/grasp_util.h +++ b/include/grasp_util.h @@ -161,6 +161,13 @@ public: bool placeFromSide(moveit::planning_interface::MoveGroupInterface &move_group, geometry_msgs::Pose &place_pose, double open_amount, std::string supporting_surface_id, std::string object_to_place_id, bool plan_only = false); + /** + * Homes the gripper (in case it was abused before and is in an inconsistent state) + * This method is blocking with a maximum runtime of ~30s + * @return true if homing succeeded, false otherwise + */ + static bool homeGripper(); + private: /** @@ -179,12 +186,4 @@ private: tf2::Quaternion approach_orientation, float y_distance_diff, float x_distance_diff, double reach = FRANKA_GRIPPER_FINGERTIP_SIZE / 2); }; - - /** - * Homes the gripper (in case it was abused before and is in an inconsistent state) - * This method is blocking with a maximum runtime of ~30s - * @return true if homing succeeded, false otherwise - */ - static bool homeGripper(); - #endif //PANDA_GRASPING_GRASP_UTIL_H