61 explicit Robot(
const std::string& franka_address,
63 size_t log_size = 50);
148 bool limit_rate = true,
178 bool limit_rate = true,
179 double cutoff_frequency = kDefaultCutoffFrequency);
208 bool limit_rate = true,
209 double cutoff_frequency = kDefaultCutoffFrequency);
238 bool limit_rate = true,
239 double cutoff_frequency = kDefaultCutoffFrequency);
267 motion_generator_callback,
268 bool limit_rate = true,
269 double cutoff_frequency = kDefaultCutoffFrequency);
296 bool limit_rate = true,
297 double cutoff_frequency = kDefaultCutoffFrequency);
324 bool limit_rate = true,
325 double cutoff_frequency = kDefaultCutoffFrequency);
352 bool limit_rate = true,
353 double cutoff_frequency = kDefaultCutoffFrequency);
378 motion_generator_callback,
380 bool limit_rate = true,
381 double cutoff_frequency = kDefaultCutoffFrequency);
407 void read(std::function<
bool(const RobotState&)> read_callback);
480 const std::array<
double, 7>& upper_torque_thresholds_acceleration,
481 const std::array<
double, 7>& lower_torque_thresholds_nominal,
482 const std::array<
double, 7>& upper_torque_thresholds_nominal,
483 const std::array<
double, 6>& lower_force_thresholds_acceleration,
484 const std::array<
double, 6>& upper_force_thresholds_acceleration,
485 const std::array<
double, 6>& lower_force_thresholds_nominal,
486 const std::array<
double, 6>& upper_force_thresholds_nominal);
515 const std::array<
double, 7>& upper_torque_thresholds,
516 const std::array<
double, 6>& lower_force_thresholds,
517 const std::array<
double, 6>& upper_force_thresholds);
530 const std::array<
double, 7>& K_theta);
543 const std::array<
double, 6>& K_x);
559 void setGuidingMode(const std::array<
bool, 6>& guiding_mode,
bool elbow);
573 void setK(const std::array<
double, 16>& EE_T_K);
588 void setEE(const std::array<
double, 16>& F_T_EE);
607 const std::array<
double, 3>& F_x_Cload,
608 const std::array<
double, 9>& load_inertia);
633 double joint_position_filter_frequency,
634 double joint_velocity_filter_frequency,
635 double cartesian_position_filter_frequency,
636 double cartesian_velocity_filter_frequency,
637 double controller_filter_frequency);
688 std::unique_ptr<Impl>
impl_;
RobotState readOnce()
Waits for a robot state update and returns it.
Stores values for joint velocity motion generation.
RealtimeConfig
Used to decide whether to enforce realtime mode for a control loop thread.
void setGuidingMode(const std::array< bool, 6 > &guiding_mode, bool elbow)
Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw).
ControllerMode
Available controller modes for a franka::Robot.
Stores values for Cartesian velocity motion generation.
Contains types for the commands that can be sent from franka::Robot.
ServerVersion serverVersion() const noexcept
Returns the software version reported by the connected server.
void setEE(const std::array< double, 16 > &F_T_EE)
Sets the transformation from flange to end effector frame.
Robot(const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50)
Establishes a connection with the robot.
uint16_t ServerVersion
Version of the robot server.
void setJointImpedance(const std::array< double, 7 > &K_theta)
Sets the impedance for each joint in the internal controller.
std::unique_ptr< Impl > impl_
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
Contains functions for filtering signals with a low-pass filter.
Model loadModel()
Loads the model library from the robot.
Contains helper types for returning motion generation and joint-level torque commands.
void setCartesianImpedance(const std::array< double, 6 > &K_x)
Sets the Cartesian impedance for (x, y, z, roll, pitch, yaw) in the internal controller.
Represents a duration with millisecond resolution.
Stores joint-level torque commands without gravity and friction.
void setK(const std::array< double, 16 > &EE_T_K)
Sets the transformation from end effector frame to stiffness frame.
VirtualWallCuboid getVirtualWall(int32_t id)
Returns the parameters of a virtual wall.
Parameters of a cuboid used as virtual wall.
std::mutex control_mutex_
void setLoad(double load_mass, const std::array< double, 3 > &F_x_Cload, const std::array< double, 9 > &load_inertia)
Sets dynamic parameters of a payload.
void setCollisionBehavior(const std::array< double, 7 > &lower_torque_thresholds_acceleration, const std::array< double, 7 > &upper_torque_thresholds_acceleration, const std::array< double, 7 > &lower_torque_thresholds_nominal, const std::array< double, 7 > &upper_torque_thresholds_nominal, const std::array< double, 6 > &lower_force_thresholds_acceleration, const std::array< double, 6 > &upper_force_thresholds_acceleration, const std::array< double, 6 > &lower_force_thresholds_nominal, const std::array< double, 6 > &upper_force_thresholds_nominal)
Changes the collision behavior.
void stop()
Stops all currently running motions.
void read(std::function< bool(const RobotState &)> read_callback)
Starts a loop for reading the current robot state.
Stores values for Cartesian pose motion generation.
Contains the franka::RobotState types.
Contains the franka::Duration type.
constexpr double kDefaultCutoffFrequency
Default cutoff frequency.
Calculates poses of joints and dynamic properties of the robot.
Stores values for joint position motion generation.
Describes the robot state.
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
double lowpassFilter(double sample_time, double y, double y_last, double cutoff_frequency)
Applies a first-order low-pass filter.
void automaticErrorRecovery()
Runs automatic error recovery on the robot.
void setFilters(double joint_position_filter_frequency, double joint_velocity_filter_frequency, double cartesian_position_filter_frequency, double cartesian_velocity_filter_frequency, double controller_filter_frequency)
Sets the cut off frequency for the given motion generator or controller.