robot.h
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
3 #pragma once
4 
5 #include <functional>
6 #include <memory>
7 #include <mutex>
8 #include <string>
9 
10 #include <franka/command_types.h>
11 #include <franka/control_types.h>
12 #include <franka/duration.h>
13 #include <franka/lowpass_filter.h>
14 #include <franka/robot_state.h>
15 
21 namespace franka {
22 
23 class Model;
24 
42 class Robot {
43  public:
47  using ServerVersion = uint16_t;
48 
61  explicit Robot(const std::string& franka_address,
62  RealtimeConfig realtime_config = RealtimeConfig::kEnforce,
63  size_t log_size = 50);
64 
70  Robot(Robot&& other) noexcept;
71 
79  Robot& operator=(Robot&& other) noexcept;
80 
84  ~Robot() noexcept;
85 
147  void control(std::function<Torques(const RobotState&, franka::Duration)> control_callback,
148  bool limit_rate = true,
149  double cutoff_frequency = kDefaultCutoffFrequency);
150 
175  void control(
176  std::function<Torques(const RobotState&, franka::Duration)> control_callback,
177  std::function<JointPositions(const RobotState&, franka::Duration)> motion_generator_callback,
178  bool limit_rate = true,
179  double cutoff_frequency = kDefaultCutoffFrequency);
180 
205  void control(
206  std::function<Torques(const RobotState&, franka::Duration)> control_callback,
207  std::function<JointVelocities(const RobotState&, franka::Duration)> motion_generator_callback,
208  bool limit_rate = true,
209  double cutoff_frequency = kDefaultCutoffFrequency);
210 
235  void control(
236  std::function<Torques(const RobotState&, franka::Duration)> control_callback,
237  std::function<CartesianPose(const RobotState&, franka::Duration)> motion_generator_callback,
238  bool limit_rate = true,
239  double cutoff_frequency = kDefaultCutoffFrequency);
240 
265  void control(std::function<Torques(const RobotState&, franka::Duration)> control_callback,
266  std::function<CartesianVelocities(const RobotState&, franka::Duration)>
267  motion_generator_callback,
268  bool limit_rate = true,
269  double cutoff_frequency = kDefaultCutoffFrequency);
270 
293  void control(
294  std::function<JointPositions(const RobotState&, franka::Duration)> motion_generator_callback,
295  ControllerMode controller_mode = ControllerMode::kJointImpedance,
296  bool limit_rate = true,
297  double cutoff_frequency = kDefaultCutoffFrequency);
298 
321  void control(
322  std::function<JointVelocities(const RobotState&, franka::Duration)> motion_generator_callback,
323  ControllerMode controller_mode = ControllerMode::kJointImpedance,
324  bool limit_rate = true,
325  double cutoff_frequency = kDefaultCutoffFrequency);
326 
349  void control(
350  std::function<CartesianPose(const RobotState&, franka::Duration)> motion_generator_callback,
351  ControllerMode controller_mode = ControllerMode::kJointImpedance,
352  bool limit_rate = true,
353  double cutoff_frequency = kDefaultCutoffFrequency);
354 
377  void control(std::function<CartesianVelocities(const RobotState&, franka::Duration)>
378  motion_generator_callback,
379  ControllerMode controller_mode = ControllerMode::kJointImpedance,
380  bool limit_rate = true,
381  double cutoff_frequency = kDefaultCutoffFrequency);
382 
407  void read(std::function<bool(const RobotState&)> read_callback);
408 
421  RobotState readOnce();
422 
441  VirtualWallCuboid getVirtualWall(int32_t id);
442 
479  void setCollisionBehavior(const std::array<double, 7>& lower_torque_thresholds_acceleration,
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);
487 
514  void setCollisionBehavior(const std::array<double, 7>& lower_torque_thresholds,
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);
518 
529  void setJointImpedance(
530  const std::array<double, 7>& K_theta); // NOLINT(readability-identifier-naming)
531 
543  const std::array<double, 6>& K_x); // NOLINT(readability-identifier-naming)
544 
559  void setGuidingMode(const std::array<bool, 6>& guiding_mode, bool elbow);
560 
573  void setK(const std::array<double, 16>& EE_T_K); // NOLINT(readability-identifier-naming)
574 
588  void setEE(const std::array<double, 16>& F_T_EE); // NOLINT(readability-identifier-naming)
589 
606  void setLoad(double load_mass,
607  const std::array<double, 3>& F_x_Cload, // NOLINT(readability-identifier-naming)
608  const std::array<double, 9>& load_inertia);
609 
632  [[deprecated("Use franka::lowpassFilter instead")]] void setFilters(
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);
646  void automaticErrorRecovery();
647 
657  void stop();
658 
671  Model loadModel();
672 
678  ServerVersion serverVersion() const noexcept;
679 
681  Robot(const Robot&) = delete;
682  Robot& operator=(const Robot&) = delete;
684 
685  class Impl;
686 
687  private:
688  std::unique_ptr<Impl> impl_;
689  std::mutex control_mutex_;
690 };
691 
692 } // namespace franka
RobotState readOnce()
Waits for a robot state update and returns it.
Stores values for joint velocity motion generation.
Definition: control_types.h:99
RealtimeConfig
Used to decide whether to enforce realtime mode for a control loop thread.
Definition: control_types.h:26
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.
Definition: control_types.h:19
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.
Definition: robot.h:47
void setJointImpedance(const std::array< double, 7 > &K_theta)
Sets the impedance for each joint in the internal controller.
std::unique_ptr< Impl > impl_
Definition: robot.h:685
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 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
std::mutex control_mutex_
Definition: robot.h:689
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.
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:42
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.


libfranka
Author(s): Franka Emika GmbH
autogenerated on Tue Jul 9 2019 03:32:01