Classes | Typedefs | Enumerations | Variables
franka_gazebo Namespace Reference

Classes

class  ControllerVerifier
 Can be used to check controllers in franka_gazebo. More...
 
struct  ErrorRecovery
 
class  FrankaGripperSim
 Simulate the franka_gripper_node. More...
 
class  FrankaHWSim
 A custom implementation of a gazebo_ros_control plugin, which is able to simulate franka interfaces in Gazebo. More...
 
struct  Idle
 
struct  Joint
 A data container holding all relevant information about a robotic joint. More...
 
class  ModelKDL
 Calculates poses of links and dynamic properties of the robot. More...
 
struct  Move
 
struct  StateMachine
 
struct  SwitchControl
 
struct  UserStop
 
struct  UserStopped
 

Typedefs

using JointMap = std::map< std::string, std::shared_ptr< Joint > >
 

Enumerations

enum  ControlMethod { EFFORT, POSITION, VELOCITY }
 Specifies the current control method of the joint. More...
 

Variables

auto contains
 
auto idle = [](franka::RobotState& state) { state.robot_mode = franka::RobotMode::kIdle; }
 
auto isPressed = [](const UserStop& event) { return event.pressed; }
 
auto isReleased = [](const UserStop& event, const JointMap& joints) { return not event.pressed; }
 
auto isStarting
 
auto isStopping
 
const double kDefaultGripperActionSpeed = 0.1
 How fast shall the gripper execute gripper command actions? [m/s]. More...
 
const double kDefaultGripperActionWidthTolerance = 0.005
 When width between fingers is below this, the gripper action succeeds [m]. More...
 
const double kDefaultMoveWidthTolerance = 0.001
 When width between fingers is below this, the move action succeeds [m]. More...
 
const double kDefaultTauExtLowpassFilter = 1.0
 
const int kGraspConsecutiveSamples = 10
 How many times the speed has to drop below resting threshold before the grasping will be checked. More...
 
const double kGraspRestingThreshold = 0.003
 Below which speed the target width should be checked to abort or succeed the grasp action [m/s]. More...
 
const double kMaxFingerWidth = 0.08
 
auto start = [](franka::RobotState& state) { state.robot_mode = franka::RobotMode::kMove; }
 
auto stop
 

Typedef Documentation

◆ JointMap

using franka_gazebo::JointMap = typedef std::map<std::string, std::shared_ptr<Joint> >

Definition at line 14 of file statemachine.h.

Enumeration Type Documentation

◆ ControlMethod

Specifies the current control method of the joint.

Enumerator
EFFORT 
POSITION 
VELOCITY 

Definition at line 17 of file joint.h.

Variable Documentation

◆ contains

auto franka_gazebo::contains
Initial value:
= [](const auto& haystack, const auto& needle) {
return haystack.find(needle) != std::string::npos;
}

Definition at line 29 of file statemachine.h.

◆ idle

auto franka_gazebo::idle = [](franka::RobotState& state) { state.robot_mode = franka::RobotMode::kIdle; }

Definition at line 51 of file statemachine.h.

◆ isPressed

auto franka_gazebo::isPressed = [](const UserStop& event) { return event.pressed; }

Definition at line 32 of file statemachine.h.

◆ isReleased

auto franka_gazebo::isReleased = [](const UserStop& event, const JointMap& joints) { return not event.pressed; }

Definition at line 33 of file statemachine.h.

◆ isStarting

auto franka_gazebo::isStarting
Initial value:
= [](const SwitchControl& event, const JointMap& joints) {
for (auto& joint : joints) {
if (contains(joint.first, "_finger_joint")) {
continue;
}
if (joint.second->control_method) {
return true;
}
}
return false;
}

Definition at line 34 of file statemachine.h.

◆ isStopping

auto franka_gazebo::isStopping
Initial value:
= [](const SwitchControl& event, const JointMap& joints) {
return not isStarting(event, joints);
}

Definition at line 45 of file statemachine.h.

◆ kDefaultGripperActionSpeed

const double franka_gazebo::kDefaultGripperActionSpeed = 0.1

How fast shall the gripper execute gripper command actions? [m/s].

Definition at line 33 of file franka_gripper_sim.h.

◆ kDefaultGripperActionWidthTolerance

const double franka_gazebo::kDefaultGripperActionWidthTolerance = 0.005

When width between fingers is below this, the gripper action succeeds [m].

Definition at line 30 of file franka_gripper_sim.h.

◆ kDefaultMoveWidthTolerance

const double franka_gazebo::kDefaultMoveWidthTolerance = 0.001

When width between fingers is below this, the move action succeeds [m].

Definition at line 27 of file franka_gripper_sim.h.

◆ kDefaultTauExtLowpassFilter

const double franka_gazebo::kDefaultTauExtLowpassFilter = 1.0

Definition at line 30 of file franka_hw_sim.h.

◆ kGraspConsecutiveSamples

const int franka_gazebo::kGraspConsecutiveSamples = 10

How many times the speed has to drop below resting threshold before the grasping will be checked.

Definition at line 39 of file franka_gripper_sim.h.

◆ kGraspRestingThreshold

const double franka_gazebo::kGraspRestingThreshold = 0.003

Below which speed the target width should be checked to abort or succeed the grasp action [m/s].

Definition at line 36 of file franka_gripper_sim.h.

◆ kMaxFingerWidth

const double franka_gazebo::kMaxFingerWidth = 0.08

Definition at line 24 of file franka_gripper_sim.h.

◆ start

auto franka_gazebo::start = [](franka::RobotState& state) { state.robot_mode = franka::RobotMode::kMove; }

Definition at line 50 of file statemachine.h.

◆ stop

auto franka_gazebo::stop
Initial value:
= [](franka::RobotState& state, JointMap& joints) {
ROS_WARN("User stop pressed, stopping robot");
state.robot_mode = franka::RobotMode::kUserStopped;
state.q_d = state.q;
state.dq_d = {0};
state.ddq_d = {0};
for (auto& joint : joints) {
if (contains(joint.first, "_finger_joint")) {
continue;
}
joint.second->stop_position = joint.second->position;
joint.second->desired_position = joint.second->position;
joint.second->desired_velocity = 0;
}
}

Definition at line 52 of file statemachine.h.

franka_gazebo::isStarting
auto isStarting
Definition: statemachine.h:34
franka_gazebo::JointMap
std::map< std::string, std::shared_ptr< Joint > > JointMap
Definition: statemachine.h:14
ROS_WARN
#define ROS_WARN(...)
franka_gazebo::contains
auto contains
Definition: statemachine.h:29


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