franka_gripper_sim.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <functional>
4 #include <mutex>
5 
7 #include <control_msgs/GripperCommandAction.h>
8 #include <control_toolbox/pid.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>
15 #include <franka_hw/trigger_rate.h>
19 #include <ros/time.h>
20 #include <sensor_msgs/JointState.h>
21 
22 namespace franka_gazebo {
23 
24 const double kMaxFingerWidth = 0.08;
25 
27 const double kDefaultMoveWidthTolerance = 0.001;
28 
31 
33 const double kDefaultGripperActionSpeed = 0.1;
34 
36 const double kGraspRestingThreshold = 0.003;
37 
39 const int kGraspConsecutiveSamples = 10;
40 
62  : public controller_interface::Controller<hardware_interface::EffortJointInterface> {
63  public:
64  enum State {
65  IDLE,
66  HOLDING,
68  MOVING,
71  };
74 
75  struct Config {
76  double width_desired;
77  double speed_desired;
78  double force_desired;
79  franka_gripper::GraspEpsilon tolerance;
80  };
81 
83  void starting(const ros::Time&) override;
84  void update(const ros::Time& now, const ros::Duration& period) override;
85 
86  private:
87  State state_ = State::IDLE;
89 
96 
97  std::mutex mutex_;
98 
99  // Configurable by parameters
105 
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_;
112 
113  void setState(const State&& state);
114  void setConfig(const Config&& config);
115  void transition(const State&& state, const Config&& config);
116 
119  double q_d,
120  double dq_d,
121  double f_d,
122  const ros::Duration& period);
123 
130  void interrupt(const std::string& message, const State& except);
131 
132  void waitUntilStateChange();
133 
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);
138  void onGripperActionGoal(const control_msgs::GripperCommandGoalConstPtr& goal);
139 
149  bool grasp(double width, double speed, double force, const franka_gripper::GraspEpsilon& epsilon);
150 
157  bool move(double width, double speed);
158 };
159 } // namespace franka_gazebo
franka_gazebo::FrankaGripperSim::speed_default_
double speed_default_
Definition: franka_gripper_sim.h:102
realtime_publisher.h
franka_gazebo
Definition: controller_verifier.h:8
franka_gazebo::FrankaGripperSim::grasp
bool grasp(double width, double speed, double force, const franka_gripper::GraspEpsilon &epsilon)
libfranka-like method to grasp an object with the gripper
Definition: franka_gripper_sim.cpp:492
franka_gazebo::FrankaGripperSim::speed_samples_
int speed_samples_
Definition: franka_gripper_sim.h:100
franka_gazebo::FrankaGripperSim::state_
State state_
Definition: franka_gripper_sim.h:87
franka_gazebo::FrankaGripperSim::State
State
Definition: franka_gripper_sim.h:64
franka_gazebo::FrankaGripperSim::config_
Config config_
Definition: franka_gripper_sim.h:88
franka_gazebo::kGraspRestingThreshold
const double kGraspRestingThreshold
Below which speed the target width should be checked to abort or succeed the grasp action [m/s].
Definition: franka_gripper_sim.h:36
franka_gazebo::FrankaGripperSim::action_move_
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::MoveAction > > action_move_
Definition: franka_gripper_sim.h:109
time.h
franka_gazebo::FrankaGripperSim::tolerance_gripper_action_
double tolerance_gripper_action_
[m] inner + outer position tolerances used during gripper action
Definition: franka_gripper_sim.h:104
franka_gazebo::FrankaGripperSim::rate_trigger_
franka_hw::TriggerRate rate_trigger_
Definition: franka_gripper_sim.h:90
franka_gazebo::kDefaultGripperActionWidthTolerance
const double kDefaultGripperActionWidthTolerance
When width between fingers is below this, the gripper action succeeds [m].
Definition: franka_gripper_sim.h:30
franka_gazebo::FrankaGripperSim::init
bool init(hardware_interface::EffortJointInterface *hw, ros::NodeHandle &nh) override
Definition: franka_gripper_sim.cpp:16
franka_gazebo::FrankaGripperSim::speed_threshold_
double speed_threshold_
Definition: franka_gripper_sim.h:101
simple_action_server.h
franka_gazebo::FrankaGripperSim::interrupt
void interrupt(const std::string &message, const State &except)
Interrupt any running action server unless the gripper is currently in a specific state.
Definition: franka_gripper_sim.cpp:217
franka_gazebo::FrankaGripperSim::Config::width_desired
double width_desired
Desired width between both fingers [m].
Definition: franka_gripper_sim.h:76
franka_gazebo::FrankaGripperSim::Config::force_desired
double force_desired
Desired force with which to grasp objects, if grasps succeed [N].
Definition: franka_gripper_sim.h:78
franka_gazebo::FrankaGripperSim::pid2_
control_toolbox::Pid pid2_
Definition: franka_gripper_sim.h:92
controller_interface::Controller
trigger_rate.h
franka_gazebo::FrankaGripperSim::HOLDING
@ HOLDING
Gripper is holding position and tracking zero velocity while mainting a desired force.
Definition: franka_gripper_sim.h:67
franka_gazebo::FrankaGripperSim::Config
Definition: franka_gripper_sim.h:75
franka_gazebo::FrankaGripperSim::onGripperActionGoal
void onGripperActionGoal(const control_msgs::GripperCommandGoalConstPtr &goal)
Definition: franka_gripper_sim.cpp:418
franka_gazebo::FrankaGripperSim::finger2_
hardware_interface::JointHandle finger2_
Definition: franka_gripper_sim.h:95
franka_gazebo::FrankaGripperSim::MOVING
@ MOVING
Gripper is tracking a desired position and velocity.
Definition: franka_gripper_sim.h:69
realtime_tools::RealtimePublisher< sensor_msgs::JointState >
franka_gazebo::FrankaGripperSim::setState
void setState(const State &&state)
Definition: franka_gripper_sim.cpp:201
franka_gazebo::FrankaGripperSim::action_homing_
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::HomingAction > > action_homing_
Definition: franka_gripper_sim.h:108
franka_gazebo::FrankaGripperSim::onStopGoal
void onStopGoal(const franka_gripper::StopGoalConstPtr &goal)
Definition: franka_gripper_sim.cpp:256
controller.h
joint_command_interface.h
franka_gazebo::FrankaGripperSim::control
void control(hardware_interface::JointHandle &joint, control_toolbox::Pid &, double q_d, double dq_d, double f_d, const ros::Duration &period)
Definition: franka_gripper_sim.cpp:190
franka_gazebo::kDefaultGripperActionSpeed
const double kDefaultGripperActionSpeed
How fast shall the gripper execute gripper command actions? [m/s].
Definition: franka_gripper_sim.h:33
franka_gazebo::FrankaGripperSim::action_stop_
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::StopAction > > action_stop_
Definition: franka_gripper_sim.h:107
franka_gazebo::FrankaGripperSim::IDLE
@ IDLE
Gripper is not actively controlled, but tracks the other finger to simulate a mimicked joint.
Definition: franka_gripper_sim.h:65
franka_gazebo::FrankaGripperSim::Config::speed_desired
double speed_desired
Desired magnitude of the speed with which fingers should move [m/s].
Definition: franka_gripper_sim.h:77
franka_gazebo::FrankaGripperSim::starting
void starting(const ros::Time &) override
Definition: franka_gripper_sim.cpp:97
hardware_interface::EffortJointInterface
franka_gazebo::FrankaGripperSim::mutex_
std::mutex mutex_
Definition: franka_gripper_sim.h:97
franka_gazebo::FrankaGripperSim::waitUntilStateChange
void waitUntilStateChange()
Definition: franka_gripper_sim.cpp:241
franka_gazebo::kMaxFingerWidth
const double kMaxFingerWidth
Definition: franka_gripper_sim.h:24
franka_gazebo::FrankaGripperSim::setConfig
void setConfig(const Config &&config)
Definition: franka_gripper_sim.cpp:206
franka_gazebo::FrankaGripperSim::action_grasp_
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::GraspAction > > action_grasp_
Definition: franka_gripper_sim.h:110
hardware_interface::JointHandle
franka_gazebo::FrankaGripperSim::move
bool move(double width, double speed)
libfranka-like method to move the gripper to a certain position
Definition: franka_gripper_sim.cpp:480
franka_gazebo::FrankaGripperSim::pid1_
control_toolbox::Pid pid1_
Definition: franka_gripper_sim.h:91
ros::Time
franka_gazebo::kDefaultMoveWidthTolerance
const double kDefaultMoveWidthTolerance
When width between fingers is below this, the move action succeeds [m].
Definition: franka_gripper_sim.h:27
franka_gazebo::FrankaGripperSim::onGraspGoal
void onGraspGoal(const franka_gripper::GraspGoalConstPtr &goal)
Definition: franka_gripper_sim.cpp:364
franka_gazebo::FrankaGripperSim
Simulate the franka_gripper_node.
Definition: franka_gripper_sim.h:61
franka_gazebo::FrankaGripperSim::pub_
realtime_tools::RealtimePublisher< sensor_msgs::JointState > pub_
Definition: franka_gripper_sim.h:93
franka_gazebo::FrankaGripperSim::GRASPING
@ GRASPING
Gripper is tracking a desired position and velocity.
Definition: franka_gripper_sim.h:70
control_toolbox::Pid
robot_hw.h
pid.h
franka_hw::TriggerRate
franka_gazebo::kGraspConsecutiveSamples
const int kGraspConsecutiveSamples
How many times the speed has to drop below resting threshold before the grasping will be checked.
Definition: franka_gripper_sim.h:39
franka_gazebo::FrankaGripperSim::tolerance_move_
double tolerance_move_
[m] inner + outer position tolerances used during grasp
Definition: franka_gripper_sim.h:103
franka_gazebo::FrankaGripperSim::onMoveGoal
void onMoveGoal(const franka_gripper::MoveGoalConstPtr &goal)
Definition: franka_gripper_sim.cpp:316
ros::Duration
franka_gazebo::FrankaGripperSim::finger1_
hardware_interface::JointHandle finger1_
Definition: franka_gripper_sim.h:94
franka_gazebo::FrankaGripperSim::transition
void transition(const State &&state, const Config &&config)
Definition: franka_gripper_sim.cpp:211
franka_gazebo::FrankaGripperSim::update
void update(const ros::Time &now, const ros::Duration &period) override
Definition: franka_gripper_sim.cpp:103
ros::NodeHandle
franka_gazebo::FrankaGripperSim::onHomingGoal
void onHomingGoal(const franka_gripper::HomingGoalConstPtr &goal)
Definition: franka_gripper_sim.cpp:271
franka_gazebo::FrankaGripperSim::Config::tolerance
franka_gripper::GraspEpsilon tolerance
Tolerance range to check if grasping succeeds.
Definition: franka_gripper_sim.h:79
franka_gazebo::FrankaGripperSim::action_gc_
std::unique_ptr< actionlib::SimpleActionServer< control_msgs::GripperCommandAction > > action_gc_
Definition: franka_gripper_sim.h:111


franka_gazebo
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:28