Go to the documentation of this file.
7 #include <control_msgs/GripperCommandAction.h>
10 #include <franka_gripper/GraspAction.h>
11 #include <franka_gripper/GraspEpsilon.h>
12 #include <franka_gripper/HomingAction.h>
13 #include <franka_gripper/MoveAction.h>
14 #include <franka_gripper/StopAction.h>
20 #include <sensor_msgs/JointState.h>
107 std::unique_ptr<actionlib::SimpleActionServer<franka_gripper::StopAction>>
action_stop_;
108 std::unique_ptr<actionlib::SimpleActionServer<franka_gripper::HomingAction>>
action_homing_;
109 std::unique_ptr<actionlib::SimpleActionServer<franka_gripper::MoveAction>>
action_move_;
110 std::unique_ptr<actionlib::SimpleActionServer<franka_gripper::GraspAction>>
action_grasp_;
111 std::unique_ptr<actionlib::SimpleActionServer<control_msgs::GripperCommandAction>>
action_gc_;
134 void onStopGoal(
const franka_gripper::StopGoalConstPtr& goal);
135 void onHomingGoal(
const franka_gripper::HomingGoalConstPtr& goal);
136 void onMoveGoal(
const franka_gripper::MoveGoalConstPtr& goal);
137 void onGraspGoal(
const franka_gripper::GraspGoalConstPtr& goal);
149 bool grasp(
double width,
double speed,
double force,
const franka_gripper::GraspEpsilon& epsilon);
157 bool move(
double width,
double speed);
bool grasp(double width, double speed, double force, const franka_gripper::GraspEpsilon &epsilon)
libfranka-like method to grasp an object with the gripper
const double kGraspRestingThreshold
Below which speed the target width should be checked to abort or succeed the grasp action [m/s].
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::MoveAction > > action_move_
double tolerance_gripper_action_
[m] inner + outer position tolerances used during gripper action
franka_hw::TriggerRate rate_trigger_
const double kDefaultGripperActionWidthTolerance
When width between fingers is below this, the gripper action succeeds [m].
bool init(hardware_interface::EffortJointInterface *hw, ros::NodeHandle &nh) override
void interrupt(const std::string &message, const State &except)
Interrupt any running action server unless the gripper is currently in a specific state.
double width_desired
Desired width between both fingers [m].
double force_desired
Desired force with which to grasp objects, if grasps succeed [N].
control_toolbox::Pid pid2_
@ HOLDING
Gripper is holding position and tracking zero velocity while mainting a desired force.
void onGripperActionGoal(const control_msgs::GripperCommandGoalConstPtr &goal)
hardware_interface::JointHandle finger2_
@ MOVING
Gripper is tracking a desired position and velocity.
void setState(const State &&state)
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::HomingAction > > action_homing_
void onStopGoal(const franka_gripper::StopGoalConstPtr &goal)
void control(hardware_interface::JointHandle &joint, control_toolbox::Pid &, double q_d, double dq_d, double f_d, const ros::Duration &period)
const double kDefaultGripperActionSpeed
How fast shall the gripper execute gripper command actions? [m/s].
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::StopAction > > action_stop_
@ IDLE
Gripper is not actively controlled, but tracks the other finger to simulate a mimicked joint.
double speed_desired
Desired magnitude of the speed with which fingers should move [m/s].
void starting(const ros::Time &) override
void waitUntilStateChange()
const double kMaxFingerWidth
void setConfig(const Config &&config)
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::GraspAction > > action_grasp_
bool move(double width, double speed)
libfranka-like method to move the gripper to a certain position
control_toolbox::Pid pid1_
const double kDefaultMoveWidthTolerance
When width between fingers is below this, the move action succeeds [m].
void onGraspGoal(const franka_gripper::GraspGoalConstPtr &goal)
Simulate the franka_gripper_node.
realtime_tools::RealtimePublisher< sensor_msgs::JointState > pub_
@ GRASPING
Gripper is tracking a desired position and velocity.
const int kGraspConsecutiveSamples
How many times the speed has to drop below resting threshold before the grasping will be checked.
double tolerance_move_
[m] inner + outer position tolerances used during grasp
void onMoveGoal(const franka_gripper::MoveGoalConstPtr &goal)
hardware_interface::JointHandle finger1_
void transition(const State &&state, const Config &&config)
void update(const ros::Time &now, const ros::Duration &period) override
void onHomingGoal(const franka_gripper::HomingGoalConstPtr &goal)
franka_gripper::GraspEpsilon tolerance
Tolerance range to check if grasping succeeds.
std::unique_ptr< actionlib::SimpleActionServer< control_msgs::GripperCommandAction > > action_gc_
franka_gazebo
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:28