Simulate the franka_gripper_node. More...
#include <franka_gripper_sim.h>

Classes | |
| struct | Config |
Public Types | |
| enum | State { IDLE, HOLDING, MOVING, GRASPING } |
Public Types inherited from controller_interface::ControllerBase | |
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
Public Member Functions | |
| bool | init (hardware_interface::EffortJointInterface *hw, ros::NodeHandle &nh) override |
| void | starting (const ros::Time &) override |
| void | update (const ros::Time &now, const ros::Duration &period) override |
Public Member Functions inherited from controller_interface::Controller< hardware_interface::EffortJointInterface > | |
| virtual bool | init (T *, ros::NodeHandle &) |
| virtual bool | init (T *, ros::NodeHandle &, ros::NodeHandle &) |
Public Member Functions inherited from controller_interface::ControllerBase | |
| virtual void | aborting (const ros::Time &) |
| virtual void | aborting (const ros::Time &) |
| bool | abortRequest (const ros::Time &time) |
| bool | abortRequest (const ros::Time &time) |
| ControllerBase ()=default | |
| ControllerBase (const ControllerBase &)=delete | |
| ControllerBase (ControllerBase &&)=delete | |
| bool | isAborted () const |
| bool | isAborted () const |
| bool | isInitialized () const |
| bool | isInitialized () const |
| bool | isRunning () const |
| bool | isRunning () const |
| bool | isStopped () const |
| bool | isStopped () const |
| bool | isWaiting () const |
| bool | isWaiting () const |
| ControllerBase & | operator= (const ControllerBase &)=delete |
| ControllerBase & | operator= (ControllerBase &&)=delete |
| bool | startRequest (const ros::Time &time) |
| bool | startRequest (const ros::Time &time) |
| virtual void | stopping (const ros::Time &) |
| virtual void | stopping (const ros::Time &) |
| bool | stopRequest (const ros::Time &time) |
| bool | stopRequest (const ros::Time &time) |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| virtual void | waiting (const ros::Time &) |
| virtual void | waiting (const ros::Time &) |
| bool | waitRequest (const ros::Time &time) |
| bool | waitRequest (const ros::Time &time) |
| virtual | ~ControllerBase ()=default |
Private Member Functions | |
| void | control (hardware_interface::JointHandle &joint, control_toolbox::Pid &, double q_d, double dq_d, double f_d, const ros::Duration &period) |
| bool | grasp (double width, double speed, double force, const franka_gripper::GraspEpsilon &epsilon) |
| libfranka-like method to grasp an object with the gripper More... | |
| void | interrupt (const std::string &message, const State &except) |
| Interrupt any running action server unless the gripper is currently in a specific state. More... | |
| bool | move (double width, double speed) |
| libfranka-like method to move the gripper to a certain position More... | |
| void | onGraspGoal (const franka_gripper::GraspGoalConstPtr &goal) |
| void | onGripperActionGoal (const control_msgs::GripperCommandGoalConstPtr &goal) |
| void | onHomingGoal (const franka_gripper::HomingGoalConstPtr &goal) |
| void | onMoveGoal (const franka_gripper::MoveGoalConstPtr &goal) |
| void | onStopGoal (const franka_gripper::StopGoalConstPtr &goal) |
| void | setConfig (const Config &&config) |
| void | setState (const State &&state) |
| void | transition (const State &&state, const Config &&config) |
| void | waitUntilStateChange () |
Additional Inherited Members | |
Public Attributes inherited from controller_interface::ControllerBase | |
| ABORTED | |
| CONSTRUCTED | |
| INITIALIZED | |
| RUNNING | |
| enum controller_interface::ControllerBase:: { ... } | state_ |
| STOPPED | |
| WAITING | |
Protected Member Functions inherited from controller_interface::Controller< hardware_interface::EffortJointInterface > | |
| std::string | getHardwareInterfaceType () const |
| bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
Simulate the franka_gripper_node.
Internally this is done via ROS control. This controller assumes there are two finger joints in the URDF which can be effort (force) controlled. It simulates the behavior of the real franka_gripper by offering the same actions:
NOTE: The grasp action has a bug, that it will not succeed nor abort if the target width lets the fingers open. This is because of missing the joint limits interface which lets the finger oscillate at their limits.
Definition at line 61 of file franka_gripper_sim.h.
Definition at line 64 of file franka_gripper_sim.h.
|
private |
Definition at line 190 of file franka_gripper_sim.cpp.
|
private |
libfranka-like method to grasp an object with the gripper
| [in] | width | Size of the object to grasp. [m] |
| [in] | speed | Closing speed. [m/s] |
| [in] | force | Grasping force. [N] |
| [in] | epsilon | Maximum tolerated deviation between the commanded width and the desired width |
Definition at line 492 of file franka_gripper_sim.cpp.
|
override |
Definition at line 16 of file franka_gripper_sim.cpp.
|
private |
Interrupt any running action server unless the gripper is currently in a specific state.
| [in] | message | The message to send via the result of all running actions |
| [in] | except | If the gripper is currently in this state, don't interrupt any actions |
Definition at line 217 of file franka_gripper_sim.cpp.
|
private |
libfranka-like method to move the gripper to a certain position
| [in] | width | Intended opening width. [m] |
| [in] | speed | Closing speed. [m/s] |
Definition at line 480 of file franka_gripper_sim.cpp.
|
private |
Definition at line 364 of file franka_gripper_sim.cpp.
|
private |
Definition at line 418 of file franka_gripper_sim.cpp.
|
private |
Definition at line 271 of file franka_gripper_sim.cpp.
|
private |
Definition at line 316 of file franka_gripper_sim.cpp.
|
private |
Definition at line 256 of file franka_gripper_sim.cpp.
|
private |
Definition at line 206 of file franka_gripper_sim.cpp.
|
private |
Definition at line 201 of file franka_gripper_sim.cpp.
|
overridevirtual |
Reimplemented from controller_interface::ControllerBase.
Definition at line 97 of file franka_gripper_sim.cpp.
|
private |
Definition at line 211 of file franka_gripper_sim.cpp.
|
overridevirtual |
Implements controller_interface::ControllerBase.
Definition at line 103 of file franka_gripper_sim.cpp.
|
private |
Definition at line 241 of file franka_gripper_sim.cpp.
|
private |
Definition at line 111 of file franka_gripper_sim.h.
|
private |
Definition at line 110 of file franka_gripper_sim.h.
|
private |
Definition at line 108 of file franka_gripper_sim.h.
|
private |
Definition at line 109 of file franka_gripper_sim.h.
|
private |
Definition at line 107 of file franka_gripper_sim.h.
|
private |
Definition at line 88 of file franka_gripper_sim.h.
|
private |
Definition at line 94 of file franka_gripper_sim.h.
|
private |
Definition at line 95 of file franka_gripper_sim.h.
|
private |
Definition at line 97 of file franka_gripper_sim.h.
|
private |
Definition at line 91 of file franka_gripper_sim.h.
|
private |
Definition at line 92 of file franka_gripper_sim.h.
|
private |
Definition at line 93 of file franka_gripper_sim.h.
|
private |
Definition at line 90 of file franka_gripper_sim.h.
|
private |
Definition at line 102 of file franka_gripper_sim.h.
|
private |
Definition at line 100 of file franka_gripper_sim.h.
|
private |
Definition at line 101 of file franka_gripper_sim.h.
|
private |
Definition at line 87 of file franka_gripper_sim.h.
|
private |
[m] inner + outer position tolerances used during gripper action
Definition at line 104 of file franka_gripper_sim.h.
|
private |
[m] inner + outer position tolerances used during grasp
Definition at line 103 of file franka_gripper_sim.h.