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

ROS distribution compatibility update

parent 39f5a3d6
No related tags found
No related merge requests found
publish_rate: 30 # [Hz]
default_speed: 0.08 # [m/s]
default_speed: 0.1 # [m/s]
default_grasp_epsilon:
inner: 0.01 # [m]
outer: 0.01 # [m]
inner: 0.005 # [m]
outer: 0.005 # [m]
<?xml version="1.0" ?>
<launch>
<arg name="robot_ip" />
<arg name="stop_at_shutdown" default="false" />
<arg name="arm_id" default="panda" />
<arg name="joint_names" default="[$(arg arm_id)_finger_joint1, $(arg arm_id)_finger_joint2]" />
<node name="franka_gripper" pkg="franka_gripper" type="franka_gripper_node" output="screen">
<param name="robot_ip" value="$(arg robot_ip)"/>
<param name="stop_at_shutdown" value="$(arg stop_at_shutdown)" />
<rosparam command="load" file="$(find franka_gripper)/config/franka_gripper_node.yaml" />
<rosparam param="joint_names" subst_value="true">$(arg joint_names)</rosparam>
</node>
......
<?xml version="1.0"?>
<package format="2">
<name>franka_gripper</name>
<version>0.7.0</version>
<version>0.8.2</version>
<description>This package implements the franka gripper of type Franka Hand for the use in ros</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
......
......@@ -33,7 +33,6 @@ void gripperCommandExecuteCallback(
double default_speed,
actionlib::SimpleActionServer<control_msgs::GripperCommandAction>* action_server,
const control_msgs::GripperCommandGoalConstPtr& goal) {
auto gripper_command_handler = [goal, grasp_epsilon, default_speed, &gripper]() {
// HACK: As one gripper finger is <mimic>, MoveIt!'s trajectory execution manager
// only sends us the width of one finger. Multiply by 2 to get the intended width.
......
......@@ -152,6 +152,12 @@ int main(int argc, char** argv) {
return -1;
}
bool stop_at_shutdown(false);
if (!node_handle.getParam("stop_at_shutdown", stop_at_shutdown)) {
ROS_INFO_STREAM("franka_gripper_node: Could not find parameter stop_at_shutdown. Defaulting to "
<< std::boolalpha << stop_at_shutdown);
}
franka::GripperState gripper_state;
std::mutex gripper_state_mutex;
std::thread read_thread([&gripper_state, &gripper, &gripper_state_mutex]() {
......@@ -188,5 +194,8 @@ int main(int argc, char** argv) {
rate.sleep();
}
read_thread.join();
if (stop_at_shutdown) {
gripper.stop();
}
return 0;
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment