Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
franka_gazebo::FrankaGripperSim Class Reference

Simulate the franka_gripper_node. More...

#include <franka_gripper_sim.h>

Inheritance diagram for franka_gazebo::FrankaGripperSim:
Inheritance graph
[legend]

Classes

struct  Config
 

Public Types

enum  State { IDLE, HOLDING, MOVING, GRASPING }
 
- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
enum  ControllerState {
  ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED,
  ControllerState::WAITING, ControllerState::ABORTED
}
 

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
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (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 ()
 

Private Attributes

std::unique_ptr< actionlib::SimpleActionServer< control_msgs::GripperCommandAction > > action_gc_
 
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::GraspAction > > action_grasp_
 
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::HomingAction > > action_homing_
 
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::MoveAction > > action_move_
 
std::unique_ptr< actionlib::SimpleActionServer< franka_gripper::StopAction > > action_stop_
 
Config config_
 
hardware_interface::JointHandle finger1_
 
hardware_interface::JointHandle finger2_
 
std::mutex mutex_
 
control_toolbox::Pid pid1_
 
control_toolbox::Pid pid2_
 
realtime_tools::RealtimePublisher< sensor_msgs::JointState > pub_
 
franka_hw::TriggerRate rate_trigger_ {30.0}
 
double speed_default_
 
int speed_samples_
 
double speed_threshold_
 
State state_ = State::IDLE
 
double tolerance_gripper_action_
 [m] inner + outer position tolerances used during gripper action More...
 
double tolerance_move_
 [m] inner + outer position tolerances used during grasp More...
 

Additional Inherited Members

- Public Attributes inherited from controller_interface::ControllerBase
ControllerState state_
 
- 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
 

Detailed Description

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.

Member Enumeration Documentation

◆ State

Enumerator
IDLE 

Gripper is not actively controlled, but tracks the other finger to simulate a mimicked joint.

HOLDING 

Gripper is holding position and tracking zero velocity while mainting a desired force.

MOVING 

Gripper is tracking a desired position and velocity.

GRASPING 

Gripper is tracking a desired position and velocity.

On contact it switches to HOLDING if inside the epsilon of the desired grasping width otherwise back to IDLE

Definition at line 64 of file franka_gripper_sim.h.

Member Function Documentation

◆ control()

void franka_gazebo::FrankaGripperSim::control ( hardware_interface::JointHandle joint,
control_toolbox::Pid pid,
double  q_d,
double  dq_d,
double  f_d,
const ros::Duration period 
)
private

Definition at line 190 of file franka_gripper_sim.cpp.

◆ grasp()

bool franka_gazebo::FrankaGripperSim::grasp ( double  width,
double  speed,
double  force,
const franka_gripper::GraspEpsilon &  epsilon 
)
private

libfranka-like method to grasp an object with the gripper

Parameters
[in]widthSize of the object to grasp. [m]
[in]speedClosing speed. [m/s]
[in]forceGrasping force. [N]
[in]epsilonMaximum tolerated deviation between the commanded width and the desired width
Returns
True if the object could be grasped, false otherwise

Definition at line 492 of file franka_gripper_sim.cpp.

◆ init()

bool franka_gazebo::FrankaGripperSim::init ( hardware_interface::EffortJointInterface hw,
ros::NodeHandle nh 
)
override

Definition at line 16 of file franka_gripper_sim.cpp.

◆ interrupt()

void franka_gazebo::FrankaGripperSim::interrupt ( const std::string &  message,
const State except 
)
private

Interrupt any running action server unless the gripper is currently in a specific state.

Parameters
[in]messageThe message to send via the result of all running actions
[in]exceptIf the gripper is currently in this state, don't interrupt any actions

Definition at line 217 of file franka_gripper_sim.cpp.

◆ move()

bool franka_gazebo::FrankaGripperSim::move ( double  width,
double  speed 
)
private

libfranka-like method to move the gripper to a certain position

Parameters
[in]widthIntended opening width. [m]
[in]speedClosing speed. [m/s]
Returns
True if the command was successful, false otherwise.

Definition at line 480 of file franka_gripper_sim.cpp.

◆ onGraspGoal()

void franka_gazebo::FrankaGripperSim::onGraspGoal ( const franka_gripper::GraspGoalConstPtr &  goal)
private

Definition at line 364 of file franka_gripper_sim.cpp.

◆ onGripperActionGoal()

void franka_gazebo::FrankaGripperSim::onGripperActionGoal ( const control_msgs::GripperCommandGoalConstPtr &  goal)
private

Definition at line 418 of file franka_gripper_sim.cpp.

◆ onHomingGoal()

void franka_gazebo::FrankaGripperSim::onHomingGoal ( const franka_gripper::HomingGoalConstPtr &  goal)
private

Definition at line 271 of file franka_gripper_sim.cpp.

◆ onMoveGoal()

void franka_gazebo::FrankaGripperSim::onMoveGoal ( const franka_gripper::MoveGoalConstPtr &  goal)
private

Definition at line 316 of file franka_gripper_sim.cpp.

◆ onStopGoal()

void franka_gazebo::FrankaGripperSim::onStopGoal ( const franka_gripper::StopGoalConstPtr &  goal)
private

Definition at line 256 of file franka_gripper_sim.cpp.

◆ setConfig()

void franka_gazebo::FrankaGripperSim::setConfig ( const Config &&  config)
private

Definition at line 206 of file franka_gripper_sim.cpp.

◆ setState()

void franka_gazebo::FrankaGripperSim::setState ( const State &&  state)
private

Definition at line 201 of file franka_gripper_sim.cpp.

◆ starting()

void franka_gazebo::FrankaGripperSim::starting ( const ros::Time )
overridevirtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 97 of file franka_gripper_sim.cpp.

◆ transition()

void franka_gazebo::FrankaGripperSim::transition ( const State &&  state,
const Config &&  config 
)
private

Definition at line 211 of file franka_gripper_sim.cpp.

◆ update()

void franka_gazebo::FrankaGripperSim::update ( const ros::Time now,
const ros::Duration period 
)
overridevirtual

Implements controller_interface::ControllerBase.

Definition at line 103 of file franka_gripper_sim.cpp.

◆ waitUntilStateChange()

void franka_gazebo::FrankaGripperSim::waitUntilStateChange ( )
private

Definition at line 241 of file franka_gripper_sim.cpp.

Member Data Documentation

◆ action_gc_

std::unique_ptr<actionlib::SimpleActionServer<control_msgs::GripperCommandAction> > franka_gazebo::FrankaGripperSim::action_gc_
private

Definition at line 111 of file franka_gripper_sim.h.

◆ action_grasp_

std::unique_ptr<actionlib::SimpleActionServer<franka_gripper::GraspAction> > franka_gazebo::FrankaGripperSim::action_grasp_
private

Definition at line 110 of file franka_gripper_sim.h.

◆ action_homing_

std::unique_ptr<actionlib::SimpleActionServer<franka_gripper::HomingAction> > franka_gazebo::FrankaGripperSim::action_homing_
private

Definition at line 108 of file franka_gripper_sim.h.

◆ action_move_

std::unique_ptr<actionlib::SimpleActionServer<franka_gripper::MoveAction> > franka_gazebo::FrankaGripperSim::action_move_
private

Definition at line 109 of file franka_gripper_sim.h.

◆ action_stop_

std::unique_ptr<actionlib::SimpleActionServer<franka_gripper::StopAction> > franka_gazebo::FrankaGripperSim::action_stop_
private

Definition at line 107 of file franka_gripper_sim.h.

◆ config_

Config franka_gazebo::FrankaGripperSim::config_
private

Definition at line 88 of file franka_gripper_sim.h.

◆ finger1_

hardware_interface::JointHandle franka_gazebo::FrankaGripperSim::finger1_
private

Definition at line 94 of file franka_gripper_sim.h.

◆ finger2_

hardware_interface::JointHandle franka_gazebo::FrankaGripperSim::finger2_
private

Definition at line 95 of file franka_gripper_sim.h.

◆ mutex_

std::mutex franka_gazebo::FrankaGripperSim::mutex_
private

Definition at line 97 of file franka_gripper_sim.h.

◆ pid1_

control_toolbox::Pid franka_gazebo::FrankaGripperSim::pid1_
private

Definition at line 91 of file franka_gripper_sim.h.

◆ pid2_

control_toolbox::Pid franka_gazebo::FrankaGripperSim::pid2_
private

Definition at line 92 of file franka_gripper_sim.h.

◆ pub_

realtime_tools::RealtimePublisher<sensor_msgs::JointState> franka_gazebo::FrankaGripperSim::pub_
private

Definition at line 93 of file franka_gripper_sim.h.

◆ rate_trigger_

franka_hw::TriggerRate franka_gazebo::FrankaGripperSim::rate_trigger_ {30.0}
private

Definition at line 90 of file franka_gripper_sim.h.

◆ speed_default_

double franka_gazebo::FrankaGripperSim::speed_default_
private

Definition at line 102 of file franka_gripper_sim.h.

◆ speed_samples_

int franka_gazebo::FrankaGripperSim::speed_samples_
private

Definition at line 100 of file franka_gripper_sim.h.

◆ speed_threshold_

double franka_gazebo::FrankaGripperSim::speed_threshold_
private

Definition at line 101 of file franka_gripper_sim.h.

◆ state_

State franka_gazebo::FrankaGripperSim::state_ = State::IDLE
private

Definition at line 87 of file franka_gripper_sim.h.

◆ tolerance_gripper_action_

double franka_gazebo::FrankaGripperSim::tolerance_gripper_action_
private

[m] inner + outer position tolerances used during gripper action

Definition at line 104 of file franka_gripper_sim.h.

◆ tolerance_move_

double franka_gazebo::FrankaGripperSim::tolerance_move_
private

[m] inner + outer position tolerances used during grasp

Definition at line 103 of file franka_gripper_sim.h.


The documentation for this class was generated from the following files:


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