65 explicit Robot(
const std::string& franka_address,
67 size_t log_size = 50);
152 bool limit_rate = true,
153 double cutoff_frequency = kDefaultCutoffFrequency);
182 bool limit_rate = true,
183 double cutoff_frequency = kDefaultCutoffFrequency);
212 bool limit_rate = true,
213 double cutoff_frequency = kDefaultCutoffFrequency);
242 bool limit_rate = true,
243 double cutoff_frequency = kDefaultCutoffFrequency);
271 motion_generator_callback,
272 bool limit_rate = true,
273 double cutoff_frequency = kDefaultCutoffFrequency);
300 bool limit_rate = true,
301 double cutoff_frequency = kDefaultCutoffFrequency);
328 bool limit_rate = true,
329 double cutoff_frequency = kDefaultCutoffFrequency);
356 bool limit_rate = true,
357 double cutoff_frequency = kDefaultCutoffFrequency);
382 motion_generator_callback,
384 bool limit_rate = true,
385 double cutoff_frequency = kDefaultCutoffFrequency);
411 void read(std::function<
bool(const RobotState&)> read_callback);
484 const std::array<
double, 7>& upper_torque_thresholds_acceleration,
485 const std::array<
double, 7>& lower_torque_thresholds_nominal,
486 const std::array<
double, 7>& upper_torque_thresholds_nominal,
487 const std::array<
double, 6>& lower_force_thresholds_acceleration,
488 const std::array<
double, 6>& upper_force_thresholds_acceleration,
489 const std::array<
double, 6>& lower_force_thresholds_nominal,
490 const std::array<
double, 6>& upper_force_thresholds_nominal);
519 const std::array<
double, 7>& upper_torque_thresholds,
520 const std::array<
double, 6>& lower_force_thresholds,
521 const std::array<
double, 6>& upper_force_thresholds);
534 const std::array<
double, 7>& K_theta);
548 const std::array<
double, 6>& K_x);
564 void setGuidingMode(const std::array<
bool, 6>& guiding_mode,
bool elbow);
578 void setK(const std::array<
double, 16>& EE_T_K);
595 void setEE(const std::array<
double, 16>& NE_T_EE);
614 const std::array<
double, 3>& F_x_Cload,
615 const std::array<
double, 9>& load_inertia);
640 double joint_position_filter_frequency,
641 double joint_velocity_filter_frequency,
642 double cartesian_position_filter_frequency,
643 double cartesian_velocity_filter_frequency,
644 double controller_filter_frequency);
695 std::unique_ptr<Impl> impl_;
696 std::mutex control_mutex_;
RobotState readOnce()
Waits for a robot state update and returns it.
Stores values for joint velocity motion generation.
Definition: control_types.h:99
void setGuidingMode(const std::array< bool, 6 > &guiding_mode, bool elbow)
Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw).
Stores values for Cartesian velocity motion generation.
Definition: control_types.h:201
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.
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.
Definition: robot.h:51
void setJointImpedance(const std::array< double, 7 > &K_theta)
Sets the impedance for each joint in the internal controller.
RealtimeConfig
Used to decide whether to enforce realtime mode for a control loop thread.
Definition: control_types.h:26
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.
Definition: duration.h:19
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
void setEE(const std::array< double, 16 > &NE_T_EE)
Sets the transformation from nominal end effector to end effector frame.
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.
Definition: command_types.h:20
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.
Definition: control_types.h:127
Definition: command_types.h:13
Contains the franka::RobotState types.
Contains the franka::Duration type.
Calculates poses of joints and dynamic properties of the robot.
Definition: model.h:51
Stores values for joint position motion generation.
Definition: control_types.h:72
Describes the robot state.
Definition: robot_state.h:35
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:46
~Robot() noexcept
Closes the connection.
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.
Robot & operator=(Robot &&other) noexcept
Move-assigns this Robot from another Robot instance.
ControllerMode
Available controller modes for a franka::Robot.
Definition: control_types.h:19