Skip to content
Snippets Groups Projects
Commit 56bafa5e authored by Johannes Mey's avatar Johannes Mey
Browse files

fix missing dependency to franka_gripper, move franka-specific things into new library

parent 0d1d2262
No related branches found
No related tags found
No related merge requests found
...@@ -14,6 +14,7 @@ find_package(catkin REQUIRED ...@@ -14,6 +14,7 @@ find_package(catkin REQUIRED
tf2 tf2
moveit_core moveit_core
moveit_ros_planning_interface moveit_ros_planning_interface
franka_gripper
message_generation) message_generation)
## Generate services in the 'srv' folder ## Generate services in the 'srv' folder
...@@ -50,11 +51,13 @@ include_directories(${catkin_INCLUDE_DIRS}) ...@@ -50,11 +51,13 @@ include_directories(${catkin_INCLUDE_DIRS})
add_library(EnvironmentUtil src/grasping/environment_util.cpp src/grasping/environment_util.h) add_library(EnvironmentUtil src/grasping/environment_util.cpp src/grasping/environment_util.h)
add_library(GraspUtil src/grasping/grasp_util.cpp src/grasping/grasp_util.h) add_library(GraspUtil src/grasping/grasp_util.cpp src/grasping/grasp_util.h)
add_library(FrankaGripperUtil src/grasping/franka_gripper_util.cpp src/grasping/franka_gripper_util.h)
add_executable(grasp_service src/grasping/grasp_service.cpp) add_executable(grasp_service src/grasping/grasp_service.cpp)
target_link_libraries(EnvironmentUtil ${catkin_LIBRARIES}) target_link_libraries(EnvironmentUtil ${catkin_LIBRARIES})
target_link_libraries(GraspUtil ${catkin_LIBRARIES}) target_link_libraries(GraspUtil ${catkin_LIBRARIES})
target_link_libraries(FrankaGripperUtil ${catkin_LIBRARIES})
target_link_libraries(grasp_service ${catkin_LIBRARIES} EnvironmentUtil GraspUtil) target_link_libraries(grasp_service ${catkin_LIBRARIES} EnvironmentUtil GraspUtil)
add_dependencies(grasp_service panda_grasping_generate_messages_cpp) add_dependencies(grasp_service panda_grasping_generate_messages_cpp)
......
<?xml version="1.0"?> <?xml version="1.0"?>
<package format="2"> <package format="2">
<name>panda_grasping</name> <name>panda_grasping</name>
<version>0.0.0</version> <version>0.1.0</version>
<description>The panda_grasping package</description> <description>The panda_grasping package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag --> <!-- One maintainer tag required, multiple allowed, one person per tag -->
...@@ -29,6 +29,7 @@ ...@@ -29,6 +29,7 @@
<depend>moveit_visual_tools</depend> <depend>moveit_visual_tools</depend>
<depend>robot_state_publisher</depend> <depend>robot_state_publisher</depend>
<depend>tf2</depend> <depend>tf2</depend>
<depend>franka_gripper</depend>
<exec_depend>message_runtime</exec_depend> <exec_depend>message_runtime</exec_depend>
<exec_depend>roscpp</exec_depend> <exec_depend>roscpp</exec_depend>
......
//
// Created by jm on 03.12.20.
//
#include "franka_gripper_util.h"
// Actionlib
#include <actionlib/client/simple_action_client.h>
// Franka
#include <franka_gripper/MoveAction.h>
void FrankaGripperUtil::resetGripperForNextAction() {
actionlib::SimpleActionClient<franka_gripper::MoveAction> ac("franka_gripper/move", true);
ROS_INFO("Waiting for reset action server to start.");
ac.waitForServer();
ROS_INFO("Reset action server started, sending goal.");
franka_gripper::MoveGoal goal;
goal.speed = 0.08;
goal.width = 0.0;
ac.sendGoal(goal);
//wait for the action to return
bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
if (finished_before_timeout) {
actionlib::SimpleClientGoalState state = ac.getState();
ROS_INFO("Reset action finished: %s", state.toString().c_str());
} else {
ROS_INFO("Reset action did not finish before the time out.");
}
}
//
// Created by jm on 03.12.20.
//
#ifndef PUBLIC_FRANKA_GRIPPER_UTIL_H
#define PUBLIC_FRANKA_GRIPPER_UTIL_H
class FrankaGripperUtil {
/**
* resets the real robot, to allow correct future movements and grasps
*/
void resetGripperForNextAction();
};
#endif //PUBLIC_FRANKA_GRIPPER_UTIL_H
...@@ -4,14 +4,6 @@ ...@@ -4,14 +4,6 @@
#include "grasp_util.h" #include "grasp_util.h"
#include <tf2/transform_datatypes.h> #include <tf2/transform_datatypes.h>
// Actionlib
#include <actionlib/client/simple_action_client.h>
#include <actionlib/client/simple_client_goal_state.h>
// Franka
// if this should be required, the dependency to franka_gripper must also be declared
#include <franka_gripper/MoveAction.h>
void GraspUtil::setupOpenGripper(trajectory_msgs::JointTrajectory &posture, double amount) { void GraspUtil::setupOpenGripper(trajectory_msgs::JointTrajectory &posture, double amount) {
posture.joint_names.resize(2); posture.joint_names.resize(2);
posture.joint_names[0] = "panda_finger_joint1"; posture.joint_names[0] = "panda_finger_joint1";
...@@ -164,27 +156,3 @@ GraspUtil::placeFromAbove(moveit::planning_interface::MoveGroupInterface &move_g ...@@ -164,27 +156,3 @@ GraspUtil::placeFromAbove(moveit::planning_interface::MoveGroupInterface &move_g
ROS_ERROR_STREAM("Error while executing place task. MoveItErrorCode: " << miec.val); ROS_ERROR_STREAM("Error while executing place task. MoveItErrorCode: " << miec.val);
return false; return false;
} }
void GraspUtil::resetGripperForNextAction() {
actionlib::SimpleActionClient<franka_gripper::MoveAction> ac("franka_gripper/move", true);
ROS_INFO("Waiting for reset action server to start.");
ac.waitForServer();
ROS_INFO("Reset action server started, sending goal.");
franka_gripper::MoveGoal goal;
goal.speed = 0.08;
goal.width = 0.0;
ac.sendGoal(goal);
//wait for the action to return
bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
if (finished_before_timeout) {
actionlib::SimpleClientGoalState state = ac.getState();
ROS_INFO("Reset action finished: %s", state.toString().c_str());
} else {
ROS_INFO("Reset action did not finish before the time out.");
}
}
...@@ -90,10 +90,6 @@ public: ...@@ -90,10 +90,6 @@ public:
bool placeFromAbove(moveit::planning_interface::MoveGroupInterface &move_group, geometry_msgs::Pose &place_pose, bool placeFromAbove(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); double open_amount, std::string supporting_surface_id, std::string object_to_place_id);
/**
* resets the real robot, to allow correct future movements and grasps
*/
void resetGripperForNextAction();
}; };
#endif //PANDA_GRASPING_GRASP_UTIL_H #endif //PANDA_GRASPING_GRASP_UTIL_H
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment