diff --git a/Logo_FRANKA_ROBOTICS_dark.png b/Logo_FRANKA_ROBOTICS_dark.png new file mode 100644 index 00000000..b38bb6b4 Binary files /dev/null and b/Logo_FRANKA_ROBOTICS_dark.png differ diff --git a/active__control_8h.html b/active__control_8h.html new file mode 100644 index 00000000..a20f74a0 --- /dev/null +++ b/active__control_8h.html @@ -0,0 +1,153 @@ + + + + + + + +libfranka: include/franka/active_control.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Classes
+
+
active_control.h File Reference
+
+
+ +

Implements the ActiveControlBase abstract class. +More...

+
#include <franka/active_control_base.h>
+#include <franka/exception.h>
+#include "robot.h"
+
+Include dependency graph for active_control.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  franka::ActiveControl
 Documented in ActiveControlBase. More...
 
+

Detailed Description

+

Implements the ActiveControlBase abstract class.

+

Contains the franka::ActiveControl, franka::ActiveTorqueControl and franka::ActiveMotionGenerator type.

+
+ + + + diff --git a/active__control_8h__dep__incl.map b/active__control_8h__dep__incl.map new file mode 100644 index 00000000..0e04e39c --- /dev/null +++ b/active__control_8h__dep__incl.map @@ -0,0 +1,5 @@ + + + + + diff --git a/active__control_8h__dep__incl.md5 b/active__control_8h__dep__incl.md5 new file mode 100644 index 00000000..76ef17fe --- /dev/null +++ b/active__control_8h__dep__incl.md5 @@ -0,0 +1 @@ +9a374d8e50e3a608f6533cbfcd76543f \ No newline at end of file diff --git a/active__control_8h__dep__incl.png b/active__control_8h__dep__incl.png new file mode 100644 index 00000000..8e40e06f Binary files /dev/null and b/active__control_8h__dep__incl.png differ diff --git a/active__control_8h__incl.map b/active__control_8h__incl.map new file mode 100644 index 00000000..5b10d8e2 --- /dev/null +++ b/active__control_8h__incl.map @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/active__control_8h__incl.md5 b/active__control_8h__incl.md5 new file mode 100644 index 00000000..b8f86930 --- /dev/null +++ b/active__control_8h__incl.md5 @@ -0,0 +1 @@ +023ffc9f29468d08c3bc15bf2684a02f \ No newline at end of file diff --git a/active__control_8h__incl.png b/active__control_8h__incl.png new file mode 100644 index 00000000..a2ca9250 Binary files /dev/null and b/active__control_8h__incl.png differ diff --git a/active__control_8h_source.html b/active__control_8h_source.html new file mode 100644 index 00000000..0bbfb590 --- /dev/null +++ b/active__control_8h_source.html @@ -0,0 +1,193 @@ + + + + + + + +libfranka: include/franka/active_control.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
active_control.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+ +
6 #include <franka/exception.h>
+
7 
+
8 #include "robot.h"
+
9 
+
16 namespace franka {
+
17 
+ +
22  public:
+
23  ~ActiveControl() override;
+
24 
+
25  std::pair<RobotState, Duration> readOnce() override;
+
26 
+
27  void writeOnce(const Torques& /* control_input */) override {
+
28  throw franka::ControlException(wrong_write_once_method_called);
+
29  };
+
30 
+
31  void writeOnce(const JointPositions& /* motion_generator_input */,
+
32  const std::optional<const Torques>& /*control_input*/) override {
+
33  throw franka::ControlException(wrong_write_once_method_called);
+
34  };
+
35 
+
36  void writeOnce(const JointVelocities& /* motion_generator_input */,
+
37  const std::optional<const Torques>& /* control_input */) override {
+
38  throw franka::ControlException(wrong_write_once_method_called);
+
39  };
+
40 
+
41  void writeOnce(const CartesianPose& /* motion_generator_input */,
+
42  const std::optional<const Torques>& /* control_input */) override {
+
43  throw franka::ControlException(wrong_write_once_method_called);
+
44  };
+
45 
+
46  void writeOnce(const CartesianVelocities& /* motion_generator_input */,
+
47  const std::optional<const Torques>& /* control_input */) override {
+
48  throw franka::ControlException(wrong_write_once_method_called);
+
49  };
+
50 
+
51  void writeOnce(const JointPositions& motion_generator_input) override {
+
52  writeOnce(motion_generator_input, std::optional<const Torques>());
+
53  };
+
54 
+
55  void writeOnce(const JointVelocities& motion_generator_input) override {
+
56  writeOnce(motion_generator_input, std::optional<const Torques>());
+
57  };
+
58 
+
59  void writeOnce(const CartesianPose& motion_generator_input) override {
+
60  writeOnce(motion_generator_input, std::optional<const Torques>());
+
61  };
+
62 
+
63  void writeOnce(const CartesianVelocities& motion_generator_input) override {
+
64  writeOnce(motion_generator_input, std::optional<const Torques>());
+
65  };
+
66 
+
67  protected:
+
76  ActiveControl(std::shared_ptr<Robot::Impl> robot_impl,
+
77  uint32_t motion_id,
+
78  std::unique_lock<std::mutex> control_lock);
+
79 
+
81  std::shared_ptr<Robot::Impl> robot_impl;
+
82 
+
84  uint32_t motion_id;
+
85 
+
87  std::unique_lock<std::mutex> control_lock;
+
88 
+ +
91 
+
93  std::optional<Duration> last_read_access;
+
94 
+
95  private:
+
96  const std::string wrong_write_once_method_called{
+
97  "Wrong writeOnce method called for currently active control!"};
+
98 };
+
99 
+
100 } // namespace franka
+
Abstract interface class as the base of the active controllers.
+
Allows the user to read the state of a Robot and to send new control commands after starting a contro...
Definition: active_control_base.h:27
+
Documented in ActiveControlBase.
Definition: active_control.h:21
+
uint32_t motion_id
motion id of running motion
Definition: active_control.h:84
+
void writeOnce(const CartesianVelocities &, const std::optional< const Torques > &) override
Updates the cartesian velocity and torque commands of an active control.
Definition: active_control.h:46
+
std::optional< Duration > last_read_access
duration to last read access
Definition: active_control.h:93
+
void writeOnce(const JointVelocities &, const std::optional< const Torques > &) override
Updates the joint velocity and torque commands of an active control.
Definition: active_control.h:36
+
ActiveControl(std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock)
Construct a new ActiveControl object.
+
void writeOnce(const CartesianPose &, const std::optional< const Torques > &) override
Updates the cartesian position and torque commands of an active control.
Definition: active_control.h:41
+
std::pair< RobotState, Duration > readOnce() override
Waits for a robot state update and returns it.
+
void writeOnce(const CartesianPose &motion_generator_input) override
Updates the cartesian pose commands of an active control, with internal controller.
Definition: active_control.h:59
+
void writeOnce(const JointPositions &, const std::optional< const Torques > &) override
Updates the joint position and torque commands of an active control.
Definition: active_control.h:31
+
void writeOnce(const JointVelocities &motion_generator_input) override
Updates the joint velocity commands of an active control, with internal controller.
Definition: active_control.h:55
+
void writeOnce(const JointPositions &motion_generator_input) override
Updates the joint position commands of an active control, with internal controller.
Definition: active_control.h:51
+
void writeOnce(const Torques &) override
Updates torque commands of an active control.
Definition: active_control.h:27
+
std::shared_ptr< Robot::Impl > robot_impl
shared pointer to Robot::Impl instance for read and write accesses
Definition: active_control.h:81
+
void writeOnce(const CartesianVelocities &motion_generator_input) override
Updates the cartesian velocity commands of an active control, with internal controller.
Definition: active_control.h:63
+
std::unique_lock< std::mutex > control_lock
control-lock preventing parallel control processes
Definition: active_control.h:87
+
bool control_finished
flag indicating if control process is finished
Definition: active_control.h:90
+
Stores values for Cartesian pose motion generation.
Definition: control_types.h:127
+
Stores values for Cartesian velocity motion generation.
Definition: control_types.h:211
+
Stores values for joint position motion generation.
Definition: control_types.h:72
+
Stores values for joint velocity motion generation.
Definition: control_types.h:99
+
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
ControlException is thrown if an error occurs during motion generation or torque control.
Definition: exception.h:73
+
+ + + + diff --git a/active__control__base_8h.html b/active__control__base_8h.html new file mode 100644 index 00000000..fd269158 --- /dev/null +++ b/active__control__base_8h.html @@ -0,0 +1,148 @@ + + + + + + + +libfranka: include/franka/active_control_base.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Classes
+
+
active_control_base.h File Reference
+
+
+ +

Abstract interface class as the base of the active controllers. +More...

+
#include <franka/control_types.h>
+#include <franka/exception.h>
+#include <franka/robot_state.h>
+#include <memory>
+#include <optional>
+#include <utility>
+
+Include dependency graph for active_control_base.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  franka::ActiveControlBase
 Allows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot. More...
 
+

Detailed Description

+

Abstract interface class as the base of the active controllers.

+
+ + + + diff --git a/active__control__base_8h__dep__incl.map b/active__control__base_8h__dep__incl.map new file mode 100644 index 00000000..14f7dc36 --- /dev/null +++ b/active__control__base_8h__dep__incl.map @@ -0,0 +1,6 @@ + + + + + + diff --git a/active__control__base_8h__dep__incl.md5 b/active__control__base_8h__dep__incl.md5 new file mode 100644 index 00000000..a915c99e --- /dev/null +++ b/active__control__base_8h__dep__incl.md5 @@ -0,0 +1 @@ +a4c32c995e7506a493bc22231017038b \ No newline at end of file diff --git a/active__control__base_8h__dep__incl.png b/active__control__base_8h__dep__incl.png new file mode 100644 index 00000000..5dff5530 Binary files /dev/null and b/active__control__base_8h__dep__incl.png differ diff --git a/active__control__base_8h__incl.map b/active__control__base_8h__incl.map new file mode 100644 index 00000000..9037f57b --- /dev/null +++ b/active__control__base_8h__incl.map @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/active__control__base_8h__incl.md5 b/active__control__base_8h__incl.md5 new file mode 100644 index 00000000..45664dd5 --- /dev/null +++ b/active__control__base_8h__incl.md5 @@ -0,0 +1 @@ +4bffc3ae33d90eb6762ee332775cfebe \ No newline at end of file diff --git a/active__control__base_8h__incl.png b/active__control__base_8h__incl.png new file mode 100644 index 00000000..943e7f58 Binary files /dev/null and b/active__control__base_8h__incl.png differ diff --git a/active__control__base_8h_source.html b/active__control__base_8h_source.html new file mode 100644 index 00000000..a94530f6 --- /dev/null +++ b/active__control__base_8h_source.html @@ -0,0 +1,150 @@ + + + + + + + +libfranka: include/franka/active_control_base.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
active_control_base.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <franka/control_types.h>
+
6 #include <franka/exception.h>
+
7 #include <franka/robot_state.h>
+
8 #include <memory>
+
9 #include <optional>
+
10 #include <utility>
+
11 
+
17 namespace franka {
+
18 
+ +
28  public:
+
29  virtual ~ActiveControlBase() = default;
+
30 
+
40  virtual std::pair<RobotState, Duration> readOnce() = 0;
+
41 
+
48  virtual void writeOnce(const Torques& /* control_input */) = 0;
+
49 
+
56  virtual void writeOnce(const JointPositions& /* motion_generator_input */,
+
57  const std::optional<const Torques>& /*control_input*/) = 0;
+
58 
+
65  virtual void writeOnce(const JointVelocities& /* motion_generator_input */,
+
66  const std::optional<const Torques>& /* control_input */) = 0;
+
73  virtual void writeOnce(const CartesianPose& /* motion_generator_input */,
+
74  const std::optional<const Torques>& /* control_input */) = 0;
+
75 
+
82  virtual void writeOnce(const CartesianVelocities& /* motion_generator_input */,
+
83  const std::optional<const Torques>& /* control_input */) = 0;
+
90  virtual void writeOnce(const JointPositions& motion_generator_input) = 0;
+
91 
+
98  virtual void writeOnce(const JointVelocities& motion_generator_input) = 0;
+
105  virtual void writeOnce(const CartesianPose& motion_generator_input) = 0;
+
106 
+
113  virtual void writeOnce(const CartesianVelocities& motion_generator_input) = 0;
+
114 
+
115  protected:
+
116  ActiveControlBase() = default;
+
117 };
+
118 
+
119 } // namespace franka
+
Allows the user to read the state of a Robot and to send new control commands after starting a contro...
Definition: active_control_base.h:27
+
virtual void writeOnce(const Torques &)=0
Updates torque commands of an active control.
+
virtual void writeOnce(const CartesianVelocities &motion_generator_input)=0
Updates the cartesian velocity commands of an active control, with internal controller.
+
virtual void writeOnce(const JointVelocities &, const std::optional< const Torques > &)=0
Updates the joint velocity and torque commands of an active control.
+
virtual void writeOnce(const CartesianPose &, const std::optional< const Torques > &)=0
Updates the cartesian position and torque commands of an active control.
+
virtual void writeOnce(const JointPositions &motion_generator_input)=0
Updates the joint position commands of an active control, with internal controller.
+
virtual void writeOnce(const CartesianPose &motion_generator_input)=0
Updates the cartesian pose commands of an active control, with internal controller.
+
virtual void writeOnce(const JointPositions &, const std::optional< const Torques > &)=0
Updates the joint position and torque commands of an active control.
+
virtual void writeOnce(const CartesianVelocities &, const std::optional< const Torques > &)=0
Updates the cartesian velocity and torque commands of an active control.
+
virtual void writeOnce(const JointVelocities &motion_generator_input)=0
Updates the joint velocity commands of an active control, with internal controller.
+
virtual std::pair< RobotState, Duration > readOnce()=0
Waits for a robot state update and returns it.
+
Stores values for Cartesian pose motion generation.
Definition: control_types.h:127
+
Stores values for Cartesian velocity motion generation.
Definition: control_types.h:211
+
Stores values for joint position motion generation.
Definition: control_types.h:72
+
Stores values for joint velocity motion generation.
Definition: control_types.h:99
+
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
+
Contains helper types for returning motion generation and joint-level torque commands.
+
Contains exception definitions.
+
Contains the franka::RobotState types.
+
+ + + + diff --git a/active__motion__generator_8h.html b/active__motion__generator_8h.html new file mode 100644 index 00000000..9d23b67e --- /dev/null +++ b/active__motion__generator_8h.html @@ -0,0 +1,141 @@ + + + + + + + +libfranka: include/franka/active_motion_generator.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Classes
+
+
active_motion_generator.h File Reference
+
+
+ +

Contains the franka::ActiveMotionGenerator type. +More...

+
#include "active_control.h"
+
+Include dependency graph for active_motion_generator.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  franka::ActiveMotionGenerator< MotionGeneratorType >
 Allows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot. More...
 
+

Detailed Description

+

Contains the franka::ActiveMotionGenerator type.

+
+ + + + diff --git a/active__motion__generator_8h__incl.map b/active__motion__generator_8h__incl.map new file mode 100644 index 00000000..0065912b --- /dev/null +++ b/active__motion__generator_8h__incl.map @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/active__motion__generator_8h__incl.md5 b/active__motion__generator_8h__incl.md5 new file mode 100644 index 00000000..b74f747e --- /dev/null +++ b/active__motion__generator_8h__incl.md5 @@ -0,0 +1 @@ +136cc88766ca8f4ab2e394bce22ab51f \ No newline at end of file diff --git a/active__motion__generator_8h__incl.png b/active__motion__generator_8h__incl.png new file mode 100644 index 00000000..748cb39d Binary files /dev/null and b/active__motion__generator_8h__incl.png differ diff --git a/active__motion__generator_8h_source.html b/active__motion__generator_8h_source.html new file mode 100644 index 00000000..11173546 --- /dev/null +++ b/active__motion__generator_8h_source.html @@ -0,0 +1,124 @@ + + + + + + + +libfranka: include/franka/active_motion_generator.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
active_motion_generator.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include "active_control.h"
+
6 
+
12 namespace franka {
+
13 
+
21 template <typename MotionGeneratorType>
+ +
23  public:
+
36  void writeOnce(const MotionGeneratorType& motion_generator_input,
+
37  const std::optional<const Torques>& control_input) override;
+
43  friend class Robot;
+
44 
+
45  private:
+
55  ActiveMotionGenerator(std::shared_ptr<Robot::Impl> robot_impl,
+
56  uint32_t motion_id,
+
57  std::unique_lock<std::mutex> control_lock,
+
58  research_interface::robot::Move::ControllerMode controller_type)
+ +
60  controller_type_(controller_type){};
+
61 
+
62  bool isTorqueControlFinished(const std::optional<const Torques>& control_input);
+
63 
+
64  research_interface::robot::Move::ControllerMode controller_type_;
+
65 };
+
66 } // namespace franka
+
Implements the ActiveControlBase abstract class.
+
Documented in ActiveControlBase.
Definition: active_control.h:21
+
uint32_t motion_id
motion id of running motion
Definition: active_control.h:84
+
std::shared_ptr< Robot::Impl > robot_impl
shared pointer to Robot::Impl instance for read and write accesses
Definition: active_control.h:81
+
std::unique_lock< std::mutex > control_lock
control-lock preventing parallel control processes
Definition: active_control.h:87
+
Allows the user to read the state of a Robot and to send new motion generator commands after starting...
Definition: active_motion_generator.h:22
+
void writeOnce(const MotionGeneratorType &motion_generator_input, const std::optional< const Torques > &control_input) override
Updates the motion generator commands of an active control.
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
+ + + + diff --git a/active__torque__control_8h.html b/active__torque__control_8h.html new file mode 100644 index 00000000..e8134dcf --- /dev/null +++ b/active__torque__control_8h.html @@ -0,0 +1,141 @@ + + + + + + + +libfranka: include/franka/active_torque_control.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Classes
+
+
active_torque_control.h File Reference
+
+
+ +

Contains the franka::ActiveTorqueControl type. +More...

+
#include "active_control.h"
+
+Include dependency graph for active_torque_control.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  franka::ActiveTorqueControl
 Allows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot. More...
 
+

Detailed Description

+

Contains the franka::ActiveTorqueControl type.

+
+ + + + diff --git a/active__torque__control_8h__incl.map b/active__torque__control_8h__incl.map new file mode 100644 index 00000000..2f24fc60 --- /dev/null +++ b/active__torque__control_8h__incl.map @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/active__torque__control_8h__incl.md5 b/active__torque__control_8h__incl.md5 new file mode 100644 index 00000000..9128abbe --- /dev/null +++ b/active__torque__control_8h__incl.md5 @@ -0,0 +1 @@ +b31b574c20f489381f32fd3c62c8b7a4 \ No newline at end of file diff --git a/active__torque__control_8h__incl.png b/active__torque__control_8h__incl.png new file mode 100644 index 00000000..fd37df68 Binary files /dev/null and b/active__torque__control_8h__incl.png differ diff --git a/active__torque__control_8h_source.html b/active__torque__control_8h_source.html new file mode 100644 index 00000000..94f4ebba --- /dev/null +++ b/active__torque__control_8h_source.html @@ -0,0 +1,119 @@ + + + + + + + +libfranka: include/franka/active_torque_control.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
active_torque_control.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include "active_control.h"
+
6 
+
12 namespace franka {
+
13 
+ +
22  public:
+
32  void writeOnce(const Torques& control_input) override;
+
33 
+
39  friend class Robot;
+
40 
+
41  private:
+
50  ActiveTorqueControl(std::shared_ptr<Robot::Impl> robot_impl,
+
51  uint32_t motion_id,
+
52  std::unique_lock<std::mutex> control_lock)
+
53  : ActiveControl(std::move(robot_impl), motion_id, std::move(control_lock)){};
+
54 };
+
55 
+
56 } // namespace franka
+
Implements the ActiveControlBase abstract class.
+
Documented in ActiveControlBase.
Definition: active_control.h:21
+
uint32_t motion_id
motion id of running motion
Definition: active_control.h:84
+
std::shared_ptr< Robot::Impl > robot_impl
shared pointer to Robot::Impl instance for read and write accesses
Definition: active_control.h:81
+
std::unique_lock< std::mutex > control_lock
control-lock preventing parallel control processes
Definition: active_control.h:87
+
Allows the user to read the state of a Robot and to send new torque control commands after starting a...
Definition: active_torque_control.h:21
+
void writeOnce(const Torques &control_input) override
Updates the joint-level based torque commands of an active joint effort control.
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
+
+ + + + diff --git a/annotated.html b/annotated.html new file mode 100644 index 00000000..929d7909 --- /dev/null +++ b/annotated.html @@ -0,0 +1,122 @@ + + + + + + + +libfranka: Class List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
Class List
+
+
+
Here are the classes, structs, unions and interfaces with brief descriptions:
+
[detail level 12]
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
 Nfranka
 CActiveControlDocumented in ActiveControlBase
 CActiveControlBaseAllows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot
 CActiveMotionGeneratorAllows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot
 CActiveTorqueControlAllows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot
 CFinishableHelper type for control and motion generation loops
 CTorquesStores joint-level torque commands without gravity and friction
 CJointPositionsStores values for joint position motion generation
 CJointVelocitiesStores values for joint velocity motion generation
 CCartesianPoseStores values for Cartesian pose motion generation
 CCartesianVelocitiesStores values for Cartesian velocity motion generation
 CDurationRepresents a duration with millisecond resolution
 CErrorsEnumerates errors that can occur while controlling a franka::Robot
 CExceptionBase class for all exceptions used by libfranka
 CModelExceptionModelException is thrown if an error occurs when loading the model library
 CNetworkExceptionNetworkException is thrown if a connection to the robot cannot be established, or when a timeout occurs
 CProtocolExceptionProtocolException is thrown if the robot returns an incorrect message
 CIncompatibleVersionExceptionIncompatibleVersionException is thrown if the robot does not support this version of libfranka
 CControlExceptionControlException is thrown if an error occurs during motion generation or torque control
 CCommandExceptionCommandException is thrown if an error occurs during command execution
 CRealtimeExceptionRealtimeException is thrown if realtime priority cannot be set
 CInvalidOperationExceptionInvalidOperationException is thrown if an operation cannot be performed
 CGripperMaintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands
 CGripperStateDescribes the gripper state
 CRobotCommandCommand sent to the robot
 CRecordOne row of the log contains a robot command of timestamp n and a corresponding robot state of timestamp n+1
 CModelCalculates poses of joints and dynamic properties of the robot
 CRobotMaintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot
 CRobotModelImplements RobotModelBase using Pinocchio
 CRobotStateDescribes the robot state
 CVacuumGripperMaintains a network connection to the vacuum gripper, provides the current vacuum gripper state, and allows the execution of commands
 CVacuumGripperStateDescribes the vacuum gripper state
 CMotionGeneratorAn example showing how to generate a joint pose motion to a goal position
 CRobotModelBaseRobot dynamic parameters computed from the URDF model with Pinocchio
+
+
+ + + + diff --git a/bc_s.png b/bc_s.png new file mode 100644 index 00000000..224b29aa Binary files /dev/null and b/bc_s.png differ diff --git a/bdwn.png b/bdwn.png new file mode 100644 index 00000000..940a0b95 Binary files /dev/null and b/bdwn.png differ diff --git a/cartesian_impedance_control_8cpp-example.html b/cartesian_impedance_control_8cpp-example.html new file mode 100644 index 00000000..6e0cd565 --- /dev/null +++ b/cartesian_impedance_control_8cpp-example.html @@ -0,0 +1,224 @@ + + + + + + + +libfranka: cartesian_impedance_control.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
cartesian_impedance_control.cpp
+
+
+

An example showing a simple cartesian impedance controller without inertia shaping that renders a spring damper system where the equilibrium is the initial configuration.After starting the controller try to push the robot around and try different stiffness levels.

+
Warning
collision thresholds are set to high values. Make sure you have the user stop at hand!
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <array>
+
#include <cmath>
+
#include <functional>
+
#include <iostream>
+
+
#include <Eigen/Dense>
+
+ + +
#include <franka/model.h>
+
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
// Check whether the required arguments were passed
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
+
// Compliance parameters
+
const double translational_stiffness{150.0};
+
const double rotational_stiffness{10.0};
+
Eigen::MatrixXd stiffness(6, 6), damping(6, 6);
+
stiffness.setZero();
+
stiffness.topLeftCorner(3, 3) << translational_stiffness * Eigen::MatrixXd::Identity(3, 3);
+
stiffness.bottomRightCorner(3, 3) << rotational_stiffness * Eigen::MatrixXd::Identity(3, 3);
+
damping.setZero();
+
damping.topLeftCorner(3, 3) << 2.0 * sqrt(translational_stiffness) *
+
Eigen::MatrixXd::Identity(3, 3);
+
damping.bottomRightCorner(3, 3) << 2.0 * sqrt(rotational_stiffness) *
+
Eigen::MatrixXd::Identity(3, 3);
+
+
try {
+
// connect to robot
+
franka::Robot robot(argv[1]);
+ +
// load the kinematics and dynamics model
+
franka::Model model = robot.loadModel();
+
+
franka::RobotState initial_state = robot.readOnce();
+
+
// equilibrium point is the initial position
+
Eigen::Affine3d initial_transform(Eigen::Matrix4d::Map(initial_state.O_T_EE.data()));
+
Eigen::Vector3d position_d(initial_transform.translation());
+
Eigen::Quaterniond orientation_d(initial_transform.rotation());
+
+
// set collision behavior
+
robot.setCollisionBehavior({{100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}},
+
{{100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}},
+
{{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}},
+
{{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}});
+
+
// define callback for the torque control loop
+ +
impedance_control_callback = [&](const franka::RobotState& robot_state,
+
franka::Duration /*duration*/) -> franka::Torques {
+
// get state variables
+
std::array<double, 7> coriolis_array = model.coriolis(robot_state);
+
std::array<double, 42> jacobian_array =
+
model.zeroJacobian(franka::Frame::kEndEffector, robot_state);
+
+
// convert to Eigen
+
Eigen::Map<const Eigen::Matrix<double, 7, 1>> coriolis(coriolis_array.data());
+
Eigen::Map<const Eigen::Matrix<double, 6, 7>> jacobian(jacobian_array.data());
+
Eigen::Map<const Eigen::Matrix<double, 7, 1>> q(robot_state.q.data());
+
Eigen::Map<const Eigen::Matrix<double, 7, 1>> dq(robot_state.dq.data());
+
Eigen::Affine3d transform(Eigen::Matrix4d::Map(robot_state.O_T_EE.data()));
+
Eigen::Vector3d position(transform.translation());
+
Eigen::Quaterniond orientation(transform.rotation());
+
+
// compute error to desired equilibrium pose
+
// position error
+
Eigen::Matrix<double, 6, 1> error;
+
error.head(3) << position - position_d;
+
+
// orientation error
+
// "difference" quaternion
+
if (orientation_d.coeffs().dot(orientation.coeffs()) < 0.0) {
+
orientation.coeffs() << -orientation.coeffs();
+
}
+
// "difference" quaternion
+
Eigen::Quaterniond error_quaternion(orientation.inverse() * orientation_d);
+
error.tail(3) << error_quaternion.x(), error_quaternion.y(), error_quaternion.z();
+
// Transform to base frame
+
error.tail(3) << -transform.rotation() * error.tail(3);
+
+
// compute control
+
Eigen::VectorXd tau_task(7), tau_d(7);
+
+
// Spring damper system with damping ratio=1
+
tau_task << jacobian.transpose() * (-stiffness * error - damping * (jacobian * dq));
+
tau_d << tau_task + coriolis;
+
+
std::array<double, 7> tau_d_array{};
+
Eigen::VectorXd::Map(&tau_d_array[0], 7) = tau_d;
+
return tau_d_array;
+
};
+
+
// start real-time control loop
+
std::cout << "WARNING: Collision thresholds are set to high values. "
+
<< "Make sure you have the user stop at hand!" << std::endl
+
<< "After starting try to push the robot and see how it reacts." << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(impedance_control_callback);
+
+
} catch (const franka::Exception& ex) {
+
// print exception
+
std::cout << ex.what() << std::endl;
+
}
+
+
return 0;
+
}
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Calculates poses of joints and dynamic properties of the robot.
Definition: model.h:52
+
std::array< double, 42 > zeroJacobian(Frame frame, const franka::RobotState &robot_state) const
Gets the 6x7 Jacobian for the given joint relative to the base frame.
+
std::array< double, 7 > coriolis(const franka::RobotState &robot_state) const noexcept
Calculates the Coriolis force vector (state-space equation): , in .
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
Model loadModel()
Loads the model library from the robot.
+
virtual RobotState readOnce()
Waits for a robot state update and returns it.
+
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
+
Contains the franka::Duration type.
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains model library types.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
std::array< double, 16 > O_T_EE
Measured end effector pose in base frame.
Definition: robot_state.h:40
+
std::array< double, 7 > q
Measured joint position.
Definition: robot_state.h:233
+
std::array< double, 7 > dq
Measured joint velocity.
Definition: robot_state.h:245
+
+ + + + diff --git a/classMotionGenerator-members.html b/classMotionGenerator-members.html new file mode 100644 index 00000000..7f6dfe5f --- /dev/null +++ b/classMotionGenerator-members.html @@ -0,0 +1,89 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
MotionGenerator Member List
+
+
+ +

This is the complete list of members for MotionGenerator, including all inherited members.

+ + + +
MotionGenerator(double speed_factor, const std::array< double, 7 > q_goal)MotionGenerator
operator()(const franka::RobotState &robot_state, franka::Duration period)MotionGenerator
+ + + + diff --git a/classMotionGenerator.html b/classMotionGenerator.html new file mode 100644 index 00000000..d7dd9f28 --- /dev/null +++ b/classMotionGenerator.html @@ -0,0 +1,188 @@ + + + + + + + +libfranka: MotionGenerator Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
MotionGenerator Class Reference
+
+
+ +

An example showing how to generate a joint pose motion to a goal position. + More...

+ +

#include <examples_common.h>

+ + + + + + + + +

+Public Member Functions

 MotionGenerator (double speed_factor, const std::array< double, 7 > q_goal)
 Creates a new MotionGenerator instance for a target q. More...
 
franka::JointPositions operator() (const franka::RobotState &robot_state, franka::Duration period)
 Sends joint position calculations. More...
 
+

Detailed Description

+

An example showing how to generate a joint pose motion to a goal position.

+

Adapted from: Wisama Khalil and Etienne Dombre. 2002. Modeling, Identification and Control of Robots (Kogan Page Science Paper edition).

+
Examples
communication_test.cpp, generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_cartesian_velocity_motion.cpp, generate_cartesian_velocity_motion_external_control_loop.cpp, generate_consecutive_motions.cpp, generate_elbow_motion.cpp, generate_joint_position_motion.cpp, generate_joint_position_motion_external_control_loop.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, joint_impedance_control.cpp, joint_point_to_point_motion.cpp, motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ MotionGenerator()

+ +
+
+ + + + + + + + + + + + + + + + + + +
MotionGenerator::MotionGenerator (double speed_factor,
const std::array< double, 7 > q_goal 
)
+
+ +

Creates a new MotionGenerator instance for a target q.

+
Parameters
+ + + +
[in]speed_factorGeneral speed factor in range [0, 1].
[in]q_goalTarget joint positions.
+
+
+ +
+
+

Member Function Documentation

+ +

◆ operator()()

+ +
+
+ + + + + + + + + + + + + + + + + + +
franka::JointPositions MotionGenerator::operator() (const franka::RobotStaterobot_state,
franka::Duration period 
)
+
+ +

Sends joint position calculations.

+
Parameters
+ + + +
[in]robot_stateCurrent state of the robot.
[in]periodDuration of execution.
+
+
+
Returns
Joint positions for use inside a control loop.
+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/classRobotModelBase-members.html b/classRobotModelBase-members.html new file mode 100644 index 00000000..0695656b --- /dev/null +++ b/classRobotModelBase-members.html @@ -0,0 +1,91 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+
RobotModelBase Member List
+
+
+ +

This is the complete list of members for RobotModelBase, including all inherited members.

+ + + + + +
coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne)=0RobotModelBasepure virtual
gravity(const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne)=0RobotModelBasepure virtual
mass(const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne)=0RobotModelBasepure virtual
~RobotModelBase()=default (defined in RobotModelBase)RobotModelBasevirtual
+ + + + diff --git a/classRobotModelBase.html b/classRobotModelBase.html new file mode 100644 index 00000000..ef6df65c --- /dev/null +++ b/classRobotModelBase.html @@ -0,0 +1,333 @@ + + + + + + + +libfranka: RobotModelBase Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ +
+
+
+Public Member Functions | +List of all members
+
+
RobotModelBase Class Referenceabstract
+
+
+ +

Robot dynamic parameters computed from the URDF model with Pinocchio. + More...

+ +

#include <robot_model_base.h>

+
+Inheritance diagram for RobotModelBase:
+
+
Inheritance graph
+ + + + +
[legend]
+ + + + + + + + + + + +

+Public Member Functions

virtual void coriolis (const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne)=0
 Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\). More...
 
virtual void gravity (const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne)=0
 Calculates the gravity vector. More...
 
virtual void mass (const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne)=0
 Calculates the 7x7 mass matrix. More...
 
+

Detailed Description

+

Robot dynamic parameters computed from the URDF model with Pinocchio.

+

Member Function Documentation

+ +

◆ coriolis()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
virtual void RobotModelBase::coriolis (const std::array< double, 7 > & q,
const std::array< double, 7 > & dq,
const std::array< double, 9 > & i_total,
double m_total,
const std::array< double, 3 > & f_x_ctotal,
std::array< double, 7 > & c_ne 
)
+
+pure virtual
+
+ +

Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).

+
Parameters
+ + + + + + + +
[in]qJoint position.
[in]dqJoint velocity.
[in]i_totalInertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\).
[in]m_totalWeight of the attached total load including end effector. Unit: \([kg]\).
[in]f_x_ctotalTranslation from flange to center of mass of the attached total load. Unit: \([m]\).
[out]c_neCoriolis force vector. Unit: \([Nm]\).
+
+
+ +

Implemented in franka::RobotModel.

+ +
+
+ +

◆ gravity()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
virtual void RobotModelBase::gravity (const std::array< double, 7 > & q,
const std::array< double, 3 > & g_earth,
double m_total,
const std::array< double, 3 > & f_x_ctotal,
std::array< double, 7 > & g_ne 
)
+
+pure virtual
+
+ +

Calculates the gravity vector.

+

Unit: \([Nm]\).

+
Parameters
+ + + + + + +
[in]qJoint position.
[in]gravity_earthEarth's gravity vector. Unit: \(\frac{m}{s^2}\).
[in]m_totalWeight of the attached total load including end effector. Unit: \([kg]\).
[in]f_x_CtotalTranslation from flange to center of mass of the attached total load.
[out]g_neGravity vector. Unit: \([Nm]\).
+
+
+ +

Implemented in franka::RobotModel.

+ +
+
+ +

◆ mass()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
virtual void RobotModelBase::mass (const std::array< double, 7 > & q,
const std::array< double, 9 > & i_total,
double m_total,
const std::array< double, 3 > & f_x_ctotal,
std::array< double, 49 > & m_ne 
)
+
+pure virtual
+
+ +

Calculates the 7x7 mass matrix.

+

Unit: \([kg \times m^2]\).

+
Parameters
+ + + + + + +
[in]qJoint position.
[in]i_totalInertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\).
[in]m_totalWeight of the attached total load including end effector. Unit: \([kg]\).
[in]f_x_ctotalTranslation from flange to center of mass of the attached total load. Unit: \([m]\).
[out]m_neVectorized 7x7 mass matrix, column-major.
+
+
+ +

Implemented in franka::RobotModel.

+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classRobotModelBase__inherit__graph.map b/classRobotModelBase__inherit__graph.map new file mode 100644 index 00000000..18b3fb6b --- /dev/null +++ b/classRobotModelBase__inherit__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classRobotModelBase__inherit__graph.md5 b/classRobotModelBase__inherit__graph.md5 new file mode 100644 index 00000000..313a50b4 --- /dev/null +++ b/classRobotModelBase__inherit__graph.md5 @@ -0,0 +1 @@ +5205bb79c6252f1a60f22ff1b3838562 \ No newline at end of file diff --git a/classRobotModelBase__inherit__graph.png b/classRobotModelBase__inherit__graph.png new file mode 100644 index 00000000..baa0b89d Binary files /dev/null and b/classRobotModelBase__inherit__graph.png differ diff --git a/classes.html b/classes.html new file mode 100644 index 00000000..7e156d13 --- /dev/null +++ b/classes.html @@ -0,0 +1,129 @@ + + + + + + + +libfranka: Class Index + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
Class Index
+
+
+
A | C | D | E | F | G | I | J | M | N | P | R | T | V
+
+
+
A
+
ActiveControl (franka)
ActiveControlBase (franka)
ActiveMotionGenerator (franka)
ActiveTorqueControl (franka)
+
+
C
+
CartesianPose (franka)
CartesianVelocities (franka)
CommandException (franka)
ControlException (franka)
+
+
D
+
Duration (franka)
+
+
E
+
Errors (franka)
Exception (franka)
+
+
F
+
Finishable (franka)
+
+
G
+
Gripper (franka)
GripperState (franka)
+
+
I
+
IncompatibleVersionException (franka)
InvalidOperationException (franka)
+
+
J
+
JointPositions (franka)
JointVelocities (franka)
+
+
M
+
Model (franka)
ModelException (franka)
MotionGenerator
+
+
N
+
NetworkException (franka)
+
+
P
+
ProtocolException (franka)
+
+
R
+
RealtimeException (franka)
Record (franka)
Robot (franka)
RobotCommand (franka)
RobotModel (franka)
RobotModelBase
RobotState (franka)
+
+
T
+
Torques (franka)
+
+
V
+
VacuumGripper (franka)
VacuumGripperState (franka)
+
+
+ + + + diff --git a/classfranka_1_1ActiveControl-members.html b/classfranka_1_1ActiveControl-members.html new file mode 100644 index 00000000..45ef5e3c --- /dev/null +++ b/classfranka_1_1ActiveControl-members.html @@ -0,0 +1,110 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::ActiveControl Member List
+
+
+ +

This is the complete list of members for franka::ActiveControl, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + +
ActiveControl(std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock)franka::ActiveControlprotected
ActiveControlBase()=default (defined in franka::ActiveControlBase)franka::ActiveControlBaseprotected
control_finishedfranka::ActiveControlprotected
control_lockfranka::ActiveControlprotected
last_read_accessfranka::ActiveControlprotected
motion_idfranka::ActiveControlprotected
readOnce() overridefranka::ActiveControlvirtual
robot_implfranka::ActiveControlprotected
writeOnce(const Torques &) overridefranka::ActiveControlinlinevirtual
writeOnce(const JointPositions &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
writeOnce(const JointVelocities &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
writeOnce(const CartesianPose &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
writeOnce(const CartesianVelocities &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
writeOnce(const JointPositions &motion_generator_input) overridefranka::ActiveControlinlinevirtual
writeOnce(const JointVelocities &motion_generator_input) overridefranka::ActiveControlinlinevirtual
writeOnce(const CartesianPose &motion_generator_input) overridefranka::ActiveControlinlinevirtual
writeOnce(const CartesianVelocities &motion_generator_input) overridefranka::ActiveControlinlinevirtual
~ActiveControl() override (defined in franka::ActiveControl)franka::ActiveControl
~ActiveControlBase()=default (defined in franka::ActiveControlBase)franka::ActiveControlBasevirtual
+ + + + diff --git a/classfranka_1_1ActiveControl.html b/classfranka_1_1ActiveControl.html new file mode 100644 index 00000000..86b25f0b --- /dev/null +++ b/classfranka_1_1ActiveControl.html @@ -0,0 +1,619 @@ + + + + + + + +libfranka: franka::ActiveControl Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Protected Member Functions | +Protected Attributes | +List of all members
+
+
franka::ActiveControl Class Reference
+
+
+ +

Documented in ActiveControlBase. + More...

+ +

#include <active_control.h>

+
+Inheritance diagram for franka::ActiveControl:
+
+
Inheritance graph
+ + + + + + +
[legend]
+
+Collaboration diagram for franka::ActiveControl:
+
+
Collaboration graph
+ + + + +
[legend]
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

std::pair< RobotState, DurationreadOnce () override
 Waits for a robot state update and returns it. More...
 
void writeOnce (const Torques &) override
 Updates torque commands of an active control. More...
 
void writeOnce (const JointPositions &, const std::optional< const Torques > &) override
 Updates the joint position and torque commands of an active control. More...
 
void writeOnce (const JointVelocities &, const std::optional< const Torques > &) override
 Updates the joint velocity and torque commands of an active control. More...
 
void writeOnce (const CartesianPose &, const std::optional< const Torques > &) override
 Updates the cartesian position and torque commands of an active control. More...
 
void writeOnce (const CartesianVelocities &, const std::optional< const Torques > &) override
 Updates the cartesian velocity and torque commands of an active control. More...
 
void writeOnce (const JointPositions &motion_generator_input) override
 Updates the joint position commands of an active control, with internal controller. More...
 
void writeOnce (const JointVelocities &motion_generator_input) override
 Updates the joint velocity commands of an active control, with internal controller. More...
 
void writeOnce (const CartesianPose &motion_generator_input) override
 Updates the cartesian pose commands of an active control, with internal controller. More...
 
void writeOnce (const CartesianVelocities &motion_generator_input) override
 Updates the cartesian velocity commands of an active control, with internal controller. More...
 
+ + + + +

+Protected Member Functions

 ActiveControl (std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock)
 Construct a new ActiveControl object. More...
 
+ + + + + + + + + + + + + + + + +

+Protected Attributes

+std::shared_ptr< Robot::Impl > robot_impl
 shared pointer to Robot::Impl instance for read and write accesses
 
+uint32_t motion_id
 motion id of running motion
 
+std::unique_lock< std::mutex > control_lock
 control-lock preventing parallel control processes
 
+bool control_finished
 flag indicating if control process is finished
 
+std::optional< Durationlast_read_access
 duration to last read access
 
+

Detailed Description

+

Documented in ActiveControlBase.

+

Constructor & Destructor Documentation

+ +

◆ ActiveControl()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + +
franka::ActiveControl::ActiveControl (std::shared_ptr< Robot::Impl > robot_impl,
uint32_t motion_id,
std::unique_lock< std::mutex > control_lock 
)
+
+protected
+
+ +

Construct a new ActiveControl object.

+
Parameters
+ + + + +
robot_implshared_ptr to the Robot::Impl in the Robot
motion_idid of the managed motion
control_lockof the Robot, preventing other read and write accesses during the active control
+
+
+ +
+
+

Member Function Documentation

+ +

◆ readOnce()

+ +
+
+ + + + + +
+ + + + + + + +
std::pair<RobotState, Duration> franka::ActiveControl::readOnce ()
+
+overridevirtual
+
+ +

Waits for a robot state update and returns it.

+
Returns
Current robot state & time since last read operation
+
Exceptions
+ + + + +
NetworkExceptionif the connection is lost, e.g. after a timeout.
ProtocolExceptionif robot returns an unexpected message.
ControlExceptionif robot is in an error state.
+
+
+ +

Implements franka::ActiveControlBase.

+ +
+
+ +

◆ writeOnce() [1/9]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void franka::ActiveControl::writeOnce (const CartesianPose,
const std::optional< const Torques > &  
)
+
+inlineoverridevirtual
+
+ +

Updates the cartesian position and torque commands of an active control.

+

hint: implemented in ActiveMotionGenerator<CartesianPose>

+ +

Implements franka::ActiveControlBase.

+ +
+
+ +

◆ writeOnce() [2/9]

+ +
+
+ + + + + +
+ + + + + + + + +
void franka::ActiveControl::writeOnce (const CartesianPosemotion_generator_input)
+
+inlineoverridevirtual
+
+ +

Updates the cartesian pose commands of an active control, with internal controller.

+
Parameters
+ + +
motion_generator_inputthe new motion generator input
+
+
+ +

Implements franka::ActiveControlBase.

+ +
+
+ +

◆ writeOnce() [3/9]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void franka::ActiveControl::writeOnce (const CartesianVelocities,
const std::optional< const Torques > &  
)
+
+inlineoverridevirtual
+
+ +

Updates the cartesian velocity and torque commands of an active control.

+

hint: implemented in ActiveMotionGenerator<CartesianVelocities>

+ +

Implements franka::ActiveControlBase.

+ +
+
+ +

◆ writeOnce() [4/9]

+ +
+
+ + + + + +
+ + + + + + + + +
void franka::ActiveControl::writeOnce (const CartesianVelocitiesmotion_generator_input)
+
+inlineoverridevirtual
+
+ +

Updates the cartesian velocity commands of an active control, with internal controller.

+
Parameters
+ + +
motion_generator_inputthe new motion generator input
+
+
+ +

Implements franka::ActiveControlBase.

+ +
+
+ +

◆ writeOnce() [5/9]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void franka::ActiveControl::writeOnce (const JointPositions,
const std::optional< const Torques > &  
)
+
+inlineoverridevirtual
+
+ +

Updates the joint position and torque commands of an active control.

+

hint: implemented in ActiveMotionGenerator<JointPositions>

+ +

Implements franka::ActiveControlBase.

+ +
+
+ +

◆ writeOnce() [6/9]

+ +
+
+ + + + + +
+ + + + + + + + +
void franka::ActiveControl::writeOnce (const JointPositionsmotion_generator_input)
+
+inlineoverridevirtual
+
+ +

Updates the joint position commands of an active control, with internal controller.

+
Parameters
+ + +
motion_generator_inputthe new motion generator input
+
+
+ +

Implements franka::ActiveControlBase.

+ +
+
+ +

◆ writeOnce() [7/9]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void franka::ActiveControl::writeOnce (const JointVelocities,
const std::optional< const Torques > &  
)
+
+inlineoverridevirtual
+
+ +

Updates the joint velocity and torque commands of an active control.

+

hint: implemented in ActiveMotionGenerator<JointVelocities>

+ +

Implements franka::ActiveControlBase.

+ +
+
+ +

◆ writeOnce() [8/9]

+ +
+
+ + + + + +
+ + + + + + + + +
void franka::ActiveControl::writeOnce (const JointVelocitiesmotion_generator_input)
+
+inlineoverridevirtual
+
+ +

Updates the joint velocity commands of an active control, with internal controller.

+
Parameters
+ + +
motion_generator_inputthe new motion generator input
+
+
+ +

Implements franka::ActiveControlBase.

+ +
+
+ +

◆ writeOnce() [9/9]

+ +
+
+ + + + + +
+ + + + + + + + +
void franka::ActiveControl::writeOnce (const Torques)
+
+inlineoverridevirtual
+
+ +

Updates torque commands of an active control.

+

hint: implemented in ActiveTorqueControl

+ +

Implements franka::ActiveControlBase.

+ +

Reimplemented in franka::ActiveTorqueControl.

+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1ActiveControlBase-members.html b/classfranka_1_1ActiveControlBase-members.html new file mode 100644 index 00000000..cab53c1f --- /dev/null +++ b/classfranka_1_1ActiveControlBase-members.html @@ -0,0 +1,103 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::ActiveControlBase Member List
+
+
+ +

This is the complete list of members for franka::ActiveControlBase, including all inherited members.

+ + + + + + + + + + + + + +
ActiveControlBase()=default (defined in franka::ActiveControlBase)franka::ActiveControlBaseprotected
readOnce()=0franka::ActiveControlBasepure virtual
writeOnce(const Torques &)=0franka::ActiveControlBasepure virtual
writeOnce(const JointPositions &, const std::optional< const Torques > &)=0franka::ActiveControlBasepure virtual
writeOnce(const JointVelocities &, const std::optional< const Torques > &)=0franka::ActiveControlBasepure virtual
writeOnce(const CartesianPose &, const std::optional< const Torques > &)=0franka::ActiveControlBasepure virtual
writeOnce(const CartesianVelocities &, const std::optional< const Torques > &)=0franka::ActiveControlBasepure virtual
writeOnce(const JointPositions &motion_generator_input)=0franka::ActiveControlBasepure virtual
writeOnce(const JointVelocities &motion_generator_input)=0franka::ActiveControlBasepure virtual
writeOnce(const CartesianPose &motion_generator_input)=0franka::ActiveControlBasepure virtual
writeOnce(const CartesianVelocities &motion_generator_input)=0franka::ActiveControlBasepure virtual
~ActiveControlBase()=default (defined in franka::ActiveControlBase)franka::ActiveControlBasevirtual
+ + + + diff --git a/classfranka_1_1ActiveControlBase.html b/classfranka_1_1ActiveControlBase.html new file mode 100644 index 00000000..054954c3 --- /dev/null +++ b/classfranka_1_1ActiveControlBase.html @@ -0,0 +1,525 @@ + + + + + + + +libfranka: franka::ActiveControlBase Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +List of all members
+
+
franka::ActiveControlBase Class Referenceabstract
+
+
+ +

Allows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot. + More...

+ +

#include <active_control_base.h>

+
+Inheritance diagram for franka::ActiveControlBase:
+
+
Inheritance graph
+ + + + + + +
[legend]
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

virtual std::pair< RobotState, DurationreadOnce ()=0
 Waits for a robot state update and returns it. More...
 
virtual void writeOnce (const Torques &)=0
 Updates torque commands of an active control. More...
 
virtual void writeOnce (const JointPositions &, const std::optional< const Torques > &)=0
 Updates the joint position and torque commands of an active control. More...
 
virtual void writeOnce (const JointVelocities &, const std::optional< const Torques > &)=0
 Updates the joint velocity and torque commands of an active control. More...
 
virtual void writeOnce (const CartesianPose &, const std::optional< const Torques > &)=0
 Updates the cartesian position and torque commands of an active control. More...
 
virtual void writeOnce (const CartesianVelocities &, const std::optional< const Torques > &)=0
 Updates the cartesian velocity and torque commands of an active control. More...
 
virtual void writeOnce (const JointPositions &motion_generator_input)=0
 Updates the joint position commands of an active control, with internal controller. More...
 
virtual void writeOnce (const JointVelocities &motion_generator_input)=0
 Updates the joint velocity commands of an active control, with internal controller. More...
 
virtual void writeOnce (const CartesianPose &motion_generator_input)=0
 Updates the cartesian pose commands of an active control, with internal controller. More...
 
virtual void writeOnce (const CartesianVelocities &motion_generator_input)=0
 Updates the cartesian velocity commands of an active control, with internal controller. More...
 
+

Detailed Description

+

Allows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot.

+

hint: To create an ActiveControlBase, see franka::ActiveTorqueControl or franka::ActiveMotionGenerator

+

Member Function Documentation

+ +

◆ readOnce()

+ +
+
+ + + + + +
+ + + + + + + +
virtual std::pair<RobotState, Duration> franka::ActiveControlBase::readOnce ()
+
+pure virtual
+
+ +

Waits for a robot state update and returns it.

+
Returns
Current robot state & time since last read operation
+
Exceptions
+ + + + +
NetworkExceptionif the connection is lost, e.g. after a timeout.
ProtocolExceptionif robot returns an unexpected message.
ControlExceptionif robot is in an error state.
+
+
+ +

Implemented in franka::ActiveControl.

+ +
+
+ +

◆ writeOnce() [1/9]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
virtual void franka::ActiveControlBase::writeOnce (const CartesianPose,
const std::optional< const Torques > &  
)
+
+pure virtual
+
+ +

Updates the cartesian position and torque commands of an active control.

+

hint: implemented in ActiveMotionGenerator<CartesianPose>

+ +

Implemented in franka::ActiveControl.

+ +
+
+ +

◆ writeOnce() [2/9]

+ +
+
+ + + + + +
+ + + + + + + + +
virtual void franka::ActiveControlBase::writeOnce (const CartesianPosemotion_generator_input)
+
+pure virtual
+
+ +

Updates the cartesian pose commands of an active control, with internal controller.

+
Parameters
+ + +
motion_generator_inputthe new motion generator input
+
+
+ +

Implemented in franka::ActiveControl.

+ +
+
+ +

◆ writeOnce() [3/9]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
virtual void franka::ActiveControlBase::writeOnce (const CartesianVelocities,
const std::optional< const Torques > &  
)
+
+pure virtual
+
+ +

Updates the cartesian velocity and torque commands of an active control.

+

hint: implemented in ActiveMotionGenerator<CartesianVelocities>

+ +

Implemented in franka::ActiveControl.

+ +
+
+ +

◆ writeOnce() [4/9]

+ +
+
+ + + + + +
+ + + + + + + + +
virtual void franka::ActiveControlBase::writeOnce (const CartesianVelocitiesmotion_generator_input)
+
+pure virtual
+
+ +

Updates the cartesian velocity commands of an active control, with internal controller.

+
Parameters
+ + +
motion_generator_inputthe new motion generator input
+
+
+ +

Implemented in franka::ActiveControl.

+ +
+
+ +

◆ writeOnce() [5/9]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
virtual void franka::ActiveControlBase::writeOnce (const JointPositions,
const std::optional< const Torques > &  
)
+
+pure virtual
+
+ +

Updates the joint position and torque commands of an active control.

+

hint: implemented in ActiveMotionGenerator<JointPositions>

+ +

Implemented in franka::ActiveControl.

+ +
+
+ +

◆ writeOnce() [6/9]

+ +
+
+ + + + + +
+ + + + + + + + +
virtual void franka::ActiveControlBase::writeOnce (const JointPositionsmotion_generator_input)
+
+pure virtual
+
+ +

Updates the joint position commands of an active control, with internal controller.

+
Parameters
+ + +
motion_generator_inputthe new motion generator input
+
+
+ +

Implemented in franka::ActiveControl.

+ +
+
+ +

◆ writeOnce() [7/9]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
virtual void franka::ActiveControlBase::writeOnce (const JointVelocities,
const std::optional< const Torques > &  
)
+
+pure virtual
+
+ +

Updates the joint velocity and torque commands of an active control.

+

hint: implemented in ActiveMotionGenerator<JointVelocities>

+ +

Implemented in franka::ActiveControl.

+ +
+
+ +

◆ writeOnce() [8/9]

+ +
+
+ + + + + +
+ + + + + + + + +
virtual void franka::ActiveControlBase::writeOnce (const JointVelocitiesmotion_generator_input)
+
+pure virtual
+
+ +

Updates the joint velocity commands of an active control, with internal controller.

+
Parameters
+ + +
motion_generator_inputthe new motion generator input
+
+
+ +

Implemented in franka::ActiveControl.

+ +
+
+ +

◆ writeOnce() [9/9]

+ +
+
+ + + + + +
+ + + + + + + + +
virtual void franka::ActiveControlBase::writeOnce (const Torques)
+
+pure virtual
+
+ +

Updates torque commands of an active control.

+

hint: implemented in ActiveTorqueControl

+ +

Implemented in franka::ActiveTorqueControl, and franka::ActiveControl.

+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1ActiveControlBase__inherit__graph.map b/classfranka_1_1ActiveControlBase__inherit__graph.map new file mode 100644 index 00000000..002eb182 --- /dev/null +++ b/classfranka_1_1ActiveControlBase__inherit__graph.map @@ -0,0 +1,6 @@ + + + + + + diff --git a/classfranka_1_1ActiveControlBase__inherit__graph.md5 b/classfranka_1_1ActiveControlBase__inherit__graph.md5 new file mode 100644 index 00000000..7ba6e473 --- /dev/null +++ b/classfranka_1_1ActiveControlBase__inherit__graph.md5 @@ -0,0 +1 @@ +aa03fd1901c28b61a439fe458b0e5614 \ No newline at end of file diff --git a/classfranka_1_1ActiveControlBase__inherit__graph.png b/classfranka_1_1ActiveControlBase__inherit__graph.png new file mode 100644 index 00000000..230e2662 Binary files /dev/null and b/classfranka_1_1ActiveControlBase__inherit__graph.png differ diff --git a/classfranka_1_1ActiveControl__coll__graph.map b/classfranka_1_1ActiveControl__coll__graph.map new file mode 100644 index 00000000..dd4e764f --- /dev/null +++ b/classfranka_1_1ActiveControl__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1ActiveControl__coll__graph.md5 b/classfranka_1_1ActiveControl__coll__graph.md5 new file mode 100644 index 00000000..c8f07a3c --- /dev/null +++ b/classfranka_1_1ActiveControl__coll__graph.md5 @@ -0,0 +1 @@ +e649630b56bc1d780882f73637fc8cdd \ No newline at end of file diff --git a/classfranka_1_1ActiveControl__coll__graph.png b/classfranka_1_1ActiveControl__coll__graph.png new file mode 100644 index 00000000..61ee0188 Binary files /dev/null and b/classfranka_1_1ActiveControl__coll__graph.png differ diff --git a/classfranka_1_1ActiveControl__inherit__graph.map b/classfranka_1_1ActiveControl__inherit__graph.map new file mode 100644 index 00000000..ac16dbee --- /dev/null +++ b/classfranka_1_1ActiveControl__inherit__graph.map @@ -0,0 +1,6 @@ + + + + + + diff --git a/classfranka_1_1ActiveControl__inherit__graph.md5 b/classfranka_1_1ActiveControl__inherit__graph.md5 new file mode 100644 index 00000000..0ae66989 --- /dev/null +++ b/classfranka_1_1ActiveControl__inherit__graph.md5 @@ -0,0 +1 @@ +dbf0db27a226cca34edfe498f13494fe \ No newline at end of file diff --git a/classfranka_1_1ActiveControl__inherit__graph.png b/classfranka_1_1ActiveControl__inherit__graph.png new file mode 100644 index 00000000..31500519 Binary files /dev/null and b/classfranka_1_1ActiveControl__inherit__graph.png differ diff --git a/classfranka_1_1ActiveMotionGenerator-members.html b/classfranka_1_1ActiveMotionGenerator-members.html new file mode 100644 index 00000000..cc034dc0 --- /dev/null +++ b/classfranka_1_1ActiveMotionGenerator-members.html @@ -0,0 +1,112 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::ActiveMotionGenerator< MotionGeneratorType > Member List
+
+
+ +

This is the complete list of members for franka::ActiveMotionGenerator< MotionGeneratorType >, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + +
ActiveControl(std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock)franka::ActiveControlprotected
ActiveControlBase()=default (defined in franka::ActiveControlBase)franka::ActiveControlBaseprotected
control_finishedfranka::ActiveControlprotected
control_lockfranka::ActiveControlprotected
last_read_accessfranka::ActiveControlprotected
motion_idfranka::ActiveControlprotected
readOnce() overridefranka::ActiveControlvirtual
Robot classfranka::ActiveMotionGenerator< MotionGeneratorType >friend
robot_implfranka::ActiveControlprotected
writeOnce(const MotionGeneratorType &motion_generator_input, const std::optional< const Torques > &control_input) overridefranka::ActiveMotionGenerator< MotionGeneratorType >
franka::ActiveControl::writeOnce(const Torques &) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const JointPositions &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const JointVelocities &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const CartesianPose &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const CartesianVelocities &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const JointPositions &motion_generator_input) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const JointVelocities &motion_generator_input) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const CartesianPose &motion_generator_input) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const CartesianVelocities &motion_generator_input) overridefranka::ActiveControlinlinevirtual
~ActiveControl() override (defined in franka::ActiveControl)franka::ActiveControl
~ActiveControlBase()=default (defined in franka::ActiveControlBase)franka::ActiveControlBasevirtual
+ + + + diff --git a/classfranka_1_1ActiveMotionGenerator.html b/classfranka_1_1ActiveMotionGenerator.html new file mode 100644 index 00000000..20457033 --- /dev/null +++ b/classfranka_1_1ActiveMotionGenerator.html @@ -0,0 +1,254 @@ + + + + + + + +libfranka: franka::ActiveMotionGenerator< MotionGeneratorType > Class Template Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Friends | +List of all members
+
+
franka::ActiveMotionGenerator< MotionGeneratorType > Class Template Reference
+
+
+ +

Allows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot. + More...

+ +

#include <active_motion_generator.h>

+
+Inheritance diagram for franka::ActiveMotionGenerator< MotionGeneratorType >:
+
+
Inheritance graph
+ + + + + +
[legend]
+
+Collaboration diagram for franka::ActiveMotionGenerator< MotionGeneratorType >:
+
+
Collaboration graph
+ + + + + +
[legend]
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

void writeOnce (const MotionGeneratorType &motion_generator_input, const std::optional< const Torques > &control_input) override
 Updates the motion generator commands of an active control. More...
 
- Public Member Functions inherited from franka::ActiveControl
std::pair< RobotState, DurationreadOnce () override
 Waits for a robot state update and returns it. More...
 
void writeOnce (const Torques &) override
 Updates torque commands of an active control. More...
 
void writeOnce (const JointPositions &, const std::optional< const Torques > &) override
 Updates the joint position and torque commands of an active control. More...
 
void writeOnce (const JointVelocities &, const std::optional< const Torques > &) override
 Updates the joint velocity and torque commands of an active control. More...
 
void writeOnce (const CartesianPose &, const std::optional< const Torques > &) override
 Updates the cartesian position and torque commands of an active control. More...
 
void writeOnce (const CartesianVelocities &, const std::optional< const Torques > &) override
 Updates the cartesian velocity and torque commands of an active control. More...
 
void writeOnce (const JointPositions &motion_generator_input) override
 Updates the joint position commands of an active control, with internal controller. More...
 
void writeOnce (const JointVelocities &motion_generator_input) override
 Updates the joint velocity commands of an active control, with internal controller. More...
 
void writeOnce (const CartesianPose &motion_generator_input) override
 Updates the cartesian pose commands of an active control, with internal controller. More...
 
void writeOnce (const CartesianVelocities &motion_generator_input) override
 Updates the cartesian velocity commands of an active control, with internal controller. More...
 
+ + + + +

+Friends

+class Robot
 franka::Robot as friend to allow construction of ActiveMotionGenerator<MotionGeneratorType> in start<MotionGeneratorType>Control methods
 
+ + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Protected Member Functions inherited from franka::ActiveControl
 ActiveControl (std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock)
 Construct a new ActiveControl object. More...
 
- Protected Attributes inherited from franka::ActiveControl
+std::shared_ptr< Robot::Impl > robot_impl
 shared pointer to Robot::Impl instance for read and write accesses
 
+uint32_t motion_id
 motion id of running motion
 
+std::unique_lock< std::mutex > control_lock
 control-lock preventing parallel control processes
 
+bool control_finished
 flag indicating if control process is finished
 
+std::optional< Durationlast_read_access
 duration to last read access
 
+

Detailed Description

+

template<typename MotionGeneratorType>
+class franka::ActiveMotionGenerator< MotionGeneratorType >

+ +

Allows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot.

+

hint: To create an ActiveMotionGenerator, see franka::Robot

+

Member Function Documentation

+ +

◆ writeOnce()

+ +
+
+
+template<typename MotionGeneratorType >
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void franka::ActiveMotionGenerator< MotionGeneratorType >::writeOnce (const MotionGeneratorType & motion_generator_input,
const std::optional< const Torques > & control_input 
)
+
+override
+
+ +

Updates the motion generator commands of an active control.

+
Parameters
+ + + +
motion_generator_inputthe new motion generator input
control_inputoptional: the external control input for each joint, if an external controller is used
+
+
+
Exceptions
+ + + +
ControlExceptionif an error related to torque control or motion generation occurred, or the motion was already finished.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1ActiveMotionGenerator__coll__graph.map b/classfranka_1_1ActiveMotionGenerator__coll__graph.map new file mode 100644 index 00000000..952cec4f --- /dev/null +++ b/classfranka_1_1ActiveMotionGenerator__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/classfranka_1_1ActiveMotionGenerator__coll__graph.md5 b/classfranka_1_1ActiveMotionGenerator__coll__graph.md5 new file mode 100644 index 00000000..291f0ddc --- /dev/null +++ b/classfranka_1_1ActiveMotionGenerator__coll__graph.md5 @@ -0,0 +1 @@ +f15dced3563b4a11398c9b07dbca4622 \ No newline at end of file diff --git a/classfranka_1_1ActiveMotionGenerator__coll__graph.png b/classfranka_1_1ActiveMotionGenerator__coll__graph.png new file mode 100644 index 00000000..96f6fe08 Binary files /dev/null and b/classfranka_1_1ActiveMotionGenerator__coll__graph.png differ diff --git a/classfranka_1_1ActiveMotionGenerator__inherit__graph.map b/classfranka_1_1ActiveMotionGenerator__inherit__graph.map new file mode 100644 index 00000000..952cec4f --- /dev/null +++ b/classfranka_1_1ActiveMotionGenerator__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/classfranka_1_1ActiveMotionGenerator__inherit__graph.md5 b/classfranka_1_1ActiveMotionGenerator__inherit__graph.md5 new file mode 100644 index 00000000..291f0ddc --- /dev/null +++ b/classfranka_1_1ActiveMotionGenerator__inherit__graph.md5 @@ -0,0 +1 @@ +f15dced3563b4a11398c9b07dbca4622 \ No newline at end of file diff --git a/classfranka_1_1ActiveMotionGenerator__inherit__graph.png b/classfranka_1_1ActiveMotionGenerator__inherit__graph.png new file mode 100644 index 00000000..96f6fe08 Binary files /dev/null and b/classfranka_1_1ActiveMotionGenerator__inherit__graph.png differ diff --git a/classfranka_1_1ActiveTorqueControl-members.html b/classfranka_1_1ActiveTorqueControl-members.html new file mode 100644 index 00000000..65597c90 --- /dev/null +++ b/classfranka_1_1ActiveTorqueControl-members.html @@ -0,0 +1,111 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::ActiveTorqueControl Member List
+
+
+ +

This is the complete list of members for franka::ActiveTorqueControl, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + +
ActiveControl(std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock)franka::ActiveControlprotected
ActiveControlBase()=default (defined in franka::ActiveControlBase)franka::ActiveControlBaseprotected
control_finishedfranka::ActiveControlprotected
control_lockfranka::ActiveControlprotected
last_read_accessfranka::ActiveControlprotected
motion_idfranka::ActiveControlprotected
readOnce() overridefranka::ActiveControlvirtual
Robot classfranka::ActiveTorqueControlfriend
robot_implfranka::ActiveControlprotected
writeOnce(const Torques &control_input) overridefranka::ActiveTorqueControlvirtual
franka::ActiveControl::writeOnce(const JointPositions &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const JointVelocities &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const CartesianPose &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const CartesianVelocities &, const std::optional< const Torques > &) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const JointPositions &motion_generator_input) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const JointVelocities &motion_generator_input) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const CartesianPose &motion_generator_input) overridefranka::ActiveControlinlinevirtual
franka::ActiveControl::writeOnce(const CartesianVelocities &motion_generator_input) overridefranka::ActiveControlinlinevirtual
~ActiveControl() override (defined in franka::ActiveControl)franka::ActiveControl
~ActiveControlBase()=default (defined in franka::ActiveControlBase)franka::ActiveControlBasevirtual
+ + + + diff --git a/classfranka_1_1ActiveTorqueControl.html b/classfranka_1_1ActiveTorqueControl.html new file mode 100644 index 00000000..1d6ef5be --- /dev/null +++ b/classfranka_1_1ActiveTorqueControl.html @@ -0,0 +1,237 @@ + + + + + + + +libfranka: franka::ActiveTorqueControl Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Friends | +List of all members
+
+
franka::ActiveTorqueControl Class Reference
+
+
+ +

Allows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot. + More...

+ +

#include <active_torque_control.h>

+
+Inheritance diagram for franka::ActiveTorqueControl:
+
+
Inheritance graph
+ + + + + +
[legend]
+
+Collaboration diagram for franka::ActiveTorqueControl:
+
+
Collaboration graph
+ + + + + +
[legend]
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

void writeOnce (const Torques &control_input) override
 Updates the joint-level based torque commands of an active joint effort control. More...
 
- Public Member Functions inherited from franka::ActiveControl
std::pair< RobotState, DurationreadOnce () override
 Waits for a robot state update and returns it. More...
 
void writeOnce (const JointPositions &, const std::optional< const Torques > &) override
 Updates the joint position and torque commands of an active control. More...
 
void writeOnce (const JointVelocities &, const std::optional< const Torques > &) override
 Updates the joint velocity and torque commands of an active control. More...
 
void writeOnce (const CartesianPose &, const std::optional< const Torques > &) override
 Updates the cartesian position and torque commands of an active control. More...
 
void writeOnce (const CartesianVelocities &, const std::optional< const Torques > &) override
 Updates the cartesian velocity and torque commands of an active control. More...
 
void writeOnce (const JointPositions &motion_generator_input) override
 Updates the joint position commands of an active control, with internal controller. More...
 
void writeOnce (const JointVelocities &motion_generator_input) override
 Updates the joint velocity commands of an active control, with internal controller. More...
 
void writeOnce (const CartesianPose &motion_generator_input) override
 Updates the cartesian pose commands of an active control, with internal controller. More...
 
void writeOnce (const CartesianVelocities &motion_generator_input) override
 Updates the cartesian velocity commands of an active control, with internal controller. More...
 
+ + + + +

+Friends

+class Robot
 franka::Robot as friend to allow construction of ActiveTorqueControl in startTorqueControl methods
 
+ + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Protected Member Functions inherited from franka::ActiveControl
 ActiveControl (std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock)
 Construct a new ActiveControl object. More...
 
- Protected Attributes inherited from franka::ActiveControl
+std::shared_ptr< Robot::Impl > robot_impl
 shared pointer to Robot::Impl instance for read and write accesses
 
+uint32_t motion_id
 motion id of running motion
 
+std::unique_lock< std::mutex > control_lock
 control-lock preventing parallel control processes
 
+bool control_finished
 flag indicating if control process is finished
 
+std::optional< Durationlast_read_access
 duration to last read access
 
+

Detailed Description

+

Allows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot.

+

hint: To create an ActiveTorqueControl, see franka::Robot

+

Member Function Documentation

+ +

◆ writeOnce()

+ +
+
+ + + + + +
+ + + + + + + + +
void franka::ActiveTorqueControl::writeOnce (const Torquescontrol_input)
+
+overridevirtual
+
+ +

Updates the joint-level based torque commands of an active joint effort control.

+
Parameters
+ + +
control_inputthe new joint-level based torques
+
+
+
Exceptions
+ + + +
ControlExceptionif an error related to torque control or motion generation occurred, or the motion was already finished.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+ +

Reimplemented from franka::ActiveControl.

+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1ActiveTorqueControl__coll__graph.map b/classfranka_1_1ActiveTorqueControl__coll__graph.map new file mode 100644 index 00000000..c409c1e9 --- /dev/null +++ b/classfranka_1_1ActiveTorqueControl__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/classfranka_1_1ActiveTorqueControl__coll__graph.md5 b/classfranka_1_1ActiveTorqueControl__coll__graph.md5 new file mode 100644 index 00000000..e7810a63 --- /dev/null +++ b/classfranka_1_1ActiveTorqueControl__coll__graph.md5 @@ -0,0 +1 @@ +d5b6f841bc0f1b25e2f9a049ecced612 \ No newline at end of file diff --git a/classfranka_1_1ActiveTorqueControl__coll__graph.png b/classfranka_1_1ActiveTorqueControl__coll__graph.png new file mode 100644 index 00000000..4150b674 Binary files /dev/null and b/classfranka_1_1ActiveTorqueControl__coll__graph.png differ diff --git a/classfranka_1_1ActiveTorqueControl__inherit__graph.map b/classfranka_1_1ActiveTorqueControl__inherit__graph.map new file mode 100644 index 00000000..c409c1e9 --- /dev/null +++ b/classfranka_1_1ActiveTorqueControl__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/classfranka_1_1ActiveTorqueControl__inherit__graph.md5 b/classfranka_1_1ActiveTorqueControl__inherit__graph.md5 new file mode 100644 index 00000000..e7810a63 --- /dev/null +++ b/classfranka_1_1ActiveTorqueControl__inherit__graph.md5 @@ -0,0 +1 @@ +d5b6f841bc0f1b25e2f9a049ecced612 \ No newline at end of file diff --git a/classfranka_1_1ActiveTorqueControl__inherit__graph.png b/classfranka_1_1ActiveTorqueControl__inherit__graph.png new file mode 100644 index 00000000..4150b674 Binary files /dev/null and b/classfranka_1_1ActiveTorqueControl__inherit__graph.png differ diff --git a/classfranka_1_1CartesianPose-members.html b/classfranka_1_1CartesianPose-members.html new file mode 100644 index 00000000..72f03797 --- /dev/null +++ b/classfranka_1_1CartesianPose-members.html @@ -0,0 +1,99 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::CartesianPose Member List
+
+
+ +

This is the complete list of members for franka::CartesianPose, including all inherited members.

+ + + + + + + + + +
CartesianPose(const std::array< double, 16 > &cartesian_pose) noexceptfranka::CartesianPose
CartesianPose(const std::array< double, 16 > &cartesian_pose, const std::array< double, 2 > &elbow) noexceptfranka::CartesianPose
CartesianPose(std::initializer_list< double > cartesian_pose)franka::CartesianPose
CartesianPose(std::initializer_list< double > cartesian_pose, std::initializer_list< double > elbow)franka::CartesianPose
elbowfranka::CartesianPose
hasElbow() const noexceptfranka::CartesianPose
motion_finishedfranka::Finishable
O_T_EEfranka::CartesianPose
+ + + + diff --git a/classfranka_1_1CartesianPose.html b/classfranka_1_1CartesianPose.html new file mode 100644 index 00000000..96b2d33e --- /dev/null +++ b/classfranka_1_1CartesianPose.html @@ -0,0 +1,385 @@ + + + + + + + +libfranka: franka::CartesianPose Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
franka::CartesianPose Class Reference
+
+
+ +

Stores values for Cartesian pose motion generation. + More...

+ +

#include <control_types.h>

+
+Inheritance diagram for franka::CartesianPose:
+
+
Inheritance graph
+ + + + +
[legend]
+
+Collaboration diagram for franka::CartesianPose:
+
+
Collaboration graph
+ + + + +
[legend]
+ + + + + + + + + + + + + + + + + +

+Public Member Functions

 CartesianPose (const std::array< double, 16 > &cartesian_pose) noexcept
 Creates a new CartesianPose instance. More...
 
 CartesianPose (const std::array< double, 16 > &cartesian_pose, const std::array< double, 2 > &elbow) noexcept
 Creates a new CartesianPose instance. More...
 
 CartesianPose (std::initializer_list< double > cartesian_pose)
 Creates a new CartesianPose instance. More...
 
 CartesianPose (std::initializer_list< double > cartesian_pose, std::initializer_list< double > elbow)
 Creates a new CartesianPose instance. More...
 
bool hasElbow () const noexcept
 Determines whether there is a stored elbow configuration. More...
 
+ + + + + + + + + + + +

+Public Attributes

std::array< double, 16 > O_T_EE {}
 Homogeneous transformation \(^O{\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). More...
 
std::array< double, 2 > elbow {}
 Elbow configuration. More...
 
- Public Attributes inherited from franka::Finishable
+bool motion_finished = false
 Determines whether to finish a currently running motion.
 
+

Detailed Description

+

Stores values for Cartesian pose motion generation.

+
Examples
generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_elbow_motion.cpp, and joint_impedance_control.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ CartesianPose() [1/4]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::CartesianPose::CartesianPose (const std::array< double, 16 > & cartesian_pose)
+
+noexcept
+
+ +

Creates a new CartesianPose instance.

+
Parameters
+ + +
[in]cartesian_poseDesired vectorized homogeneous transformation matrix \(^O {\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). Equivalently, it is the desired end effector pose in base frame.
+
+
+ +
+
+ +

◆ CartesianPose() [2/4]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
franka::CartesianPose::CartesianPose (const std::array< double, 16 > & cartesian_pose,
const std::array< double, 2 > & elbow 
)
+
+noexcept
+
+ +

Creates a new CartesianPose instance.

+
Parameters
+ + + +
[in]cartesian_poseDesired vectorized homogeneous transformation matrix \(^O {\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). Equivalently, it is the desired end effector pose in base frame.
[in]elbowElbow configuration (see elbow member for more details).
+
+
+ +
+
+ +

◆ CartesianPose() [3/4]

+ +
+
+ + + + + + + + +
franka::CartesianPose::CartesianPose (std::initializer_list< double > cartesian_pose)
+
+ +

Creates a new CartesianPose instance.

+
Parameters
+ + +
[in]cartesian_poseDesired vectorized homogeneous transformation matrix \(^O {\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). Equivalently, it is the desired end effector pose in base frame.
+
+
+
Exceptions
+ + +
std::invalid_argumentif the given initializer list has an invalid number of arguments.
+
+
+ +
+
+ +

◆ CartesianPose() [4/4]

+ +
+
+ + + + + + + + + + + + + + + + + + +
franka::CartesianPose::CartesianPose (std::initializer_list< double > cartesian_pose,
std::initializer_list< double > elbow 
)
+
+ +

Creates a new CartesianPose instance.

+
Parameters
+ + + +
[in]cartesian_poseDesired vectorized homogeneous transformation matrix \(^O {\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). Equivalently, it is the desired end effector pose in base frame.
[in]elbowElbow configuration (see elbow member for more details).
+
+
+
Exceptions
+ + +
std::invalid_argumentif a given initializer list has an invalid number of arguments.
+
+
+ +
+
+

Member Function Documentation

+ +

◆ hasElbow()

+ +
+
+ + + + + +
+ + + + + + + +
bool franka::CartesianPose::hasElbow () const
+
+noexcept
+
+ +

Determines whether there is a stored elbow configuration.

+
Returns
True if there is a stored elbow configuration, false otherwise.
+ +
+
+

Member Data Documentation

+ +

◆ elbow

+ +
+
+ + + + +
std::array<double, 2> franka::CartesianPose::elbow {}
+
+ +

Elbow configuration.

+

The values of the array are:

    +
  • elbow[0]: Position of the 3rd joint in \([rad]\).
  • +
  • elbow[1]: Flip direction of the elbow (4th joint):
      +
    • +1 if \(q_4 > q_{elbow-flip}\)
    • +
    • 0 if \(q_4 == q_{elbow-flip} \)
    • +
    • -1 if \(q_4 < q_{elbow-flip} \)
    • +
    +
  • +
+

with \(q_{elbow-flip}\) as specified in the robot interface specification page in the FCI Documentation.

+ +
+
+ +

◆ O_T_EE

+ +
+
+ + + + +
std::array<double, 16> franka::CartesianPose::O_T_EE {}
+
+ +

Homogeneous transformation \(^O{\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\).

+

Equivalently, it is the desired end effector pose in base frame.

+
Examples
joint_impedance_control.cpp.
+
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1CartesianPose__coll__graph.map b/classfranka_1_1CartesianPose__coll__graph.map new file mode 100644 index 00000000..d0e17a63 --- /dev/null +++ b/classfranka_1_1CartesianPose__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1CartesianPose__coll__graph.md5 b/classfranka_1_1CartesianPose__coll__graph.md5 new file mode 100644 index 00000000..befdc6df --- /dev/null +++ b/classfranka_1_1CartesianPose__coll__graph.md5 @@ -0,0 +1 @@ +81c49068e9ce62a88cba1af25c92fd08 \ No newline at end of file diff --git a/classfranka_1_1CartesianPose__coll__graph.png b/classfranka_1_1CartesianPose__coll__graph.png new file mode 100644 index 00000000..486464cd Binary files /dev/null and b/classfranka_1_1CartesianPose__coll__graph.png differ diff --git a/classfranka_1_1CartesianPose__inherit__graph.map b/classfranka_1_1CartesianPose__inherit__graph.map new file mode 100644 index 00000000..d0e17a63 --- /dev/null +++ b/classfranka_1_1CartesianPose__inherit__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1CartesianPose__inherit__graph.md5 b/classfranka_1_1CartesianPose__inherit__graph.md5 new file mode 100644 index 00000000..befdc6df --- /dev/null +++ b/classfranka_1_1CartesianPose__inherit__graph.md5 @@ -0,0 +1 @@ +81c49068e9ce62a88cba1af25c92fd08 \ No newline at end of file diff --git a/classfranka_1_1CartesianPose__inherit__graph.png b/classfranka_1_1CartesianPose__inherit__graph.png new file mode 100644 index 00000000..486464cd Binary files /dev/null and b/classfranka_1_1CartesianPose__inherit__graph.png differ diff --git a/classfranka_1_1CartesianVelocities-members.html b/classfranka_1_1CartesianVelocities-members.html new file mode 100644 index 00000000..f7e39969 --- /dev/null +++ b/classfranka_1_1CartesianVelocities-members.html @@ -0,0 +1,99 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::CartesianVelocities Member List
+
+
+ +

This is the complete list of members for franka::CartesianVelocities, including all inherited members.

+ + + + + + + + + +
CartesianVelocities(const std::array< double, 6 > &cartesian_velocities) noexceptfranka::CartesianVelocities
CartesianVelocities(const std::array< double, 6 > &cartesian_velocities, const std::array< double, 2 > &elbow) noexceptfranka::CartesianVelocities
CartesianVelocities(std::initializer_list< double > cartesian_velocities)franka::CartesianVelocities
CartesianVelocities(std::initializer_list< double > cartesian_velocities, std::initializer_list< double > elbow)franka::CartesianVelocities
elbowfranka::CartesianVelocities
hasElbow() const noexceptfranka::CartesianVelocities
motion_finishedfranka::Finishable
O_dP_EEfranka::CartesianVelocities
+ + + + diff --git a/classfranka_1_1CartesianVelocities.html b/classfranka_1_1CartesianVelocities.html new file mode 100644 index 00000000..46a11b8c --- /dev/null +++ b/classfranka_1_1CartesianVelocities.html @@ -0,0 +1,368 @@ + + + + + + + +libfranka: franka::CartesianVelocities Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
franka::CartesianVelocities Class Reference
+
+
+ +

Stores values for Cartesian velocity motion generation. + More...

+ +

#include <control_types.h>

+
+Inheritance diagram for franka::CartesianVelocities:
+
+
Inheritance graph
+ + + + +
[legend]
+
+Collaboration diagram for franka::CartesianVelocities:
+
+
Collaboration graph
+ + + + +
[legend]
+ + + + + + + + + + + + + + + + + +

+Public Member Functions

 CartesianVelocities (const std::array< double, 6 > &cartesian_velocities) noexcept
 Creates a new CartesianVelocities instance. More...
 
 CartesianVelocities (const std::array< double, 6 > &cartesian_velocities, const std::array< double, 2 > &elbow) noexcept
 Creates a new CartesianVelocities instance. More...
 
 CartesianVelocities (std::initializer_list< double > cartesian_velocities)
 Creates a new CartesianVelocities instance. More...
 
 CartesianVelocities (std::initializer_list< double > cartesian_velocities, std::initializer_list< double > elbow)
 Creates a new CartesianVelocities instance. More...
 
bool hasElbow () const noexcept
 Determines whether there is a stored elbow configuration. More...
 
+ + + + + + + + + + + +

+Public Attributes

+std::array< double, 6 > O_dP_EE {}
 Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\).
 
std::array< double, 2 > elbow {}
 Elbow configuration. More...
 
- Public Attributes inherited from franka::Finishable
+bool motion_finished = false
 Determines whether to finish a currently running motion.
 
+

Detailed Description

+

Stores values for Cartesian velocity motion generation.

+

The Cartesian velocity of the end-effector is expressed in a frame parallel to the fixed/base frame, whose origin is the same as the end-effector frame. Rotations are thus expressed around the end-effector and parallel to the base frame.

+
Examples
generate_cartesian_velocity_motion.cpp, and generate_cartesian_velocity_motion_external_control_loop.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ CartesianVelocities() [1/4]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::CartesianVelocities::CartesianVelocities (const std::array< double, 6 > & cartesian_velocities)
+
+noexcept
+
+ +

Creates a new CartesianVelocities instance.

+
Parameters
+ + +
[in]cartesian_velocitiesDesired Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\).
+
+
+ +
+
+ +

◆ CartesianVelocities() [2/4]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
franka::CartesianVelocities::CartesianVelocities (const std::array< double, 6 > & cartesian_velocities,
const std::array< double, 2 > & elbow 
)
+
+noexcept
+
+ +

Creates a new CartesianVelocities instance.

+
Parameters
+ + + +
[in]cartesian_velocitiesDesired Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\).
[in]elbowElbow configuration (see elbow member for more details).
+
+
+ +
+
+ +

◆ CartesianVelocities() [3/4]

+ +
+
+ + + + + + + + +
franka::CartesianVelocities::CartesianVelocities (std::initializer_list< double > cartesian_velocities)
+
+ +

Creates a new CartesianVelocities instance.

+
Parameters
+ + +
[in]cartesian_velocitiesDesired Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\).
+
+
+
Exceptions
+ + +
std::invalid_argumentif the given initializer list has an invalid number of arguments.
+
+
+ +
+
+ +

◆ CartesianVelocities() [4/4]

+ +
+
+ + + + + + + + + + + + + + + + + + +
franka::CartesianVelocities::CartesianVelocities (std::initializer_list< double > cartesian_velocities,
std::initializer_list< double > elbow 
)
+
+ +

Creates a new CartesianVelocities instance.

+
Parameters
+ + + +
[in]cartesian_velocitiesDesired Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\).
[in]elbowElbow configuration (see elbow member for more details).
+
+
+
Exceptions
+ + +
std::invalid_argumentif a given initializer list has an invalid number of arguments.
+
+
+ +
+
+

Member Function Documentation

+ +

◆ hasElbow()

+ +
+
+ + + + + +
+ + + + + + + +
bool franka::CartesianVelocities::hasElbow () const
+
+noexcept
+
+ +

Determines whether there is a stored elbow configuration.

+
Returns
True if there is a stored elbow configuration, false otherwise.
+ +
+
+

Member Data Documentation

+ +

◆ elbow

+ +
+
+ + + + +
std::array<double, 2> franka::CartesianVelocities::elbow {}
+
+ +

Elbow configuration.

+

The values of the array are:

    +
  • elbow[0]: Position of the 3rd joint in \([rad]\).
  • +
  • elbow[1]: Flip direction of the elbow (4th joint):
      +
    • +1 if \(q_4 > \alpha\)
    • +
    • 0 if \(q_4 == \alpha \)
    • +
    • -1 if \(q_4 < \alpha \)
    • +
    +
  • +
+

with \(\alpha = -0.467002423653011\) \(rad\)

+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1CartesianVelocities__coll__graph.map b/classfranka_1_1CartesianVelocities__coll__graph.map new file mode 100644 index 00000000..2a929887 --- /dev/null +++ b/classfranka_1_1CartesianVelocities__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1CartesianVelocities__coll__graph.md5 b/classfranka_1_1CartesianVelocities__coll__graph.md5 new file mode 100644 index 00000000..5ce9c197 --- /dev/null +++ b/classfranka_1_1CartesianVelocities__coll__graph.md5 @@ -0,0 +1 @@ +32bed61017a88b35679a2bc229a0ebf7 \ No newline at end of file diff --git a/classfranka_1_1CartesianVelocities__coll__graph.png b/classfranka_1_1CartesianVelocities__coll__graph.png new file mode 100644 index 00000000..2c627a59 Binary files /dev/null and b/classfranka_1_1CartesianVelocities__coll__graph.png differ diff --git a/classfranka_1_1CartesianVelocities__inherit__graph.map b/classfranka_1_1CartesianVelocities__inherit__graph.map new file mode 100644 index 00000000..2a929887 --- /dev/null +++ b/classfranka_1_1CartesianVelocities__inherit__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1CartesianVelocities__inherit__graph.md5 b/classfranka_1_1CartesianVelocities__inherit__graph.md5 new file mode 100644 index 00000000..5ce9c197 --- /dev/null +++ b/classfranka_1_1CartesianVelocities__inherit__graph.md5 @@ -0,0 +1 @@ +32bed61017a88b35679a2bc229a0ebf7 \ No newline at end of file diff --git a/classfranka_1_1CartesianVelocities__inherit__graph.png b/classfranka_1_1CartesianVelocities__inherit__graph.png new file mode 100644 index 00000000..2c627a59 Binary files /dev/null and b/classfranka_1_1CartesianVelocities__inherit__graph.png differ diff --git a/classfranka_1_1Duration-members.html b/classfranka_1_1Duration-members.html new file mode 100644 index 00000000..8d5d5610 --- /dev/null +++ b/classfranka_1_1Duration-members.html @@ -0,0 +1,118 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::Duration Member List
+
+
+ +

This is the complete list of members for franka::Duration, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Duration() noexceptfranka::Duration
Duration(uint64_t milliseconds) noexceptfranka::Durationexplicit
Duration(std::chrono::duration< uint64_t, std::milli > duration) noexceptfranka::Duration
Duration(const Duration &)=defaultfranka::Duration
operator std::chrono::duration< uint64_t, std::milli >() const noexceptfranka::Duration
operator!=(const Duration &rhs) const noexceptfranka::Duration
operator%(const Duration &rhs) const noexceptfranka::Duration
operator%(uint64_t rhs) const noexceptfranka::Duration
operator%=(const Duration &rhs) noexceptfranka::Duration
operator%=(uint64_t rhs) noexceptfranka::Duration
operator*(uint64_t rhs) const noexceptfranka::Duration
operator*=(uint64_t rhs) noexceptfranka::Duration
operator+(const Duration &rhs) const noexceptfranka::Duration
operator+=(const Duration &rhs) noexceptfranka::Duration
operator-(const Duration &rhs) const noexceptfranka::Duration
operator-=(const Duration &rhs) noexceptfranka::Duration
operator/(const Duration &rhs) const noexceptfranka::Duration
operator/(uint64_t rhs) const noexceptfranka::Duration
operator/=(uint64_t rhs) noexceptfranka::Duration
operator<(const Duration &rhs) const noexceptfranka::Duration
operator<=(const Duration &rhs) const noexceptfranka::Duration
operator=(const Duration &)=defaultfranka::Duration
operator==(const Duration &rhs) const noexceptfranka::Duration
operator>(const Duration &rhs) const noexceptfranka::Duration
operator>=(const Duration &rhs) const noexceptfranka::Duration
toMSec() const noexceptfranka::Duration
toSec() const noexceptfranka::Duration
+ + + + diff --git a/classfranka_1_1Duration.html b/classfranka_1_1Duration.html new file mode 100644 index 00000000..8854b2c4 --- /dev/null +++ b/classfranka_1_1Duration.html @@ -0,0 +1,1044 @@ + + + + + + + +libfranka: franka::Duration Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +List of all members
+
+
franka::Duration Class Reference
+
+
+ +

Represents a duration with millisecond resolution. + More...

+ +

#include <duration.h>

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

Duration () noexcept
 Creates a new Duration instance with zero milliseconds.
 
 Duration (uint64_t milliseconds) noexcept
 Creates a new Duration instance from the given number of milliseconds. More...
 
 Duration (std::chrono::duration< uint64_t, std::milli > duration) noexcept
 Creates a new Duration instance from an std::chrono::duration. More...
 
Duration (const Duration &)=default
 Creates a copy of a Duration instance.
 
Durationoperator= (const Duration &)=default
 Assigns the contents of one Duration to another. More...
 
 operator std::chrono::duration< uint64_t, std::milli > () const noexcept
 Returns the stored duration as an std::chrono::duration. More...
 
double toSec () const noexcept
 Returns the stored duration in \([s]\). More...
 
uint64_t toMSec () const noexcept
 Returns the stored duration in \([ms]\). More...
 
Arithmetic operators
Duration operator+ (const Duration &rhs) const noexcept
 Performs addition. More...
 
Durationoperator+= (const Duration &rhs) noexcept
 Performs addition. More...
 
Duration operator- (const Duration &rhs) const noexcept
 Performs subtraction. More...
 
Durationoperator-= (const Duration &rhs) noexcept
 Performs subtraction. More...
 
Duration operator* (uint64_t rhs) const noexcept
 Performs multiplication. More...
 
Durationoperator*= (uint64_t rhs) noexcept
 Performs multiplication. More...
 
uint64_t operator/ (const Duration &rhs) const noexcept
 Performs division. More...
 
Duration operator/ (uint64_t rhs) const noexcept
 Performs division. More...
 
Durationoperator/= (uint64_t rhs) noexcept
 Performs division. More...
 
Duration operator% (const Duration &rhs) const noexcept
 Performs the modulo operation. More...
 
Duration operator% (uint64_t rhs) const noexcept
 Performs the modulo operation. More...
 
Durationoperator%= (const Duration &rhs) noexcept
 Performs the modulo operation. More...
 
Durationoperator%= (uint64_t rhs) noexcept
 Performs the modulo operation. More...
 
Comparison operators
bool operator== (const Duration &rhs) const noexcept
 Compares two durations for equality. More...
 
bool operator!= (const Duration &rhs) const noexcept
 Compares two durations for inequality. More...
 
bool operator< (const Duration &rhs) const noexcept
 Compares two durations. More...
 
bool operator<= (const Duration &rhs) const noexcept
 Compares two durations. More...
 
bool operator> (const Duration &rhs) const noexcept
 Compares two durations. More...
 
bool operator>= (const Duration &rhs) const noexcept
 Compares two durations. More...
 
+

Detailed Description

+

Represents a duration with millisecond resolution.

+
Examples
cartesian_impedance_control.cpp, communication_test.cpp, force_control.cpp, generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_cartesian_velocity_motion.cpp, generate_cartesian_velocity_motion_external_control_loop.cpp, generate_consecutive_motions.cpp, generate_elbow_motion.cpp, generate_joint_position_motion.cpp, generate_joint_position_motion_external_control_loop.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, joint_impedance_control.cpp, motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ Duration() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::Duration::Duration (uint64_t milliseconds)
+
+explicitnoexcept
+
+ +

Creates a new Duration instance from the given number of milliseconds.

+
Parameters
+ + +
[in]millisecondsNumber of milliseconds.
+
+
+ +
+
+ +

◆ Duration() [2/2]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::Duration::Duration (std::chrono::duration< uint64_t, std::milli > duration)
+
+noexcept
+
+ +

Creates a new Duration instance from an std::chrono::duration.

+
Parameters
+ + +
[in]durationDuration.
+
+
+ +
+
+

Member Function Documentation

+ +

◆ operator std::chrono::duration< uint64_t, std::milli >()

+ +
+
+ + + + + +
+ + + + + + + +
franka::Duration::operator std::chrono::duration< uint64_t, std::milli > () const
+
+noexcept
+
+ +

Returns the stored duration as an std::chrono::duration.

+
Returns
Duration as std::chrono::duration.
+ +
+
+ +

◆ operator!=()

+ +
+
+ + + + + +
+ + + + + + + + +
bool franka::Duration::operator!= (const Durationrhs) const
+
+noexcept
+
+ +

Compares two durations for inequality.

+
Parameters
+ + +
[in]rhsRight-hand side of the comparison.
+
+
+
Returns
True if the duration are not equal, false otherwise.
+ +
+
+ +

◆ operator%() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
Duration franka::Duration::operator% (const Durationrhs) const
+
+noexcept
+
+ +

Performs the modulo operation.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
Result of the operation.
+ +
+
+ +

◆ operator%() [2/2]

+ +
+
+ + + + + +
+ + + + + + + + +
Duration franka::Duration::operator% (uint64_t rhs) const
+
+noexcept
+
+ +

Performs the modulo operation.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
Result of the operation.
+ +
+
+ +

◆ operator%=() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
Duration& franka::Duration::operator%= (const Durationrhs)
+
+noexcept
+
+ +

Performs the modulo operation.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
This duration.
+ +
+
+ +

◆ operator%=() [2/2]

+ +
+
+ + + + + +
+ + + + + + + + +
Duration& franka::Duration::operator%= (uint64_t rhs)
+
+noexcept
+
+ +

Performs the modulo operation.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
This duration.
+ +
+
+ +

◆ operator*()

+ +
+
+ + + + + +
+ + + + + + + + +
Duration franka::Duration::operator* (uint64_t rhs) const
+
+noexcept
+
+ +

Performs multiplication.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
Result of the operation.
+ +
+
+ +

◆ operator*=()

+ +
+
+ + + + + +
+ + + + + + + + +
Duration& franka::Duration::operator*= (uint64_t rhs)
+
+noexcept
+
+ +

Performs multiplication.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
This duration.
+ +
+
+ +

◆ operator+()

+ +
+
+ + + + + +
+ + + + + + + + +
Duration franka::Duration::operator+ (const Durationrhs) const
+
+noexcept
+
+ +

Performs addition.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
Result of the operation.
+ +
+
+ +

◆ operator+=()

+ +
+
+ + + + + +
+ + + + + + + + +
Duration& franka::Duration::operator+= (const Durationrhs)
+
+noexcept
+
+ +

Performs addition.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
This duration.
+ +
+
+ +

◆ operator-()

+ +
+
+ + + + + +
+ + + + + + + + +
Duration franka::Duration::operator- (const Durationrhs) const
+
+noexcept
+
+ +

Performs subtraction.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
Result of the operation.
+ +
+
+ +

◆ operator-=()

+ +
+
+ + + + + +
+ + + + + + + + +
Duration& franka::Duration::operator-= (const Durationrhs)
+
+noexcept
+
+ +

Performs subtraction.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
This duration.
+ +
+
+ +

◆ operator/() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
uint64_t franka::Duration::operator/ (const Durationrhs) const
+
+noexcept
+
+ +

Performs division.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
Result of the operation.
+ +
+
+ +

◆ operator/() [2/2]

+ +
+
+ + + + + +
+ + + + + + + + +
Duration franka::Duration::operator/ (uint64_t rhs) const
+
+noexcept
+
+ +

Performs division.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
Result of the operation.
+ +
+
+ +

◆ operator/=()

+ +
+
+ + + + + +
+ + + + + + + + +
Duration& franka::Duration::operator/= (uint64_t rhs)
+
+noexcept
+
+ +

Performs division.

+
Parameters
+ + +
[in]rhsRight-hand side of the operation.
+
+
+
Returns
This duration.
+ +
+
+ +

◆ operator<()

+ +
+
+ + + + + +
+ + + + + + + + +
bool franka::Duration::operator< (const Durationrhs) const
+
+noexcept
+
+ +

Compares two durations.

+
Parameters
+ + +
[in]rhsRight-hand side of the comparison.
+
+
+
Returns
True if this duration is shorter than rhs, false otherwise.
+ +
+
+ +

◆ operator<=()

+ +
+
+ + + + + +
+ + + + + + + + +
bool franka::Duration::operator<= (const Durationrhs) const
+
+noexcept
+
+ +

Compares two durations.

+
Parameters
+ + +
[in]rhsRight-hand side of the comparison.
+
+
+
Returns
True if this duration is shorter than or equal to rhs, false otherwise.
+ +
+
+ +

◆ operator=()

+ +
+
+ + + + + +
+ + + + + + + + +
Duration& franka::Duration::operator= (const Duration)
+
+default
+
+ +

Assigns the contents of one Duration to another.

+
Returns
Result of the operation.
+ +
+
+ +

◆ operator==()

+ +
+
+ + + + + +
+ + + + + + + + +
bool franka::Duration::operator== (const Durationrhs) const
+
+noexcept
+
+ +

Compares two durations for equality.

+
Parameters
+ + +
[in]rhsRight-hand side of the comparison.
+
+
+
Returns
True if the duration are equal, false otherwise.
+ +
+
+ +

◆ operator>()

+ +
+
+ + + + + +
+ + + + + + + + +
bool franka::Duration::operator> (const Durationrhs) const
+
+noexcept
+
+ +

Compares two durations.

+
Parameters
+ + +
[in]rhsRight-hand side of the comparison.
+
+
+
Returns
True if this duration is longer than rhs, false otherwise.
+ +
+
+ +

◆ operator>=()

+ +
+
+ + + + + +
+ + + + + + + + +
bool franka::Duration::operator>= (const Durationrhs) const
+
+noexcept
+
+ +

Compares two durations.

+
Parameters
+ + +
[in]rhsRight-hand side of the comparison.
+
+
+
Returns
True if this duration is longer than or equal to rhs, false otherwise.
+ +
+
+ +

◆ toMSec()

+ +
+
+ + + + + +
+ + + + + + + +
uint64_t franka::Duration::toMSec () const
+
+noexcept
+
+ +

Returns the stored duration in \([ms]\).

+
Returns
Duration in \([ms]\).
+
Examples
communication_test.cpp.
+
+ +
+
+ +

◆ toSec()

+ +
+
+ + + + + +
+ + + + + + + +
double franka::Duration::toSec () const
+
+noexcept
+
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1Gripper-members.html b/classfranka_1_1Gripper-members.html new file mode 100644 index 00000000..faad367a --- /dev/null +++ b/classfranka_1_1Gripper-members.html @@ -0,0 +1,102 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::Gripper Member List
+
+
+ +

This is the complete list of members for franka::Gripper, including all inherited members.

+ + + + + + + + + + + + +
grasp(double width, double speed, double force, double epsilon_inner=0.005, double epsilon_outer=0.005) constfranka::Gripper
Gripper(const std::string &franka_address)franka::Gripperexplicit
Gripper(Gripper &&gripper) noexceptfranka::Gripper
homing() constfranka::Gripper
move(double width, double speed) constfranka::Gripper
operator=(Gripper &&gripper) noexceptfranka::Gripper
readOnce() constfranka::Gripper
ServerVersion typedeffranka::Gripper
serverVersion() const noexceptfranka::Gripper
stop() constfranka::Gripper
~Gripper() noexceptfranka::Gripper
+ + + + diff --git a/classfranka_1_1Gripper.html b/classfranka_1_1Gripper.html new file mode 100644 index 00000000..eb0a9037 --- /dev/null +++ b/classfranka_1_1Gripper.html @@ -0,0 +1,490 @@ + + + + + + + +libfranka: franka::Gripper Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Types | +Public Member Functions | +List of all members
+
+
franka::Gripper Class Reference
+
+
+ +

Maintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands. + More...

+ +

#include <gripper.h>

+ + + + + +

+Public Types

+using ServerVersion = uint16_t
 Version of the gripper server.
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 Gripper (const std::string &franka_address)
 Establishes a connection with a gripper connected to a robot. More...
 
 Gripper (Gripper &&gripper) noexcept
 Move-constructs a new Gripper instance. More...
 
Gripperoperator= (Gripper &&gripper) noexcept
 Move-assigns this Gripper from another Gripper instance. More...
 
~Gripper () noexcept
 Closes the connection.
 
bool homing () const
 Performs homing of the gripper. More...
 
bool grasp (double width, double speed, double force, double epsilon_inner=0.005, double epsilon_outer=0.005) const
 Grasps an object. More...
 
bool move (double width, double speed) const
 Moves the gripper fingers to a specified width. More...
 
bool stop () const
 Stops a currently running gripper move or grasp. More...
 
GripperState readOnce () const
 Waits for a gripper state update and returns it. More...
 
ServerVersion serverVersion () const noexcept
 Returns the software version reported by the connected server. More...
 
+

Detailed Description

+

Maintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands.

+
Note
The members of this class are threadsafe.
+
Examples
grasp_object.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ Gripper() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::Gripper::Gripper (const std::string & franka_address)
+
+explicit
+
+ +

Establishes a connection with a gripper connected to a robot.

+
Parameters
+ + +
[in]franka_addressIP/hostname of the robot the gripper is connected to.
+
+
+
Exceptions
+ + + +
NetworkExceptionif the connection is unsuccessful.
IncompatibleVersionExceptionif this version of libfranka is not supported.
+
+
+ +
+
+ +

◆ Gripper() [2/2]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::Gripper::Gripper (Gripper && gripper)
+
+noexcept
+
+ +

Move-constructs a new Gripper instance.

+
Parameters
+ + +
[in]gripperOther Gripper instance.
+
+
+ +
+
+

Member Function Documentation

+ +

◆ grasp()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
bool franka::Gripper::grasp (double width,
double speed,
double force,
double epsilon_inner = 0.005,
double epsilon_outer = 0.005 
) const
+
+ +

Grasps an object.

+

An object is considered grasped if the distance \(d\) between the gripper fingers satisfies \((\text{width} - \text{epsilon_inner}) < d < (\text{width} + \text{epsilon_outer})\).

+
Parameters
+ + + + + + +
[in]widthSize of the object to grasp in \([m]\).
[in]speedClosing speed in \([\frac{m}{s}]\).
[in]forceGrasping force in \([N]\).
[in]epsilon_innerMaximum tolerated deviation when the actual grasped width is smaller than the commanded grasp width.
[in]epsilon_outerMaximum tolerated deviation when the actual grasped width is larger than the commanded grasp width.
+
+
+
Returns
True if an object has been grasped, false otherwise.
+
Exceptions
+ + + +
CommandExceptionif an error occurred.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Examples
grasp_object.cpp.
+
+ +
+
+ +

◆ homing()

+ +
+
+ + + + + + + +
bool franka::Gripper::homing () const
+
+ +

Performs homing of the gripper.

+

After changing the gripper fingers, a homing needs to be done. This is needed to estimate the maximum grasping width.

+
Returns
True if command was successful, false otherwise.
+
Exceptions
+ + + +
CommandExceptionif an error occurred.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
See also
GripperState for the maximum grasping width.
+
Examples
grasp_object.cpp.
+
+ +
+
+ +

◆ move()

+ +
+
+ + + + + + + + + + + + + + + + + + +
bool franka::Gripper::move (double width,
double speed 
) const
+
+ +

Moves the gripper fingers to a specified width.

+
Parameters
+ + + +
[in]widthIntended opening width in \([m]\).
[in]speedClosing speed in \([\frac{m}{s}]\).
+
+
+
Returns
True if command was successful, false otherwise.
+
Exceptions
+ + + +
CommandExceptionif an error occurred.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+ +
+
+ +

◆ operator=()

+ +
+
+ + + + + +
+ + + + + + + + +
Gripper& franka::Gripper::operator= (Gripper && gripper)
+
+noexcept
+
+ +

Move-assigns this Gripper from another Gripper instance.

+
Parameters
+ + +
[in]gripperOther Gripper instance.
+
+
+
Returns
Model instance.
+ +
+
+ +

◆ readOnce()

+ +
+
+ + + + + + + +
GripperState franka::Gripper::readOnce () const
+
+ +

Waits for a gripper state update and returns it.

+
Returns
Current gripper state.
+
Exceptions
+ + + +
NetworkExceptionif the connection is lost, e.g. after a timeout.
InvalidOperationExceptionif another readOnce is already running.
+
+
+
Examples
grasp_object.cpp.
+
+ +
+
+ +

◆ serverVersion()

+ +
+
+ + + + + +
+ + + + + + + +
ServerVersion franka::Gripper::serverVersion () const
+
+noexcept
+
+ +

Returns the software version reported by the connected server.

+
Returns
Software version of the connected server.
+ +
+
+ +

◆ stop()

+ +
+
+ + + + + + + +
bool franka::Gripper::stop () const
+
+ +

Stops a currently running gripper move or grasp.

+
Returns
True if command was successful, false otherwise.
+
Exceptions
+ + + +
CommandExceptionif an error occurred.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Examples
grasp_object.cpp.
+
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1JointPositions-members.html b/classfranka_1_1JointPositions-members.html new file mode 100644 index 00000000..9481ab56 --- /dev/null +++ b/classfranka_1_1JointPositions-members.html @@ -0,0 +1,95 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::JointPositions Member List
+
+
+ +

This is the complete list of members for franka::JointPositions, including all inherited members.

+ + + + + +
JointPositions(const std::array< double, 7 > &joint_positions) noexceptfranka::JointPositions
JointPositions(std::initializer_list< double > joint_positions)franka::JointPositions
motion_finishedfranka::Finishable
qfranka::JointPositions
+ + + + diff --git a/classfranka_1_1JointPositions.html b/classfranka_1_1JointPositions.html new file mode 100644 index 00000000..5006a1f3 --- /dev/null +++ b/classfranka_1_1JointPositions.html @@ -0,0 +1,211 @@ + + + + + + + +libfranka: franka::JointPositions Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
franka::JointPositions Class Reference
+
+
+ +

Stores values for joint position motion generation. + More...

+ +

#include <control_types.h>

+
+Inheritance diagram for franka::JointPositions:
+
+
Inheritance graph
+ + + + +
[legend]
+
+Collaboration diagram for franka::JointPositions:
+
+
Collaboration graph
+ + + + +
[legend]
+ + + + + + + + +

+Public Member Functions

 JointPositions (const std::array< double, 7 > &joint_positions) noexcept
 Creates a new JointPositions instance. More...
 
 JointPositions (std::initializer_list< double > joint_positions)
 Creates a new JointPositions instance. More...
 
+ + + + + + + + +

+Public Attributes

+std::array< double, 7 > q {}
 Desired joint angles in [rad].
 
- Public Attributes inherited from franka::Finishable
+bool motion_finished = false
 Determines whether to finish a currently running motion.
 
+

Detailed Description

+

Stores values for joint position motion generation.

+
Examples
generate_joint_position_motion.cpp, and generate_joint_position_motion_external_control_loop.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ JointPositions() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::JointPositions::JointPositions (const std::array< double, 7 > & joint_positions)
+
+noexcept
+
+ +

Creates a new JointPositions instance.

+
Parameters
+ + +
[in]joint_positionsDesired joint angles in \([rad]\).
+
+
+ +
+
+ +

◆ JointPositions() [2/2]

+ +
+
+ + + + + + + + +
franka::JointPositions::JointPositions (std::initializer_list< double > joint_positions)
+
+ +

Creates a new JointPositions instance.

+
Parameters
+ + +
[in]joint_positionsDesired joint angles in \([rad]\).
+
+
+
Exceptions
+ + +
std::invalid_argumentif the given initializer list has an invalid number of arguments.
+
+
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1JointPositions__coll__graph.map b/classfranka_1_1JointPositions__coll__graph.map new file mode 100644 index 00000000..262848ce --- /dev/null +++ b/classfranka_1_1JointPositions__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1JointPositions__coll__graph.md5 b/classfranka_1_1JointPositions__coll__graph.md5 new file mode 100644 index 00000000..9cca88b9 --- /dev/null +++ b/classfranka_1_1JointPositions__coll__graph.md5 @@ -0,0 +1 @@ +c5f3272f047935d0f40484fdb8d71742 \ No newline at end of file diff --git a/classfranka_1_1JointPositions__coll__graph.png b/classfranka_1_1JointPositions__coll__graph.png new file mode 100644 index 00000000..081de5b8 Binary files /dev/null and b/classfranka_1_1JointPositions__coll__graph.png differ diff --git a/classfranka_1_1JointPositions__inherit__graph.map b/classfranka_1_1JointPositions__inherit__graph.map new file mode 100644 index 00000000..262848ce --- /dev/null +++ b/classfranka_1_1JointPositions__inherit__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1JointPositions__inherit__graph.md5 b/classfranka_1_1JointPositions__inherit__graph.md5 new file mode 100644 index 00000000..9cca88b9 --- /dev/null +++ b/classfranka_1_1JointPositions__inherit__graph.md5 @@ -0,0 +1 @@ +c5f3272f047935d0f40484fdb8d71742 \ No newline at end of file diff --git a/classfranka_1_1JointPositions__inherit__graph.png b/classfranka_1_1JointPositions__inherit__graph.png new file mode 100644 index 00000000..081de5b8 Binary files /dev/null and b/classfranka_1_1JointPositions__inherit__graph.png differ diff --git a/classfranka_1_1JointVelocities-members.html b/classfranka_1_1JointVelocities-members.html new file mode 100644 index 00000000..bd60ddb5 --- /dev/null +++ b/classfranka_1_1JointVelocities-members.html @@ -0,0 +1,95 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::JointVelocities Member List
+
+
+ +

This is the complete list of members for franka::JointVelocities, including all inherited members.

+ + + + + +
dqfranka::JointVelocities
JointVelocities(const std::array< double, 7 > &joint_velocities) noexceptfranka::JointVelocities
JointVelocities(std::initializer_list< double > joint_velocities)franka::JointVelocities
motion_finishedfranka::Finishable
+ + + + diff --git a/classfranka_1_1JointVelocities.html b/classfranka_1_1JointVelocities.html new file mode 100644 index 00000000..0aa52fce --- /dev/null +++ b/classfranka_1_1JointVelocities.html @@ -0,0 +1,211 @@ + + + + + + + +libfranka: franka::JointVelocities Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
franka::JointVelocities Class Reference
+
+
+ +

Stores values for joint velocity motion generation. + More...

+ +

#include <control_types.h>

+
+Inheritance diagram for franka::JointVelocities:
+
+
Inheritance graph
+ + + + +
[legend]
+
+Collaboration diagram for franka::JointVelocities:
+
+
Collaboration graph
+ + + + +
[legend]
+ + + + + + + + +

+Public Member Functions

 JointVelocities (const std::array< double, 7 > &joint_velocities) noexcept
 Creates a new JointVelocities instance. More...
 
 JointVelocities (std::initializer_list< double > joint_velocities)
 Creates a new JointVelocities instance. More...
 
+ + + + + + + + +

+Public Attributes

+std::array< double, 7 > dq {}
 Desired joint velocities in \([\frac{rad}{s}]\).
 
- Public Attributes inherited from franka::Finishable
+bool motion_finished = false
 Determines whether to finish a currently running motion.
 
+

Detailed Description

+

Stores values for joint velocity motion generation.

+
Examples
generate_consecutive_motions.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ JointVelocities() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::JointVelocities::JointVelocities (const std::array< double, 7 > & joint_velocities)
+
+noexcept
+
+ +

Creates a new JointVelocities instance.

+
Parameters
+ + +
[in]joint_velocitiesDesired joint velocities in \([\frac{rad}{s}]\).
+
+
+ +
+
+ +

◆ JointVelocities() [2/2]

+ +
+
+ + + + + + + + +
franka::JointVelocities::JointVelocities (std::initializer_list< double > joint_velocities)
+
+ +

Creates a new JointVelocities instance.

+
Parameters
+ + +
[in]joint_velocitiesDesired joint velocities in \([\frac{rad}{s}]\).
+
+
+
Exceptions
+ + +
std::invalid_argumentif the given initializer list has an invalid number of arguments.
+
+
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1JointVelocities__coll__graph.map b/classfranka_1_1JointVelocities__coll__graph.map new file mode 100644 index 00000000..a8a2195a --- /dev/null +++ b/classfranka_1_1JointVelocities__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1JointVelocities__coll__graph.md5 b/classfranka_1_1JointVelocities__coll__graph.md5 new file mode 100644 index 00000000..dad6b14e --- /dev/null +++ b/classfranka_1_1JointVelocities__coll__graph.md5 @@ -0,0 +1 @@ +94bb303f7a32ad60e8c00cad1f7d60a0 \ No newline at end of file diff --git a/classfranka_1_1JointVelocities__coll__graph.png b/classfranka_1_1JointVelocities__coll__graph.png new file mode 100644 index 00000000..b3bab018 Binary files /dev/null and b/classfranka_1_1JointVelocities__coll__graph.png differ diff --git a/classfranka_1_1JointVelocities__inherit__graph.map b/classfranka_1_1JointVelocities__inherit__graph.map new file mode 100644 index 00000000..a8a2195a --- /dev/null +++ b/classfranka_1_1JointVelocities__inherit__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1JointVelocities__inherit__graph.md5 b/classfranka_1_1JointVelocities__inherit__graph.md5 new file mode 100644 index 00000000..dad6b14e --- /dev/null +++ b/classfranka_1_1JointVelocities__inherit__graph.md5 @@ -0,0 +1 @@ +94bb303f7a32ad60e8c00cad1f7d60a0 \ No newline at end of file diff --git a/classfranka_1_1JointVelocities__inherit__graph.png b/classfranka_1_1JointVelocities__inherit__graph.png new file mode 100644 index 00000000..b3bab018 Binary files /dev/null and b/classfranka_1_1JointVelocities__inherit__graph.png differ diff --git a/classfranka_1_1Model-members.html b/classfranka_1_1Model-members.html new file mode 100644 index 00000000..0c7828d9 --- /dev/null +++ b/classfranka_1_1Model-members.html @@ -0,0 +1,109 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::Model Member List
+
+
+ +

This is the complete list of members for franka::Model, including all inherited members.

+ + + + + + + + + + + + + + + + + + + +
bodyJacobian(Frame frame, const franka::RobotState &robot_state) constfranka::Model
bodyJacobian(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) constfranka::Model
coriolis(const franka::RobotState &robot_state) const noexceptfranka::Model
coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexceptfranka::Model
gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexceptfranka::Model
gravity(const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const noexceptfranka::Model
gravity(const franka::RobotState &robot_state) const noexceptfranka::Model
mass(const franka::RobotState &robot_state) const noexceptfranka::Model
mass(const std::array< double, 7 > &q, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexceptfranka::Model
Model(franka::Network &network, const std::string &urdf_model)franka::Modelexplicit
Model(franka::Network &network, std::unique_ptr< RobotModelBase > robot_model)franka::Modelexplicit
Model(Model &&model) noexceptfranka::Model
operator=(Model &&model) noexceptfranka::Model
pose(Frame frame, const franka::RobotState &robot_state) constfranka::Model
pose(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) constfranka::Model
zeroJacobian(Frame frame, const franka::RobotState &robot_state) constfranka::Model
zeroJacobian(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) constfranka::Model
~Model() noexceptfranka::Model
+ + + + diff --git a/classfranka_1_1Model.html b/classfranka_1_1Model.html new file mode 100644 index 00000000..37fa29b0 --- /dev/null +++ b/classfranka_1_1Model.html @@ -0,0 +1,956 @@ + + + + + + + +libfranka: franka::Model Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +List of all members
+
+
franka::Model Class Reference
+
+
+ +

Calculates poses of joints and dynamic properties of the robot. + More...

+ +

#include <model.h>

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 Model (franka::Network &network, const std::string &urdf_model)
 Creates a new Model instance. More...
 
 Model (franka::Network &network, std::unique_ptr< RobotModelBase > robot_model)
 Creates a new Model instance only for the tests. More...
 
 Model (Model &&model) noexcept
 Move-constructs a new Model instance. More...
 
Modeloperator= (Model &&model) noexcept
 Move-assigns this Model from another Model instance. More...
 
~Model () noexcept
 Unloads the model library.
 
std::array< double, 16 > pose (Frame frame, const franka::RobotState &robot_state) const
 Gets the 4x4 pose matrix for the given frame in base frame. More...
 
std::array< double, 16 > pose (Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const
 Gets the 4x4 pose matrix for the given frame in base frame. More...
 
std::array< double, 42 > bodyJacobian (Frame frame, const franka::RobotState &robot_state) const
 Gets the 6x7 Jacobian for the given frame, relative to that frame. More...
 
std::array< double, 42 > bodyJacobian (Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const
 Gets the 6x7 Jacobian for the given frame, relative to that frame. More...
 
std::array< double, 42 > zeroJacobian (Frame frame, const franka::RobotState &robot_state) const
 Gets the 6x7 Jacobian for the given joint relative to the base frame. More...
 
std::array< double, 42 > zeroJacobian (Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const
 Gets the 6x7 Jacobian for the given joint relative to the base frame. More...
 
std::array< double, 49 > mass (const franka::RobotState &robot_state) const noexcept
 Calculates the 7x7 mass matrix. More...
 
std::array< double, 49 > mass (const std::array< double, 7 > &q, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept
 Calculates the 7x7 mass matrix. More...
 
std::array< double, 7 > coriolis (const franka::RobotState &robot_state) const noexcept
 Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\). More...
 
std::array< double, 7 > coriolis (const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept
 Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\). More...
 
std::array< double, 7 > gravity (const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexcept
 Calculates the gravity vector. More...
 
std::array< double, 7 > gravity (const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const noexcept
 Calculates the gravity vector. More...
 
std::array< double, 7 > gravity (const franka::RobotState &robot_state) const noexcept
 Calculates the gravity vector using the robot state. More...
 
+

Detailed Description

+

Calculates poses of joints and dynamic properties of the robot.

+
Examples
cartesian_impedance_control.cpp, force_control.cpp, joint_impedance_control.cpp, and print_joint_poses.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ Model() [1/3]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
franka::Model::Model (franka::Network & network,
const std::string & urdf_model 
)
+
+explicit
+
+ +

Creates a new Model instance.

+

This constructor is for internal use only.

+
See also
Robot::loadModel
+
Parameters
+ + +
[in]networkFor internal use.
+
+
+
Exceptions
+ + +
ModelExceptionif the model library cannot be loaded.
+
+
+ +
+
+ +

◆ Model() [2/3]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
franka::Model::Model (franka::Network & network,
std::unique_ptr< RobotModelBaserobot_model 
)
+
+explicit
+
+ +

Creates a new Model instance only for the tests.

+

This constructor is for the unittests for enabling mocks.

+
Parameters
+ + + +
[in]networkFor internal use.
[in]robot_modelunique pointer to the mocked robot_model
+
+
+ +
+
+ +

◆ Model() [3/3]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::Model::Model (Model && model)
+
+noexcept
+
+ +

Move-constructs a new Model instance.

+
Parameters
+ + +
[in]modelOther Model instance.
+
+
+ +
+
+

Member Function Documentation

+ +

◆ bodyJacobian() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + +
std::array<double, 42> franka::Model::bodyJacobian (Frame frame,
const franka::RobotStaterobot_state 
) const
+
+ +

Gets the 6x7 Jacobian for the given frame, relative to that frame.

+

The Jacobian is represented as a 6x7 matrix in column-major format.

+
Parameters
+ + + +
[in]frameThe desired frame.
[in]robot_stateState from which the pose should be calculated.
+
+
+
Returns
Vectorized 6x7 Jacobian, column-major.
+ +
+
+ +

◆ bodyJacobian() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
std::array<double, 42> franka::Model::bodyJacobian (Frame frame,
const std::array< double, 7 > & q,
const std::array< double, 16 > & F_T_EE,
const std::array< double, 16 > & EE_T_K 
) const
+
+ +

Gets the 6x7 Jacobian for the given frame, relative to that frame.

+

The Jacobian is represented as a 6x7 matrix in column-major format.

+
Parameters
+ + + + + +
[in]frameThe desired frame.
[in]qJoint position.
[in]F_T_EEEnd effector in flange frame.
[in]EE_T_KStiffness frame K in the end effector frame.
+
+
+
Returns
Vectorized 6x7 Jacobian, column-major.
+ +
+
+ +

◆ coriolis() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
std::array<double, 7> franka::Model::coriolis (const franka::RobotStaterobot_state) const
+
+noexcept
+
+ +

Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).

+
Parameters
+ + +
[in]robot_stateState from which the Coriolis force vector should be calculated.
+
+
+
Returns
Coriolis force vector.
+
Examples
cartesian_impedance_control.cpp.
+
+ +
+
+ +

◆ coriolis() [2/2]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
std::array<double, 7> franka::Model::coriolis (const std::array< double, 7 > & q,
const std::array< double, 7 > & dq,
const std::array< double, 9 > & I_total,
double m_total,
const std::array< double, 3 > & F_x_Ctotal 
) const
+
+noexcept
+
+ +

Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).

+
Parameters
+ + + + + + +
[in]qJoint position.
[in]dqJoint velocity.
[in]I_totalInertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\).
[in]m_totalWeight of the attached total load including end effector. Unit: \([kg]\).
[in]F_x_CtotalTranslation from flange to center of mass of the attached total load. Unit: \([m]\).
+
+
+
Returns
Coriolis force vector.
+ +
+
+ +

◆ gravity() [1/3]

+ +
+
+ + + + + +
+ + + + + + + + +
std::array<double, 7> franka::Model::gravity (const franka::RobotStaterobot_state) const
+
+noexcept
+
+ +

Calculates the gravity vector using the robot state.

+

Unit: \([Nm]\).

+
Parameters
+ + +
[in]robot_stateState from which the gravity vector should be calculated.
+
+
+
Returns
Gravity vector.
+ +
+
+ +

◆ gravity() [2/3]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
std::array<double, 7> franka::Model::gravity (const franka::RobotStaterobot_state,
const std::array< double, 3 > & gravity_earth 
) const
+
+noexcept
+
+ +

Calculates the gravity vector.

+

Unit: \([Nm]\).

+
Parameters
+ + + +
[in]robot_stateState from which the gravity vector should be calculated.
[in]gravity_earthEarth's gravity vector. Unit: \(\frac{m}{s^2}\).
+
+
+
Returns
Gravity vector.
+ +
+
+ +

◆ gravity() [3/3]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
std::array<double, 7> franka::Model::gravity (const std::array< double, 7 > & q,
double m_total,
const std::array< double, 3 > & F_x_Ctotal,
const std::array< double, 3 > & gravity_earth = {{0., 0., -9.81}} 
) const
+
+noexcept
+
+ +

Calculates the gravity vector.

+

Unit: \([Nm]\).

+
Parameters
+ + + + + +
[in]qJoint position.
[in]m_totalWeight of the attached total load including end effector. Unit: \([kg]\).
[in]F_x_CtotalTranslation from flange to center of mass of the attached total load. Unit: \([m]\).
[in]gravity_earthEarth's gravity vector. Unit: \(\frac{m}{s^2}\). Default to {0.0, 0.0, -9.81}.
+
+
+
Returns
Gravity vector.
+
Examples
force_control.cpp.
+
+ +
+
+ +

◆ mass() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
std::array<double, 49> franka::Model::mass (const franka::RobotStaterobot_state) const
+
+noexcept
+
+ +

Calculates the 7x7 mass matrix.

+

Unit: \([kg \times m^2]\).

+
Parameters
+ + +
[in]robot_stateState from which the mass matrix should be calculated.
+
+
+
Returns
Vectorized 7x7 mass matrix, column-major.
+ +
+
+ +

◆ mass() [2/2]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
std::array<double, 49> franka::Model::mass (const std::array< double, 7 > & q,
const std::array< double, 9 > & I_total,
double m_total,
const std::array< double, 3 > & F_x_Ctotal 
) const
+
+noexcept
+
+ +

Calculates the 7x7 mass matrix.

+

Unit: \([kg \times m^2]\).

+
Parameters
+ + + + + +
[in]qJoint position.
[in]I_totalInertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\).
[in]m_totalWeight of the attached total load including end effector. Unit: \([kg]\).
[in]F_x_CtotalTranslation from flange to center of mass of the attached total load. Unit: \([m]\).
+
+
+
Returns
Vectorized 7x7 mass matrix, column-major.
+ +
+
+ +

◆ operator=()

+ +
+
+ + + + + +
+ + + + + + + + +
Model& franka::Model::operator= (Model && model)
+
+noexcept
+
+ +

Move-assigns this Model from another Model instance.

+
Parameters
+ + +
[in]modelOther Model instance.
+
+
+
Returns
Model instance.
+ +
+
+ +

◆ pose() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + +
std::array<double, 16> franka::Model::pose (Frame frame,
const franka::RobotStaterobot_state 
) const
+
+ +

Gets the 4x4 pose matrix for the given frame in base frame.

+

The pose is represented as a 4x4 matrix in column-major format.

+
Parameters
+ + + +
[in]frameThe desired frame.
[in]robot_stateState from which the pose should be calculated.
+
+
+
Returns
Vectorized 4x4 pose matrix, column-major.
+ +
+
+ +

◆ pose() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
std::array<double, 16> franka::Model::pose (Frame frame,
const std::array< double, 7 > & q,
const std::array< double, 16 > & F_T_EE,
const std::array< double, 16 > & EE_T_K 
) const
+
+ +

Gets the 4x4 pose matrix for the given frame in base frame.

+

The pose is represented as a 4x4 matrix in column-major format.

+
Parameters
+ + + + + +
[in]frameThe desired frame.
[in]qJoint position.
[in]F_T_EEEnd effector in flange frame.
[in]EE_T_KStiffness frame K in the end effector frame.
+
+
+
Returns
Vectorized 4x4 pose matrix, column-major.
+ +
+
+ +

◆ zeroJacobian() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + +
std::array<double, 42> franka::Model::zeroJacobian (Frame frame,
const franka::RobotStaterobot_state 
) const
+
+ +

Gets the 6x7 Jacobian for the given joint relative to the base frame.

+

The Jacobian is represented as a 6x7 matrix in column-major format.

+
Parameters
+ + + +
[in]frameThe desired frame.
[in]robot_stateState from which the pose should be calculated.
+
+
+
Returns
Vectorized 6x7 Jacobian, column-major.
+
Examples
cartesian_impedance_control.cpp, and force_control.cpp.
+
+ +
+
+ +

◆ zeroJacobian() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
std::array<double, 42> franka::Model::zeroJacobian (Frame frame,
const std::array< double, 7 > & q,
const std::array< double, 16 > & F_T_EE,
const std::array< double, 16 > & EE_T_K 
) const
+
+ +

Gets the 6x7 Jacobian for the given joint relative to the base frame.

+

The Jacobian is represented as a 6x7 matrix in column-major format.

+
Parameters
+ + + + + +
[in]frameThe desired frame.
[in]qJoint position.
[in]F_T_EEEnd effector in flange frame.
[in]EE_T_KStiffness frame K in the end effector frame.
+
+
+
Returns
Vectorized 6x7 Jacobian, column-major.
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1Robot-members.html b/classfranka_1_1Robot-members.html new file mode 100644 index 00000000..512fb9e6 --- /dev/null +++ b/classfranka_1_1Robot-members.html @@ -0,0 +1,128 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::Robot Member List
+
+
+ +

This is the complete list of members for franka::Robot, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
automaticErrorRecovery()franka::Robot
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)franka::Robot
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)franka::Robot
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)franka::Robot
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)franka::Robot
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)franka::Robot
control(std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)franka::Robot
control(std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)franka::Robot
control(std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)franka::Robot
control(std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)franka::Robot
getRobotModel() -> std::stringfranka::Robot
loadModel()franka::Robot
loadModel(std::unique_ptr< RobotModelBase > robot_model) (defined in franka::Robot)franka::Robot
operator=(Robot &&other) noexceptfranka::Robot
read(std::function< bool(const RobotState &)> read_callback)franka::Robot
readOnce()franka::Robotvirtual
Robot(const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50)franka::Robotexplicit
Robot(Robot &&other) noexceptfranka::Robot
Robot(std::shared_ptr< Impl > robot_impl)franka::Robotprotected
Robot()=defaultfranka::Robotprotected
serverVersion() const noexceptfranka::Robot
ServerVersion typedeffranka::Robot
setCartesianImpedance(const std::array< double, 6 > &K_x)franka::Robot
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)franka::Robot
setCollisionBehavior(const std::array< double, 7 > &lower_torque_thresholds, const std::array< double, 7 > &upper_torque_thresholds, const std::array< double, 6 > &lower_force_thresholds, const std::array< double, 6 > &upper_force_thresholds)franka::Robot
setEE(const std::array< double, 16 > &NE_T_EE)franka::Robot
setGuidingMode(const std::array< bool, 6 > &guiding_mode, bool elbow)franka::Robot
setJointImpedance(const std::array< double, 7 > &K_theta)franka::Robot
setK(const std::array< double, 16 > &EE_T_K)franka::Robot
setLoad(double load_mass, const std::array< double, 3 > &F_x_Cload, const std::array< double, 9 > &load_inertia)franka::Robot
startCartesianPoseControl(const research_interface::robot::Move::ControllerMode &control_type)franka::Robotvirtual
startCartesianVelocityControl(const research_interface::robot::Move::ControllerMode &control_type)franka::Robotvirtual
startJointPositionControl(const research_interface::robot::Move::ControllerMode &control_type)franka::Robotvirtual
startJointVelocityControl(const research_interface::robot::Move::ControllerMode &control_type)franka::Robotvirtual
startTorqueControl()franka::Robotvirtual
stop()franka::Robot
~Robot() noexceptfranka::Robotvirtual
+ + + + diff --git a/classfranka_1_1Robot.html b/classfranka_1_1Robot.html new file mode 100644 index 00000000..2c5993ff --- /dev/null +++ b/classfranka_1_1Robot.html @@ -0,0 +1,1845 @@ + + + + + + + +libfranka: franka::Robot Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Types | +Public Member Functions | +Protected Member Functions | +List of all members
+
+
franka::Robot Class Reference
+
+
+ +

Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot. + More...

+ +

#include <robot.h>

+ + + + + +

+Public Types

+using ServerVersion = uint16_t
 Version of the robot server.
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 Robot (const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50)
 Establishes a connection with the robot. More...
 
 Robot (Robot &&other) noexcept
 Move-constructs a new Robot instance. More...
 
Robotoperator= (Robot &&other) noexcept
 Move-assigns this Robot from another Robot instance. More...
 
+virtual ~Robot () noexcept
 Closes the connection.
 
void read (std::function< bool(const RobotState &)> read_callback)
 Starts a loop for reading the current robot state. More...
 
virtual RobotState readOnce ()
 Waits for a robot state update and returns it. More...
 
Model loadModel ()
 Loads the model library from the robot. More...
 
+Model loadModel (std::unique_ptr< RobotModelBase > robot_model)
 
ServerVersion serverVersion () const noexcept
 Returns the software version reported by the connected server. More...
 
Motion generation and joint-level torque commands

The following methods allow to perform motion generation and/or send joint-level torque commands without gravity and friction by providing callback functions.

+

Only one of these methods can be active at the same time; a franka::ControlException is thrown otherwise.

+

When a robot state is received, the callback function is used to calculate the response: the desired values for that time step. After sending back the response, the callback function will be called again with the most recently received robot state. Since the robot is controlled with a 1 kHz frequency, the callback functions have to compute their result in a short time frame in order to be accepted. Callback functions take two parameters:

+
    +
  • A franka::RobotState showing the current robot state.
  • +
  • A franka::Duration to indicate the time since the last callback invocation. Thus, the duration is zero on the first invocation of the callback function!
  • +
+

The following incomplete example shows the general structure of a callback function:

+
double time = 0.0;
+
auto control_callback = [&time](const franka::RobotState& robot_state,
+ +
time += time_step.toSec(); // Update time at the beginning of the callback.
+
+
franka::JointPositions output = getJointPositions(time);
+
+
if (time >= max_time) {
+
// Return MotionFinished at the end of the trajectory.
+
return franka::MotionFinished(output);
+
}
+
+
return output;
+
}
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Stores values for joint position motion generation.
Definition: control_types.h:72
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Describes the robot state.
Definition: robot_state.h:34
+
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands. More...
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and joint positions. More...
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and joint velocities. More...
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and Cartesian poses. More...
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and Cartesian velocities. More...
 
void control (std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a joint position motion generator with a given controller mode. More...
 
void control (std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a joint velocity motion generator with a given controller mode. More...
 
void control (std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a Cartesian pose motion generator with a given controller mode. More...
 
void control (std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a Cartesian velocity motion generator with a given controller mode. More...
 
Commands

Commands are executed by communicating with the robot over the network.

+

These functions should therefore not be called from within control or motion generator loops.

+
auto getRobotModel () -> std::string
 
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. More...
 
void setCollisionBehavior (const std::array< double, 7 > &lower_torque_thresholds, const std::array< double, 7 > &upper_torque_thresholds, const std::array< double, 6 > &lower_force_thresholds, const std::array< double, 6 > &upper_force_thresholds)
 Changes the collision behavior. More...
 
void setJointImpedance (const std::array< double, 7 > &K_theta)
 Sets the impedance for each joint in the internal controller. More...
 
void setCartesianImpedance (const std::array< double, 6 > &K_x)
 Sets the Cartesian stiffness/compliance (for x, y, z, roll, pitch, yaw) in the internal controller. More...
 
void setGuidingMode (const std::array< bool, 6 > &guiding_mode, bool elbow)
 Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw). More...
 
void setK (const std::array< double, 16 > &EE_T_K)
 Sets the transformation \(^{EE}T_K\) from end effector frame to stiffness frame. More...
 
void setEE (const std::array< double, 16 > &NE_T_EE)
 Sets the transformation \(^{NE}T_{EE}\) from nominal end effector to end effector frame. More...
 
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. More...
 
void automaticErrorRecovery ()
 Runs automatic error recovery on the robot. More...
 
virtual std::unique_ptr< ActiveControlBasestartTorqueControl ()
 Starts a new torque controller. More...
 
virtual std::unique_ptr< ActiveControlBasestartJointPositionControl (const research_interface::robot::Move::ControllerMode &control_type)
 Starts a new joint position motion generator. More...
 
virtual std::unique_ptr< ActiveControlBasestartJointVelocityControl (const research_interface::robot::Move::ControllerMode &control_type)
 Starts a new joint velocity motion generator. More...
 
virtual std::unique_ptr< ActiveControlBasestartCartesianPoseControl (const research_interface::robot::Move::ControllerMode &control_type)
 Starts a new cartesian position motion generator. More...
 
virtual std::unique_ptr< ActiveControlBasestartCartesianVelocityControl (const research_interface::robot::Move::ControllerMode &control_type)
 Starts a new cartesian velocity motion generator. More...
 
void stop ()
 Stops all currently running motions. More...
 
+ + + + + + + +

+Protected Member Functions

 Robot (std::shared_ptr< Impl > robot_impl)
 Constructs a new Robot given a Robot::Impl. More...
 
Robot ()=default
 Default constructor to enable mocking and testing.
 
+

Detailed Description

+

Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot.

+
Note
The members of this class are threadsafe.
+

Base frame O
The base frame is located at the center of the robot's base. Its z-axis is identical with the axis of rotation of the first joint.
+

Flange frame F
The flange frame is located at the center of the flange surface. Its z-axis is identical with the axis of rotation of the last joint. This frame is fixed and cannot be changed.
+

Nominal end effector frame NE
The nominal end effector frame is configured outside of libfranka (in DESK) and cannot be changed here. It may be used to set end effector frames which are rarely changed.
+

end effector frame EE
By default, the end effector frame EE is the same as the nominal end effector frame NE (i.e. the transformation between NE and EE is the identity transformation). It may be used to set end effector frames which are changed more frequently (such as a tool that is grasped with the end effector). With Robot::setEE, a custom transformation matrix can be set.
+

Stiffness frame K
This frame describes the transformation from the end effector frame EE to the stiffness frame K. The stiffness frame is used for Cartesian impedance control, and for measuring and applying forces. The values set using Robot::setCartesianImpedance are used in the direction of the stiffness frame. It can be set with Robot::setK. This frame allows to modify the compliance behavior of the robot (e.g. to have a low stiffness around a specific point which is not the end effector). The stiffness frame does not affect where the robot will move to. The user should always command the desired end effector frame (and not the desired stiffness frame).
+
Examples
cartesian_impedance_control.cpp, communication_test.cpp, echo_robot_state.cpp, force_control.cpp, generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_cartesian_velocity_motion.cpp, generate_cartesian_velocity_motion_external_control_loop.cpp, generate_consecutive_motions.cpp, generate_elbow_motion.cpp, generate_joint_position_motion.cpp, generate_joint_position_motion_external_control_loop.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, joint_impedance_control.cpp, joint_point_to_point_motion.cpp, motion_with_control.cpp, motion_with_control_external_control_loop.cpp, and print_joint_poses.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ Robot() [1/3]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + +
franka::Robot::Robot (const std::string & franka_address,
RealtimeConfig realtime_config = RealtimeConfig::kEnforce,
size_t log_size = 50 
)
+
+explicit
+
+ +

Establishes a connection with the robot.

+
Parameters
+ + + + +
[in]franka_addressIP/hostname of the robot.
[in]realtime_configif set to Enforce, an exception will be thrown if realtime priority cannot be set when required. Setting realtime_config to Ignore disables this behavior.
[in]log_sizesets how many last states should be kept for logging purposes. The log is provided when a ControlException is thrown.
+
+
+
Exceptions
+ + + +
NetworkExceptionif the connection is unsuccessful.
IncompatibleVersionExceptionif this version of libfranka is not supported.
+
+
+ +
+
+ +

◆ Robot() [2/3]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::Robot::Robot (Robot && other)
+
+noexcept
+
+ +

Move-constructs a new Robot instance.

+
Parameters
+ + +
[in]otherOther Robot instance.
+
+
+ +
+
+ +

◆ Robot() [3/3]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::Robot::Robot (std::shared_ptr< Impl > robot_impl)
+
+protected
+
+ +

Constructs a new Robot given a Robot::Impl.

+

This enables unittests with Robot::Impl-Mocks.

+
Parameters
+ + +
robot_implRobot::Impl to use
+
+
+ +
+
+

Member Function Documentation

+ +

◆ automaticErrorRecovery()

+ +
+
+ + + + + + + +
void franka::Robot::automaticErrorRecovery ()
+
+ +

Runs automatic error recovery on the robot.

+

Automatic error recovery e.g. resets the robot after a collision occurred.

+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Examples
generate_consecutive_motions.cpp.
+
+ +
+
+ +

◆ control() [1/9]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::control (std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback,
ControllerMode controller_mode = ControllerMode::kJointImpedance,
bool limit_rate = false,
double cutoff_frequency = kDefaultCutoffFrequency 
)
+
+ +

Starts a control loop for a Cartesian pose motion generator with a given controller mode.

+

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

+
Parameters
+ + + + + +
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]controller_modeController to use to execute the motion.
[in]limit_rateTrue if rate limiting should be activated. False by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
+
+
+
Exceptions
+ + + + + + +
ControlExceptionif an error related to motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif Cartesian pose command elements are NaN or infinity.
+
+
+
See also
Robot::Robot to change behavior if realtime priority cannot be set.
+ +
+
+ +

◆ control() [2/9]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::control (std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback,
ControllerMode controller_mode = ControllerMode::kJointImpedance,
bool limit_rate = false,
double cutoff_frequency = kDefaultCutoffFrequency 
)
+
+ +

Starts a control loop for a Cartesian velocity motion generator with a given controller mode.

+

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

+
Parameters
+ + + + + +
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]controller_modeController to use to execute the motion.
[in]limit_rateTrue if rate limiting should be activated. False by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
+
+
+
Exceptions
+ + + + + + +
ControlExceptionif an error related to motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif Cartesian velocity command elements are NaN or infinity.
+
+
+
See also
Robot::Robot to change behavior if realtime priority cannot be set.
+ +
+
+ +

◆ control() [3/9]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::control (std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback,
ControllerMode controller_mode = ControllerMode::kJointImpedance,
bool limit_rate = false,
double cutoff_frequency = kDefaultCutoffFrequency 
)
+
+ +

Starts a control loop for a joint position motion generator with a given controller mode.

+

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

+
Parameters
+ + + + + +
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]controller_modeController to use to execute the motion.
[in]limit_rateTrue if rate limiting should be activated. False by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
+
+
+
Exceptions
+ + + + + + +
ControlExceptionif an error related to motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint position commands are NaN or infinity.
+
+
+
See also
Robot::Robot to change behavior if realtime priority cannot be set.
+ +
+
+ +

◆ control() [4/9]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::control (std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback,
ControllerMode controller_mode = ControllerMode::kJointImpedance,
bool limit_rate = false,
double cutoff_frequency = kDefaultCutoffFrequency 
)
+
+ +

Starts a control loop for a joint velocity motion generator with a given controller mode.

+

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

+
Parameters
+ + + + + +
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]controller_modeController to use to execute the motion.
[in]limit_rateTrue if rate limiting should be activated. False by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
+
+
+
Exceptions
+ + + + + + +
ControlExceptionif an error related to motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint velocity commands are NaN or infinity.
+
+
+
See also
Robot::Robot to change behavior if realtime priority cannot be set.
+ +
+
+ +

◆ control() [5/9]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::control (std::function< Torques(const RobotState &, franka::Duration)> control_callback,
bool limit_rate = false,
double cutoff_frequency = kDefaultCutoffFrequency 
)
+
+ +

Starts a control loop for sending joint-level torque commands.

+

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

+
Parameters
+ + + + +
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. False by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
+
+
+
Exceptions
+ + + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
+
+
+
See also
Robot::Robot to change behavior if realtime priority cannot be set.
+
Examples
cartesian_impedance_control.cpp, communication_test.cpp, force_control.cpp, generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_cartesian_velocity_motion.cpp, generate_cartesian_velocity_motion_external_control_loop.cpp, generate_consecutive_motions.cpp, generate_elbow_motion.cpp, generate_joint_position_motion.cpp, generate_joint_position_motion_external_control_loop.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, and joint_point_to_point_motion.cpp.
+
+ +
+
+ +

◆ control() [6/9]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::control (std::function< Torques(const RobotState &, franka::Duration)> control_callback,
std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback,
bool limit_rate = false,
double cutoff_frequency = kDefaultCutoffFrequency 
)
+
+ +

Starts a control loop for sending joint-level torque commands and Cartesian poses.

+

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

+
Parameters
+ + + + + +
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. False by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
+
+
+
Exceptions
+ + + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque or Cartesian pose command elements are NaN or infinity.
+
+
+
See also
Robot::Robot to change behavior if realtime priority cannot be set.
+ +
+
+ +

◆ control() [7/9]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::control (std::function< Torques(const RobotState &, franka::Duration)> control_callback,
std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback,
bool limit_rate = false,
double cutoff_frequency = kDefaultCutoffFrequency 
)
+
+ +

Starts a control loop for sending joint-level torque commands and Cartesian velocities.

+

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

+
Parameters
+ + + + + +
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. False by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
+
+
+
Exceptions
+ + + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque or Cartesian velocity command elements are NaN or infinity.
+
+
+
See also
Robot::Robot to change behavior if realtime priority cannot be set.
+ +
+
+ +

◆ control() [8/9]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::control (std::function< Torques(const RobotState &, franka::Duration)> control_callback,
std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback,
bool limit_rate = false,
double cutoff_frequency = kDefaultCutoffFrequency 
)
+
+ +

Starts a control loop for sending joint-level torque commands and joint positions.

+

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

+
Parameters
+ + + + + +
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. False by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
+
+
+
Exceptions
+ + + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque or joint position commands are NaN or infinity.
+
+
+
See also
Robot::Robot to change behavior if realtime priority cannot be set.
+ +
+
+ +

◆ control() [9/9]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::control (std::function< Torques(const RobotState &, franka::Duration)> control_callback,
std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback,
bool limit_rate = false,
double cutoff_frequency = kDefaultCutoffFrequency 
)
+
+ +

Starts a control loop for sending joint-level torque commands and joint velocities.

+

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

+
Parameters
+ + + + + +
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. False by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
+
+
+
Exceptions
+ + + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque or joint velocity commands are NaN or infinity.
+
+
+
See also
Robot::Robot to change behavior if realtime priority cannot be set.
+ +
+
+ +

◆ getRobotModel()

+ +
+
+ + + + + + + +
auto franka::Robot::getRobotModel () -> std::string
+
+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Returns
std::string Provides the URDF model of the attached robot arm as json string
+ +
+
+ +

◆ loadModel()

+ +
+
+ + + + + + + +
Model franka::Robot::loadModel ()
+
+ +

Loads the model library from the robot.

+
Returns
Model instance.
+
Exceptions
+ + + +
ModelExceptionif the model library cannot be loaded.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Examples
cartesian_impedance_control.cpp, and force_control.cpp.
+
+ +
+
+ +

◆ operator=()

+ +
+
+ + + + + +
+ + + + + + + + +
Robot& franka::Robot::operator= (Robot && other)
+
+noexcept
+
+ +

Move-assigns this Robot from another Robot instance.

+
Parameters
+ + +
[in]otherOther Robot instance.
+
+
+
Returns
Robot instance.
+ +
+
+ +

◆ read()

+ +
+
+ + + + + + + + +
void franka::Robot::read (std::function< bool(const RobotState &)> read_callback)
+
+ +

Starts a loop for reading the current robot state.

+

Cannot be executed while a control or motion generator loop is running.

+

This minimal example will print the robot state 100 times:

franka::Robot robot("robot.franka.de");
+
size_t count = 0;
+
robot.read([&count](const franka::RobotState& robot_state) {
+
std::cout << robot_state << std::endl;
+
return count++ < 100;
+
});
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
Parameters
+ + +
[in]read_callbackCallback function for robot state reading.
+
+
+
Exceptions
+ + + +
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Examples
echo_robot_state.cpp.
+
+ +
+
+ +

◆ readOnce()

+ +
+
+ + + + + +
+ + + + + + + +
virtual RobotState franka::Robot::readOnce ()
+
+virtual
+
+ +

Waits for a robot state update and returns it.

+

Cannot be executed while a control or motion generator loop is running.

+
Returns
Current robot state.
+
Exceptions
+ + + +
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
See also
Robot::read for a way to repeatedly receive the robot state.
+
Examples
cartesian_impedance_control.cpp, and force_control.cpp.
+
+ +
+
+ +

◆ serverVersion()

+ +
+
+ + + + + +
+ + + + + + + +
ServerVersion franka::Robot::serverVersion () const
+
+noexcept
+
+ +

Returns the software version reported by the connected server.

+
Returns
Software version of the connected server.
+ +
+
+ +

◆ setCartesianImpedance()

+ +
+
+ + + + + + + + +
void franka::Robot::setCartesianImpedance (const std::array< double, 6 > & K_x)
+
+ +

Sets the Cartesian stiffness/compliance (for x, y, z, roll, pitch, yaw) in the internal controller.

+

The values set using Robot::setCartesianImpedance are used in the direction of the stiffness frame, which can be set with Robot::setK.

+

Inputs received by the torque controller are not affected by this setting.

+
Parameters
+ + +
[in]K_xCartesian impedance values \(K_x=(K_{x_{x,y,z}} \in [10,3000] \frac{N}{m}, K_{x_{R,P,Y}} \in [1,300] \frac{Nm}{rad})\)
+
+
+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+ +
+
+ +

◆ setCollisionBehavior() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::setCollisionBehavior (const std::array< double, 7 > & lower_torque_thresholds,
const std::array< double, 7 > & upper_torque_thresholds,
const std::array< double, 6 > & lower_force_thresholds,
const std::array< double, 6 > & upper_force_thresholds 
)
+
+ +

Changes the collision behavior.

+

Set common torque and force boundaries for acceleration/deceleration and constant velocity movement phases.

+

Forces or torques between lower and upper threshold are shown as contacts in the RobotState. Forces or torques above the upper threshold are registered as collision and cause the robot to stop moving.

+
Parameters
+ + + + + +
[in]lower_torque_thresholdsContact torque thresholds for each joint in \([Nm]\).
[in]upper_torque_thresholdsCollision torque thresholds for each joint in \([Nm]\).
[in]lower_force_thresholdsContact force thresholds for \((x,y,z,R,P,Y)\) in \([N]\).
[in]upper_force_thresholdsCollision force thresholds for \((x,y,z,R,P,Y)\) in \([N]\).
+
+
+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
See also
RobotState::cartesian_contact
+
+RobotState::cartesian_collision
+
+RobotState::joint_contact
+
+RobotState::joint_collision
+
+Robot::automaticErrorRecovery for performing a reset after a collision.
+ +
+
+ +

◆ setCollisionBehavior() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::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.

+

Set separate torque and force boundaries for acceleration/deceleration and constant velocity movement phases.

+

Forces or torques between lower and upper threshold are shown as contacts in the RobotState. Forces or torques above the upper threshold are registered as collision and cause the robot to stop moving.

+
Parameters
+ + + + + + + + + +
[in]lower_torque_thresholds_accelerationContact torque thresholds during acceleration/deceleration for each joint in \([Nm]\).
[in]upper_torque_thresholds_accelerationCollision torque thresholds during acceleration/deceleration for each joint in \([Nm]\).
[in]lower_torque_thresholds_nominalContact torque thresholds for each joint in \([Nm]\).
[in]upper_torque_thresholds_nominalCollision torque thresholds for each joint in \([Nm]\).
[in]lower_force_thresholds_accelerationContact force thresholds during acceleration/deceleration for \((x,y,z,R,P,Y)\) in \([N]\).
[in]upper_force_thresholds_accelerationCollision force thresholds during acceleration/deceleration for \((x,y,z,R,P,Y)\) in \([N]\).
[in]lower_force_thresholds_nominalContact force thresholds for \((x,y,z,R,P,Y)\) in \([N]\).
[in]upper_force_thresholds_nominalCollision force thresholds for \((x,y,z,R,P,Y)\) in \([N]\).
+
+
+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
See also
RobotState::cartesian_contact
+
+RobotState::cartesian_collision
+
+RobotState::joint_contact
+
+RobotState::joint_collision
+
+Robot::automaticErrorRecovery for performing a reset after a collision.
+
Examples
cartesian_impedance_control.cpp, communication_test.cpp, force_control.cpp, generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_cartesian_velocity_motion.cpp, generate_cartesian_velocity_motion_external_control_loop.cpp, generate_consecutive_motions.cpp, generate_elbow_motion.cpp, generate_joint_position_motion.cpp, generate_joint_position_motion_external_control_loop.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, and joint_point_to_point_motion.cpp.
+
+ +
+
+ +

◆ setEE()

+ +
+
+ + + + + + + + +
void franka::Robot::setEE (const std::array< double, 16 > & NE_T_EE)
+
+ +

Sets the transformation \(^{NE}T_{EE}\) from nominal end effector to end effector frame.

+

The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.

+
Parameters
+ + +
[in]NE_T_EEVectorized NE-to-EE transformation matrix \(^{NE}T_{EE}\), column-major.
+
+
+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
See also
RobotState::NE_T_EE for end effector pose in nominal end effector frameNE". +@see RobotState::O_T_EE for end effector pose in @ref o-frame "world base frame O". +@see RobotState::F_T_EE for end effector pose in @ref f-frame "flange frame F".
+ +
+
+ +

◆ setGuidingMode()

+ +
+
+ + + + + + + + + + + + + + + + + + +
void franka::Robot::setGuidingMode (const std::array< bool, 6 > & guiding_mode,
bool elbow 
)
+
+ +

Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw).

+

If a flag is set to true, movement is unlocked.

+
Note
Guiding mode can be enabled by pressing the two opposing buttons near the robot's flange.
+
Parameters
+ + + +
[in]guiding_modeUnlocked movement in (x, y, z, R, P, Y) in guiding mode.
[in]elbowTrue if the elbow is free in guiding mode, false otherwise.
+
+
+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+ +
+
+ +

◆ setJointImpedance()

+ +
+
+ + + + + + + + +
void franka::Robot::setJointImpedance (const std::array< double, 7 > & K_theta)
+
+ +

Sets the impedance for each joint in the internal controller.

+

User-provided torques are not affected by this setting.

+
Parameters
+ + +
[in]K_thetaJoint impedance values \(K_{\theta_{1-7}} = \in [0,14250] \frac{Nm}{rad}\)
+
+
+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Examples
generate_cartesian_velocity_motion.cpp, and generate_cartesian_velocity_motion_external_control_loop.cpp.
+
+ +
+
+ +

◆ setK()

+ +
+
+ + + + + + + + +
void franka::Robot::setK (const std::array< double, 16 > & EE_T_K)
+
+ +

Sets the transformation \(^{EE}T_K\) from end effector frame to stiffness frame.

+

The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.

+
Parameters
+ + +
[in]EE_T_KVectorized EE-to-K transformation matrix \(^{EE}T_K\), column-major.
+
+
+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
See also
Robot for an explanation of the stiffness frame.
+ +
+
+ +

◆ setLoad()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
void franka::Robot::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.

+
Note
This is not for setting end effector parameters, which have to be set in the administrator's interface.
+
Parameters
+ + + + +
[in]load_massMass of the load in \([kg]\).
[in]F_x_CloadTranslation from flange to center of mass of load \(^Fx_{C_\text{load}}\) in \([m]\).
[in]load_inertiaInertia matrix \(I_\text{load}\) in \([kg \times m^2]\), column-major.
+
+
+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+ +
+
+ +

◆ startCartesianPoseControl()

+ +
+
+ + + + + +
+ + + + + + + + +
virtual std::unique_ptr<ActiveControlBase> franka::Robot::startCartesianPoseControl (const research_interface::robot::Move::ControllerMode & control_type)
+
+virtual
+
+ +

Starts a new cartesian position motion generator.

+
Parameters
+ + +
control_typeresearch_interface::robot::Move::ControllerMode control type for the operation
+
+
+
Returns
unique_ptr of ActiveMotionGenerator for the started motion
+
Exceptions
+ + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
+
+
+
Examples
generate_cartesian_pose_motion_external_control_loop.cpp.
+
+ +
+
+ +

◆ startCartesianVelocityControl()

+ +
+
+ + + + + +
+ + + + + + + + +
virtual std::unique_ptr<ActiveControlBase> franka::Robot::startCartesianVelocityControl (const research_interface::robot::Move::ControllerMode & control_type)
+
+virtual
+
+ +

Starts a new cartesian velocity motion generator.

+
Parameters
+ + +
control_typeresearch_interface::robot::Move::ControllerMode control type for the operation
+
+
+
Returns
unique_ptr of ActiveMotionGenerator for the started motion
+
Exceptions
+ + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
+
+
+
Examples
generate_cartesian_velocity_motion_external_control_loop.cpp.
+
+ +
+
+ +

◆ startJointPositionControl()

+ +
+
+ + + + + +
+ + + + + + + + +
virtual std::unique_ptr<ActiveControlBase> franka::Robot::startJointPositionControl (const research_interface::robot::Move::ControllerMode & control_type)
+
+virtual
+
+ +

Starts a new joint position motion generator.

+
Parameters
+ + +
control_typeresearch_interface::robot::Move::ControllerMode control type for the operation
+
+
+
Returns
unique_ptr of ActiveMotionGenerator for the started motion
+
Exceptions
+ + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
+
+
+
Examples
generate_joint_position_motion_external_control_loop.cpp.
+
+ +
+
+ +

◆ startJointVelocityControl()

+ +
+
+ + + + + +
+ + + + + + + + +
virtual std::unique_ptr<ActiveControlBase> franka::Robot::startJointVelocityControl (const research_interface::robot::Move::ControllerMode & control_type)
+
+virtual
+
+ +

Starts a new joint velocity motion generator.

+
Parameters
+ + +
control_typeresearch_interface::robot::Move::ControllerMode control type for the operation
+
+
+
Returns
unique_ptr of ActiveMotionGenerator for the started motion
+
Exceptions
+ + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
+
+
+
Examples
generate_joint_velocity_motion_external_control_loop.cpp.
+
+ +
+
+ +

◆ startTorqueControl()

+ +
+
+ + + + + +
+ + + + + + + +
virtual std::unique_ptr<ActiveControlBase> franka::Robot::startTorqueControl ()
+
+virtual
+
+ +

Starts a new torque controller.

+
Returns
unique_ptr of ActiveTorqueControl for the started motion
+
Exceptions
+ + + + + +
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
+
+
+
Examples
communication_test.cpp.
+
+ +
+
+ +

◆ stop()

+ +
+
+ + + + + + + +
void franka::Robot::stop ()
+
+ +

Stops all currently running motions.

+

If a control or motion generator loop is running in another thread, it will be preempted with a franka::ControlException.

+
Exceptions
+ + + +
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1RobotModel-members.html b/classfranka_1_1RobotModel-members.html new file mode 100644 index 00000000..b61bdafb --- /dev/null +++ b/classfranka_1_1RobotModel-members.html @@ -0,0 +1,96 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::RobotModel Member List
+
+
+ +

This is the complete list of members for franka::RobotModel, including all inherited members.

+ + + + + + +
coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne) overridefranka::RobotModelvirtual
gravity(const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne) overridefranka::RobotModelvirtual
mass(const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne) overridefranka::RobotModelvirtual
RobotModel(const std::string &urdf) (defined in franka::RobotModel)franka::RobotModel
~RobotModelBase()=default (defined in RobotModelBase)RobotModelBasevirtual
+ + + + diff --git a/classfranka_1_1RobotModel.html b/classfranka_1_1RobotModel.html new file mode 100644 index 00000000..3b4cb32f --- /dev/null +++ b/classfranka_1_1RobotModel.html @@ -0,0 +1,349 @@ + + + + + + + +libfranka: franka::RobotModel Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +List of all members
+
+
franka::RobotModel Class Reference
+
+
+ +

Implements RobotModelBase using Pinocchio. + More...

+ +

#include <robot_model.h>

+
+Inheritance diagram for franka::RobotModel:
+
+
Inheritance graph
+ + + + +
[legend]
+
+Collaboration diagram for franka::RobotModel:
+
+
Collaboration graph
+ + + + +
[legend]
+ + + + + + + + + + + + + +

+Public Member Functions

RobotModel (const std::string &urdf)
 
void coriolis (const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne) override
 Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\). More...
 
void gravity (const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne) override
 Calculates the gravity vector. More...
 
void mass (const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne) override
 Calculates the 7x7 mass matrix. More...
 
+

Detailed Description

+

Implements RobotModelBase using Pinocchio.

+

Member Function Documentation

+ +

◆ coriolis()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::RobotModel::coriolis (const std::array< double, 7 > & q,
const std::array< double, 7 > & dq,
const std::array< double, 9 > & i_total,
double m_total,
const std::array< double, 3 > & f_x_ctotal,
std::array< double, 7 > & c_ne 
)
+
+overridevirtual
+
+ +

Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).

+
Parameters
+ + + + + + + +
[in]qJoint position.
[in]dqJoint velocity.
[in]i_totalInertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\).
[in]m_totalWeight of the attached total load including end effector. Unit: \([kg]\).
[in]f_x_ctotalTranslation from flange to center of mass of the attached total load. Unit: \([m]\).
[out]c_neCoriolis force vector. Unit: \([Nm]\).
+
+
+ +

Implements RobotModelBase.

+ +
+
+ +

◆ gravity()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::RobotModel::gravity (const std::array< double, 7 > & q,
const std::array< double, 3 > & g_earth,
double m_total,
const std::array< double, 3 > & f_x_ctotal,
std::array< double, 7 > & g_ne 
)
+
+overridevirtual
+
+ +

Calculates the gravity vector.

+

Unit: \([Nm]\).

+
Parameters
+ + + + + + +
[in]qJoint position.
[in]gravity_earthEarth's gravity vector. Unit: \(\frac{m}{s^2}\).
[in]m_totalWeight of the attached total load including end effector. Unit: \([kg]\).
[in]f_x_CtotalTranslation from flange to center of mass of the attached total load.
[out]g_neGravity vector. Unit: \([Nm]\).
+
+
+ +

Implements RobotModelBase.

+ +
+
+ +

◆ mass()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void franka::RobotModel::mass (const std::array< double, 7 > & q,
const std::array< double, 9 > & i_total,
double m_total,
const std::array< double, 3 > & f_x_ctotal,
std::array< double, 49 > & m_ne 
)
+
+overridevirtual
+
+ +

Calculates the 7x7 mass matrix.

+

Unit: \([kg \times m^2]\).

+
Parameters
+ + + + + + +
[in]qJoint position.
[in]i_totalInertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\).
[in]m_totalWeight of the attached total load including end effector. Unit: \([kg]\).
[in]f_x_ctotalTranslation from flange to center of mass of the attached total load. Unit: \([m]\).
[out]m_neVectorized 7x7 mass matrix, column-major.
+
+
+ +

Implements RobotModelBase.

+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1RobotModel__coll__graph.map b/classfranka_1_1RobotModel__coll__graph.map new file mode 100644 index 00000000..57698f31 --- /dev/null +++ b/classfranka_1_1RobotModel__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1RobotModel__coll__graph.md5 b/classfranka_1_1RobotModel__coll__graph.md5 new file mode 100644 index 00000000..912da929 --- /dev/null +++ b/classfranka_1_1RobotModel__coll__graph.md5 @@ -0,0 +1 @@ +9c27c3a04c18c899b61a6f3538c8e3ed \ No newline at end of file diff --git a/classfranka_1_1RobotModel__coll__graph.png b/classfranka_1_1RobotModel__coll__graph.png new file mode 100644 index 00000000..e276343f Binary files /dev/null and b/classfranka_1_1RobotModel__coll__graph.png differ diff --git a/classfranka_1_1RobotModel__inherit__graph.map b/classfranka_1_1RobotModel__inherit__graph.map new file mode 100644 index 00000000..57698f31 --- /dev/null +++ b/classfranka_1_1RobotModel__inherit__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1RobotModel__inherit__graph.md5 b/classfranka_1_1RobotModel__inherit__graph.md5 new file mode 100644 index 00000000..912da929 --- /dev/null +++ b/classfranka_1_1RobotModel__inherit__graph.md5 @@ -0,0 +1 @@ +9c27c3a04c18c899b61a6f3538c8e3ed \ No newline at end of file diff --git a/classfranka_1_1RobotModel__inherit__graph.png b/classfranka_1_1RobotModel__inherit__graph.png new file mode 100644 index 00000000..e276343f Binary files /dev/null and b/classfranka_1_1RobotModel__inherit__graph.png differ diff --git a/classfranka_1_1Torques-members.html b/classfranka_1_1Torques-members.html new file mode 100644 index 00000000..e41e3a6c --- /dev/null +++ b/classfranka_1_1Torques-members.html @@ -0,0 +1,95 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::Torques Member List
+
+
+ +

This is the complete list of members for franka::Torques, including all inherited members.

+ + + + + +
motion_finishedfranka::Finishable
tau_Jfranka::Torques
Torques(const std::array< double, 7 > &torques) noexceptfranka::Torques
Torques(std::initializer_list< double > torques)franka::Torques
+ + + + diff --git a/classfranka_1_1Torques.html b/classfranka_1_1Torques.html new file mode 100644 index 00000000..a8e52dcf --- /dev/null +++ b/classfranka_1_1Torques.html @@ -0,0 +1,211 @@ + + + + + + + +libfranka: franka::Torques Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Member Functions | +Public Attributes | +List of all members
+
+
franka::Torques Class Reference
+
+
+ +

Stores joint-level torque commands without gravity and friction. + More...

+ +

#include <control_types.h>

+
+Inheritance diagram for franka::Torques:
+
+
Inheritance graph
+ + + + +
[legend]
+
+Collaboration diagram for franka::Torques:
+
+
Collaboration graph
+ + + + +
[legend]
+ + + + + + + + +

+Public Member Functions

 Torques (const std::array< double, 7 > &torques) noexcept
 Creates a new Torques instance. More...
 
 Torques (std::initializer_list< double > torques)
 Creates a new Torques instance. More...
 
+ + + + + + + + +

+Public Attributes

+std::array< double, 7 > tau_J {}
 Desired torques in [Nm].
 
- Public Attributes inherited from franka::Finishable
+bool motion_finished = false
 Determines whether to finish a currently running motion.
 
+

Detailed Description

+

Stores joint-level torque commands without gravity and friction.

+
Examples
cartesian_impedance_control.cpp, communication_test.cpp, force_control.cpp, joint_impedance_control.cpp, motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ Torques() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::Torques::Torques (const std::array< double, 7 > & torques)
+
+noexcept
+
+ +

Creates a new Torques instance.

+
Parameters
+ + +
[in]torquesDesired joint-level torques without gravity and friction in \([Nm]\).
+
+
+ +
+
+ +

◆ Torques() [2/2]

+ +
+
+ + + + + + + + +
franka::Torques::Torques (std::initializer_list< double > torques)
+
+ +

Creates a new Torques instance.

+
Parameters
+ + +
[in]torquesDesired joint-level torques without gravity and friction in \([Nm]\).
+
+
+
Exceptions
+ + +
std::invalid_argumentif the given initializer list has an invalid number of arguments.
+
+
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/classfranka_1_1Torques__coll__graph.map b/classfranka_1_1Torques__coll__graph.map new file mode 100644 index 00000000..de27f9cb --- /dev/null +++ b/classfranka_1_1Torques__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1Torques__coll__graph.md5 b/classfranka_1_1Torques__coll__graph.md5 new file mode 100644 index 00000000..bb5e5fcd --- /dev/null +++ b/classfranka_1_1Torques__coll__graph.md5 @@ -0,0 +1 @@ +a943715320da47aa78a814b0a876491e \ No newline at end of file diff --git a/classfranka_1_1Torques__coll__graph.png b/classfranka_1_1Torques__coll__graph.png new file mode 100644 index 00000000..9dcd64dd Binary files /dev/null and b/classfranka_1_1Torques__coll__graph.png differ diff --git a/classfranka_1_1Torques__inherit__graph.map b/classfranka_1_1Torques__inherit__graph.map new file mode 100644 index 00000000..de27f9cb --- /dev/null +++ b/classfranka_1_1Torques__inherit__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/classfranka_1_1Torques__inherit__graph.md5 b/classfranka_1_1Torques__inherit__graph.md5 new file mode 100644 index 00000000..bb5e5fcd --- /dev/null +++ b/classfranka_1_1Torques__inherit__graph.md5 @@ -0,0 +1 @@ +a943715320da47aa78a814b0a876491e \ No newline at end of file diff --git a/classfranka_1_1Torques__inherit__graph.png b/classfranka_1_1Torques__inherit__graph.png new file mode 100644 index 00000000..9dcd64dd Binary files /dev/null and b/classfranka_1_1Torques__inherit__graph.png differ diff --git a/classfranka_1_1VacuumGripper-members.html b/classfranka_1_1VacuumGripper-members.html new file mode 100644 index 00000000..1bc564df --- /dev/null +++ b/classfranka_1_1VacuumGripper-members.html @@ -0,0 +1,102 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka::VacuumGripper Member List
+
+
+ +

This is the complete list of members for franka::VacuumGripper, including all inherited members.

+ + + + + + + + + + + + +
dropOff(std::chrono::milliseconds timeout) constfranka::VacuumGripper
operator=(VacuumGripper &&vacuum_gripper) noexceptfranka::VacuumGripper
ProductionSetupProfile enum namefranka::VacuumGripper
readOnce() constfranka::VacuumGripper
ServerVersion typedeffranka::VacuumGripper
serverVersion() const noexceptfranka::VacuumGripper
stop() constfranka::VacuumGripper
vacuum(uint8_t vacuum, std::chrono::milliseconds timeout, ProductionSetupProfile profile=ProductionSetupProfile::kP0) constfranka::VacuumGripper
VacuumGripper(const std::string &franka_address)franka::VacuumGripperexplicit
VacuumGripper(VacuumGripper &&vacuum_gripper) noexceptfranka::VacuumGripper
~VacuumGripper() noexceptfranka::VacuumGripper
+ + + + diff --git a/classfranka_1_1VacuumGripper.html b/classfranka_1_1VacuumGripper.html new file mode 100644 index 00000000..d9a353c6 --- /dev/null +++ b/classfranka_1_1VacuumGripper.html @@ -0,0 +1,439 @@ + + + + + + + +libfranka: franka::VacuumGripper Class Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Public Types | +Public Member Functions | +List of all members
+
+
franka::VacuumGripper Class Reference
+
+
+ +

Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state, and allows the execution of commands. + More...

+ +

#include <vacuum_gripper.h>

+ + + + + + + + +

+Public Types

enum class  ProductionSetupProfile { kP0 +, kP1 +, kP2 +, kP3 + }
 Vacuum production setup profile.
 
+using ServerVersion = uint16_t
 Version of the vacuum gripper server.
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 VacuumGripper (const std::string &franka_address)
 Establishes a connection with a vacuum gripper connected to a robot. More...
 
 VacuumGripper (VacuumGripper &&vacuum_gripper) noexcept
 Move-constructs a new VacuumGripper instance. More...
 
VacuumGripperoperator= (VacuumGripper &&vacuum_gripper) noexcept
 Move-assigns this VacuumGripper from another VacuumGripper instance. More...
 
~VacuumGripper () noexcept
 Closes the connection.
 
bool vacuum (uint8_t vacuum, std::chrono::milliseconds timeout, ProductionSetupProfile profile=ProductionSetupProfile::kP0) const
 Vacuums an object. More...
 
bool dropOff (std::chrono::milliseconds timeout) const
 Drops the grasped object off. More...
 
bool stop () const
 Stops a currently running vacuum gripper vacuum or drop off operation. More...
 
VacuumGripperState readOnce () const
 Waits for a vacuum gripper state update and returns it. More...
 
ServerVersion serverVersion () const noexcept
 Returns the software version reported by the connected server. More...
 
+

Detailed Description

+

Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state, and allows the execution of commands.

+
Note
The members of this class are threadsafe.
+
Examples
vacuum_object.cpp.
+
+

Constructor & Destructor Documentation

+ +

◆ VacuumGripper() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::VacuumGripper::VacuumGripper (const std::string & franka_address)
+
+explicit
+
+ +

Establishes a connection with a vacuum gripper connected to a robot.

+
Parameters
+ + +
[in]franka_addressIP/hostname of the robot the vacuum gripper is connected to.
+
+
+
Exceptions
+ + + +
NetworkExceptionif the connection is unsuccessful.
IncompatibleVersionExceptionif this version of libfranka is not supported.
+
+
+ +
+
+ +

◆ VacuumGripper() [2/2]

+ +
+
+ + + + + +
+ + + + + + + + +
franka::VacuumGripper::VacuumGripper (VacuumGripper && vacuum_gripper)
+
+noexcept
+
+ +

Move-constructs a new VacuumGripper instance.

+
Parameters
+ + +
[in]vacuum_gripperOther VacuumGripper instance.
+
+
+ +
+
+

Member Function Documentation

+ +

◆ dropOff()

+ +
+
+ + + + + + + + +
bool franka::VacuumGripper::dropOff (std::chrono::milliseconds timeout) const
+
+ +

Drops the grasped object off.

+
Parameters
+ + +
[in]timeoutDropoff timeout. Unit: \([ms]\).
+
+
+
Returns
True if command was successful, false otherwise.
+
Exceptions
+ + + +
CommandExceptionif an error occurred.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Examples
vacuum_object.cpp.
+
+ +
+
+ +

◆ operator=()

+ +
+
+ + + + + +
+ + + + + + + + +
VacuumGripper& franka::VacuumGripper::operator= (VacuumGripper && vacuum_gripper)
+
+noexcept
+
+ +

Move-assigns this VacuumGripper from another VacuumGripper instance.

+
Parameters
+ + +
[in]vacuum_gripperOther VacuumGripper instance.
+
+
+
Returns
Model instance.
+ +
+
+ +

◆ readOnce()

+ +
+
+ + + + + + + +
VacuumGripperState franka::VacuumGripper::readOnce () const
+
+ +

Waits for a vacuum gripper state update and returns it.

+
Returns
Current vacuum gripper state.
+
Exceptions
+ + + +
NetworkExceptionif the connection is lost, e.g. after a timeout.
InvalidOperationExceptionif another readOnce is already running.
+
+
+
Examples
vacuum_object.cpp.
+
+ +
+
+ +

◆ serverVersion()

+ +
+
+ + + + + +
+ + + + + + + +
ServerVersion franka::VacuumGripper::serverVersion () const
+
+noexcept
+
+ +

Returns the software version reported by the connected server.

+
Returns
Software version of the connected server.
+ +
+
+ +

◆ stop()

+ +
+
+ + + + + + + +
bool franka::VacuumGripper::stop () const
+
+ +

Stops a currently running vacuum gripper vacuum or drop off operation.

+
Returns
True if command was successful, false otherwise.
+
Exceptions
+ + + +
CommandExceptionif an error occurred.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Examples
vacuum_object.cpp.
+
+ +
+
+ +

◆ vacuum()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
bool franka::VacuumGripper::vacuum (uint8_t vacuum,
std::chrono::milliseconds timeout,
ProductionSetupProfile profile = ProductionSetupProfile::kP0 
) const
+
+ +

Vacuums an object.

+
Parameters
+ + + + +
[in]vacuumSetpoint for control mode. Unit: \([10*mbar]\).
[in]timeoutVacuum timeout. Unit: \([ms]\).
[in]profileProduction setup profile P0 to P3. Default: P0.
+
+
+
Returns
True if the vacuum has been established, false otherwise.
+
Exceptions
+ + + +
CommandExceptionif an error occurred.
NetworkExceptionif the connection is lost, e.g. after a timeout.
+
+
+
Examples
vacuum_object.cpp.
+
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/closed.png b/closed.png new file mode 100644 index 00000000..98cc2c90 Binary files /dev/null and b/closed.png differ diff --git a/communication_test_8cpp-example.html b/communication_test_8cpp-example.html new file mode 100644 index 00000000..518b4949 --- /dev/null +++ b/communication_test_8cpp-example.html @@ -0,0 +1,227 @@ + + + + + + + +libfranka: communication_test.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
communication_test.cpp
+
+
+

An example indicating the network performance.

Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <chrono>
+
#include <iostream>
+
#include <thread>
+
+ + + + +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
+
uint64_t counter = 0;
+
double avg_success_rate = 0.0;
+
double min_success_rate = 1.0;
+
double max_success_rate = 0.0;
+
uint64_t time = 0;
+
std::cout.precision(2);
+
std::cout << std::fixed;
+
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl << std::endl;
+
std::cout << "Starting communication test." << std::endl;
+
+ +
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
+
+
franka::Torques zero_torques{{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}};
+
auto rw_interface = robot.startTorqueControl();
+
+
franka::RobotState robot_state;
+ +
+
while (!zero_torques.motion_finished) {
+
std::tie(robot_state, period) = rw_interface->readOnce();
+
+
time += period.toMSec();
+
if (time == 0.0) {
+
rw_interface->writeOnce(zero_torques);
+
continue;
+
}
+
counter++;
+
+
if (counter % 100 == 0) {
+
std::cout << "#" << counter
+
<< " Current success rate: " << robot_state.control_command_success_rate
+
<< std::endl;
+
}
+
std::this_thread::sleep_for(std::chrono::microseconds(100));
+
+
avg_success_rate += robot_state.control_command_success_rate;
+
if (robot_state.control_command_success_rate > max_success_rate) {
+
max_success_rate = robot_state.control_command_success_rate;
+
}
+
if (robot_state.control_command_success_rate < min_success_rate) {
+
min_success_rate = robot_state.control_command_success_rate;
+
}
+
+
if (time >= 10000) {
+
std::cout << std::endl << "Finished test, shutting down example" << std::endl;
+
zero_torques.motion_finished = true;
+
}
+
// Sending zero torques - if EE is configured correctly, robot should not move
+
rw_interface->writeOnce(zero_torques);
+
}
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
avg_success_rate = avg_success_rate / counter;
+
+
std::cout << std::endl
+
<< std::endl
+
<< "#######################################################" << std::endl;
+
uint64_t lost_robot_states = time - counter;
+
if (lost_robot_states > 0) {
+
std::cout << "The control loop did not get executed " << lost_robot_states << " times in the"
+
<< std::endl
+
<< "last " << time << " milliseconds! (lost " << lost_robot_states << " robot states)"
+
<< std::endl
+
<< std::endl;
+
}
+
+
std::cout << "Control command success rate of " << counter << " samples: " << std::endl;
+
std::cout << "Max: " << max_success_rate << std::endl;
+
std::cout << "Avg: " << avg_success_rate << std::endl;
+
std::cout << "Min: " << min_success_rate << std::endl;
+
+
if (avg_success_rate < 0.90) {
+
std::cout << std::endl
+
<< "WARNING: THIS SETUP IS PROBABLY NOT SUFFICIENT FOR FCI!" << std::endl;
+
std::cout << "PLEASE TRY OUT A DIFFERENT PC / NIC" << std::endl;
+
} else if (avg_success_rate < 0.95) {
+
std::cout << std::endl << "WARNING: MANY PACKETS GOT LOST!" << std::endl;
+
std::cout << "PLEASE INSPECT YOUR SETUP AND FOLLOW ADVICE ON" << std::endl
+
<< "https://frankaemika.github.io/docs/troubleshooting.html" << std::endl;
+
}
+
std::cout << "#######################################################" << std::endl << std::endl;
+
+
return 0;
+
}
+
Implements the ActiveControlBase abstract class.
+
Contains the franka::ActiveTorqueControl type.
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
uint64_t toMSec() const noexcept
Returns the stored duration in .
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
virtual std::unique_ptr< ActiveControlBase > startTorqueControl()
Starts a new torque controller.
+
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
+
Contains the franka::Duration type.
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
double control_command_success_rate
Percentage of the last 100 control commands that were successfully received by the robot.
Definition: robot_state.h:388
+
+ + + + diff --git a/control__tools_8h.html b/control__tools_8h.html new file mode 100644 index 00000000..9a24467f --- /dev/null +++ b/control__tools_8h.html @@ -0,0 +1,370 @@ + + + + + + + +libfranka: include/franka/control_tools.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Functions
+
+
control_tools.h File Reference
+
+
+ +

Contains helper functions for writing control loops. +More...

+
#include <algorithm>
+#include <array>
+#include <cmath>
+#include <stdexcept>
+#include <string>
+
+Include dependency graph for control_tools.h:
+
+
+ + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + + + + + + + + + + + + + + + + + + + +

+Functions

bool franka::isValidElbow (const std::array< double, 2 > &elbow) noexcept
 Determines whether the given elbow configuration is valid or not. More...
 
bool franka::isHomogeneousTransformation (const std::array< double, 16 > &transform) noexcept
 Determines whether the given array represents a valid homogeneous transformation matrix. More...
 
bool franka::hasRealtimeKernel ()
 Determines whether the current OS kernel is a realtime kernel. More...
 
bool franka::setCurrentThreadToHighestSchedulerPriority (std::string *error_message)
 Sets the current thread to the highest possible scheduler priority. More...
 
template<size_t N>
void franka::checkFinite (const std::array< double, N > &array)
 Checks if all elements of an array of the size N have a finite value. More...
 
void franka::checkMatrix (const std::array< double, 16 > &transform)
 Checks if all elements of the transformation matrix are finite and if it is a homogeneous transformation. More...
 
void franka::checkElbow (const std::array< double, 2 > &elbow)
 Checks if all elements of the elbow vector are finite and if the elbow configuration is valid. More...
 
+

Detailed Description

+

Contains helper functions for writing control loops.

+

Function Documentation

+ +

◆ checkElbow()

+ +
+
+ + + + + +
+ + + + + + + + +
void franka::checkElbow (const std::array< double, 2 > & elbow)
+
+inline
+
+ +

Checks if all elements of the elbow vector are finite and if the elbow configuration is valid.

+
Parameters
+ + +
elbowthe elbow vector to check
+
+
+ +
+
+ +

◆ checkFinite()

+ +
+
+
+template<size_t N>
+ + + + + +
+ + + + + + + + +
void franka::checkFinite (const std::array< double, N > & array)
+
+inline
+
+ +

Checks if all elements of an array of the size N have a finite value.

+
Template Parameters
+ + +
Nthe size of the array
+
+
+
Parameters
+ + +
arraythe array to be checked
+
+
+ +
+
+ +

◆ checkMatrix()

+ +
+
+ + + + + +
+ + + + + + + + +
void franka::checkMatrix (const std::array< double, 16 > & transform)
+
+inline
+
+ +

Checks if all elements of the transformation matrix are finite and if it is a homogeneous transformation.

+
Parameters
+ + +
transformthe transformation matrix to check
+
+
+ +
+
+ +

◆ hasRealtimeKernel()

+ +
+
+ + + + + + + +
bool franka::hasRealtimeKernel ()
+
+ +

Determines whether the current OS kernel is a realtime kernel.

+

On Linux, this checks for the existence of /sys/kernel/realtime. On Windows, this always returns true.

+
Returns
True if running a realtime kernel, false otherwise.
+ +
+
+ +

◆ isHomogeneousTransformation()

+ +
+
+ + + + + +
+ + + + + + + + +
bool franka::isHomogeneousTransformation (const std::array< double, 16 > & transform)
+
+inlinenoexcept
+
+ +

Determines whether the given array represents a valid homogeneous transformation matrix.

+
Parameters
+ + +
[in]transform4x4 matrix in column-major format.
+
+
+
Returns
True if the array represents a homogeneous transformation matrix, otherwise false.
+ +
+
+ +

◆ isValidElbow()

+ +
+
+ + + + + +
+ + + + + + + + +
bool franka::isValidElbow (const std::array< double, 2 > & elbow)
+
+inlinenoexcept
+
+ +

Determines whether the given elbow configuration is valid or not.

+
Parameters
+ + +
[in]elbowElbow configuration.
+
+
+
Returns
True if valid, otherwise false.
+ +
+
+ +

◆ setCurrentThreadToHighestSchedulerPriority()

+ +
+
+ + + + + + + + +
bool franka::setCurrentThreadToHighestSchedulerPriority (std::string * error_message)
+
+ +

Sets the current thread to the highest possible scheduler priority.

+
Parameters
+ + +
[out]error_messageContains an error message if the scheduler priority cannot be set successfully.
+
+
+
Returns
True if successful, false otherwise.
+ +
+
+
+ + + + diff --git a/control__tools_8h__incl.map b/control__tools_8h__incl.map new file mode 100644 index 00000000..6d2c9291 --- /dev/null +++ b/control__tools_8h__incl.map @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/control__tools_8h__incl.md5 b/control__tools_8h__incl.md5 new file mode 100644 index 00000000..c874c351 --- /dev/null +++ b/control__tools_8h__incl.md5 @@ -0,0 +1 @@ +5141d7f3d139d959e1417dbec33a0159 \ No newline at end of file diff --git a/control__tools_8h__incl.png b/control__tools_8h__incl.png new file mode 100644 index 00000000..817cdd56 Binary files /dev/null and b/control__tools_8h__incl.png differ diff --git a/control__tools_8h_source.html b/control__tools_8h_source.html new file mode 100644 index 00000000..35cef894 --- /dev/null +++ b/control__tools_8h_source.html @@ -0,0 +1,165 @@ + + + + + + + +libfranka: include/franka/control_tools.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
control_tools.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <algorithm>
+
6 #include <array>
+
7 #include <cmath>
+
8 #include <stdexcept>
+
9 #include <string>
+
10 
+
16 namespace franka {
+
17 
+
25 inline bool isValidElbow(const std::array<double, 2>& elbow) noexcept {
+
26  return elbow[1] == -1.0 || elbow[1] == 1.0;
+
27 }
+
28 
+
36 inline bool isHomogeneousTransformation(const std::array<double, 16>& transform) noexcept {
+
37  constexpr double kOrthonormalThreshold = 1e-5;
+
38 
+
39  if (transform[3] != 0.0 || transform[7] != 0.0 || transform[11] != 0.0 || transform[15] != 1.0) {
+
40  return false;
+
41  }
+
42  for (size_t j = 0; j < 3; ++j) { // i..column
+
43  if (std::abs(std::sqrt(std::pow(transform[j * 4 + 0], 2) + std::pow(transform[j * 4 + 1], 2) +
+
44  std::pow(transform[j * 4 + 2], 2)) -
+
45  1.0) > kOrthonormalThreshold) {
+
46  return false;
+
47  }
+
48  }
+
49  for (size_t i = 0; i < 3; ++i) { // j..row
+
50  if (std::abs(std::sqrt(std::pow(transform[0 * 4 + i], 2) + std::pow(transform[1 * 4 + i], 2) +
+
51  std::pow(transform[2 * 4 + i], 2)) -
+
52  1.0) > kOrthonormalThreshold) {
+
53  return false;
+
54  }
+
55  }
+
56  return true;
+
57 }
+
58 
+ +
68 
+
77 bool setCurrentThreadToHighestSchedulerPriority(std::string* error_message);
+
78 
+
85 template <size_t N>
+
86 inline void checkFinite(const std::array<double, N>& array) {
+
87  if (!std::all_of(array.begin(), array.end(),
+
88  [](double array_element) { return std::isfinite(array_element); })) {
+
89  throw std::invalid_argument("Commanding value is infinite or NaN.");
+
90  }
+
91 }
+
92 
+
99 inline void checkMatrix(const std::array<double, 16>& transform) {
+
100  checkFinite(transform);
+
101  if (!isHomogeneousTransformation(transform)) {
+
102  throw std::invalid_argument(
+
103  "libfranka: Attempt to set invalid transformation in motion generator. Has to be column "
+
104  "major!");
+
105  }
+
106 }
+
107 
+
113 inline void checkElbow(const std::array<double, 2>& elbow) {
+
114  checkFinite(elbow);
+
115  if (!isValidElbow(elbow)) {
+
116  throw std::invalid_argument(
+
117  "Invalid elbow configuration given! Only +1 or -1 are allowed for the sign of the 4th "
+
118  "joint.");
+
119  }
+
120 }
+
121 
+
122 } // namespace franka
+
bool isValidElbow(const std::array< double, 2 > &elbow) noexcept
Determines whether the given elbow configuration is valid or not.
Definition: control_tools.h:25
+
bool setCurrentThreadToHighestSchedulerPriority(std::string *error_message)
Sets the current thread to the highest possible scheduler priority.
+
void checkFinite(const std::array< double, N > &array)
Checks if all elements of an array of the size N have a finite value.
Definition: control_tools.h:86
+
void checkMatrix(const std::array< double, 16 > &transform)
Checks if all elements of the transformation matrix are finite and if it is a homogeneous transformat...
Definition: control_tools.h:99
+
bool hasRealtimeKernel()
Determines whether the current OS kernel is a realtime kernel.
+
bool isHomogeneousTransformation(const std::array< double, 16 > &transform) noexcept
Determines whether the given array represents a valid homogeneous transformation matrix.
Definition: control_tools.h:36
+
void checkElbow(const std::array< double, 2 > &elbow)
Checks if all elements of the elbow vector are finite and if the elbow configuration is valid.
Definition: control_tools.h:113
+
+ + + + diff --git a/control__types_8h.html b/control__types_8h.html new file mode 100644 index 00000000..07f5a611 --- /dev/null +++ b/control__types_8h.html @@ -0,0 +1,392 @@ + + + + + + + +libfranka: include/franka/control_types.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Classes | +Enumerations | +Functions
+
+
control_types.h File Reference
+
+
+ +

Contains helper types for returning motion generation and joint-level torque commands. +More...

+
#include <array>
+#include <cmath>
+#include <initializer_list>
+
+Include dependency graph for control_types.h:
+
+
+ + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + + + + + + + + + + + + + + + +

+Classes

struct  franka::Finishable
 Helper type for control and motion generation loops. More...
 
class  franka::Torques
 Stores joint-level torque commands without gravity and friction. More...
 
class  franka::JointPositions
 Stores values for joint position motion generation. More...
 
class  franka::JointVelocities
 Stores values for joint velocity motion generation. More...
 
class  franka::CartesianPose
 Stores values for Cartesian pose motion generation. More...
 
class  franka::CartesianVelocities
 Stores values for Cartesian velocity motion generation. More...
 
+ + + + + + + +

+Enumerations

enum class  franka::ControllerMode { kJointImpedance +, kCartesianImpedance + }
 Available controller modes for a franka::Robot.
 
enum class  franka::RealtimeConfig { kEnforce +, kIgnore + }
 Used to decide whether to enforce realtime mode for a control loop thread. More...
 
+ + + + + + + + + + + + + + + + +

+Functions

Torques franka::MotionFinished (Torques command) noexcept
 Helper method to indicate that a motion should stop after processing the given command. More...
 
JointPositions franka::MotionFinished (JointPositions command) noexcept
 Helper method to indicate that a motion should stop after processing the given command. More...
 
JointVelocities franka::MotionFinished (JointVelocities command) noexcept
 Helper method to indicate that a motion should stop after processing the given command. More...
 
CartesianPose franka::MotionFinished (CartesianPose command) noexcept
 Helper method to indicate that a motion should stop after processing the given command. More...
 
CartesianVelocities franka::MotionFinished (CartesianVelocities command) noexcept
 Helper method to indicate that a motion should stop after processing the given command. More...
 
+

Detailed Description

+

Contains helper types for returning motion generation and joint-level torque commands.

+

Enumeration Type Documentation

+ +

◆ RealtimeConfig

+ +
+
+ + + + + +
+ + + + +
enum franka::RealtimeConfig
+
+strong
+
+ +

Used to decide whether to enforce realtime mode for a control loop thread.

+
See also
Robot::Robot
+ +
+
+

Function Documentation

+ +

◆ MotionFinished() [1/5]

+ +
+
+ + + + + +
+ + + + + + + + +
CartesianPose franka::MotionFinished (CartesianPose command)
+
+inlinenoexcept
+
+ +

Helper method to indicate that a motion should stop after processing the given command.

+
Parameters
+ + +
[in]commandLast command to be executed before the motion terminates.
+
+
+
Returns
Command with motion_finished set to true.
+
See also
Documentation on callbacks
+ +
+
+ +

◆ MotionFinished() [2/5]

+ +
+
+ + + + + +
+ + + + + + + + +
CartesianVelocities franka::MotionFinished (CartesianVelocities command)
+
+inlinenoexcept
+
+ +

Helper method to indicate that a motion should stop after processing the given command.

+
Parameters
+ + +
[in]commandLast command to be executed before the motion terminates.
+
+
+
Returns
Command with motion_finished set to true.
+
See also
Documentation on callbacks
+ +
+
+ +

◆ MotionFinished() [3/5]

+ +
+
+ + + + + +
+ + + + + + + + +
JointPositions franka::MotionFinished (JointPositions command)
+
+inlinenoexcept
+
+ +

Helper method to indicate that a motion should stop after processing the given command.

+
Parameters
+ + +
[in]commandLast command to be executed before the motion terminates.
+
+
+
Returns
Command with motion_finished set to true.
+
See also
Documentation on callbacks
+ +
+
+ +

◆ MotionFinished() [4/5]

+ +
+
+ + + + + +
+ + + + + + + + +
JointVelocities franka::MotionFinished (JointVelocities command)
+
+inlinenoexcept
+
+ +

Helper method to indicate that a motion should stop after processing the given command.

+
Parameters
+ + +
[in]commandLast command to be executed before the motion terminates.
+
+
+
Returns
Command with motion_finished set to true.
+
See also
Documentation on callbacks
+ +
+
+ +

◆ MotionFinished() [5/5]

+ +
+
+ + + + + +
+ + + + + + + + +
Torques franka::MotionFinished (Torques command)
+
+inlinenoexcept
+
+
+
+ + + + diff --git a/control__types_8h__dep__incl.map b/control__types_8h__dep__incl.map new file mode 100644 index 00000000..5a40acb1 --- /dev/null +++ b/control__types_8h__dep__incl.map @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/control__types_8h__dep__incl.md5 b/control__types_8h__dep__incl.md5 new file mode 100644 index 00000000..29a46de0 --- /dev/null +++ b/control__types_8h__dep__incl.md5 @@ -0,0 +1 @@ +c0026db29db1d1ba723208a8d80a703d \ No newline at end of file diff --git a/control__types_8h__dep__incl.png b/control__types_8h__dep__incl.png new file mode 100644 index 00000000..5a5f5092 Binary files /dev/null and b/control__types_8h__dep__incl.png differ diff --git a/control__types_8h__incl.map b/control__types_8h__incl.map new file mode 100644 index 00000000..87cc0746 --- /dev/null +++ b/control__types_8h__incl.map @@ -0,0 +1,6 @@ + + + + + + diff --git a/control__types_8h__incl.md5 b/control__types_8h__incl.md5 new file mode 100644 index 00000000..8917aa1e --- /dev/null +++ b/control__types_8h__incl.md5 @@ -0,0 +1 @@ +3a1c47faf01a25ffc032edd4841a146e \ No newline at end of file diff --git a/control__types_8h__incl.png b/control__types_8h__incl.png new file mode 100644 index 00000000..850394c8 Binary files /dev/null and b/control__types_8h__incl.png differ diff --git a/control__types_8h_source.html b/control__types_8h_source.html new file mode 100644 index 00000000..679ca0e2 --- /dev/null +++ b/control__types_8h_source.html @@ -0,0 +1,231 @@ + + + + + + + +libfranka: include/franka/control_types.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
control_types.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <array>
+
6 #include <cmath>
+
7 #include <initializer_list>
+
8 
+
14 namespace franka {
+
15 
+
19 enum class ControllerMode { kJointImpedance, kCartesianImpedance };
+
20 
+
26 enum class RealtimeConfig { kEnforce, kIgnore };
+
27 
+
35 struct Finishable {
+
39  bool motion_finished = false;
+
40 };
+
41 
+
45 class Torques : public Finishable {
+
46  public:
+
52  Torques(const std::array<double, 7>& torques) noexcept;
+
53 
+
61  Torques(std::initializer_list<double> torques);
+
62 
+
66  std::array<double, 7> tau_J{}; // NOLINT(readability-identifier-naming)
+
67 };
+
68 
+
72 class JointPositions : public Finishable {
+
73  public:
+
79  JointPositions(const std::array<double, 7>& joint_positions) noexcept;
+
80 
+
88  JointPositions(std::initializer_list<double> joint_positions);
+
89 
+
93  std::array<double, 7> q{};
+
94 };
+
95 
+
99 class JointVelocities : public Finishable {
+
100  public:
+
107  JointVelocities(const std::array<double, 7>& joint_velocities) noexcept;
+
108 
+
116  JointVelocities(std::initializer_list<double> joint_velocities);
+
117 
+
121  std::array<double, 7> dq{};
+
122 };
+
123 
+
127 class CartesianPose : public Finishable {
+
128  public:
+
136  CartesianPose(const std::array<double, 16>& cartesian_pose) noexcept;
+
137 
+
146  CartesianPose(const std::array<double, 16>& cartesian_pose,
+
147  const std::array<double, 2>& elbow) noexcept;
+
148 
+
158  CartesianPose(std::initializer_list<double> cartesian_pose);
+
159 
+
171  CartesianPose(std::initializer_list<double> cartesian_pose, std::initializer_list<double> elbow);
+
172 
+
178  std::array<double, 16> O_T_EE{}; // NOLINT(readability-identifier-naming)
+
179 
+
193  std::array<double, 2> elbow{};
+
194 
+
201  bool hasElbow() const noexcept;
+
202 };
+
203 
+ +
212  public:
+
220  CartesianVelocities(const std::array<double, 6>& cartesian_velocities) noexcept;
+
221 
+
230  CartesianVelocities(const std::array<double, 6>& cartesian_velocities,
+
231  const std::array<double, 2>& elbow) noexcept;
+
232 
+
242  CartesianVelocities(std::initializer_list<double> cartesian_velocities);
+
243 
+
254  CartesianVelocities(std::initializer_list<double> cartesian_velocities,
+
255  std::initializer_list<double> elbow);
+
256 
+
261  std::array<double, 6> O_dP_EE{}; // NOLINT(readability-identifier-naming)
+
262 
+
275  std::array<double, 2> elbow{};
+
276 
+
282  bool hasElbow() const noexcept;
+
283 };
+
284 
+
294 inline Torques MotionFinished(Torques command) noexcept { // NOLINT(readability-identifier-naming)
+
295  command.motion_finished = true;
+
296  return command;
+
297 }
+
298 
+
308 inline JointPositions MotionFinished( // NOLINT(readability-identifier-naming)
+
309  JointPositions command) noexcept {
+
310  command.motion_finished = true;
+
311  return command;
+
312 }
+
313 
+
323 inline JointVelocities MotionFinished( // NOLINT(readability-identifier-naming)
+
324  JointVelocities command) noexcept {
+
325  command.motion_finished = true;
+
326  return command;
+
327 }
+
328 
+
338 inline CartesianPose MotionFinished( // NOLINT(readability-identifier-naming)
+
339  CartesianPose command) noexcept {
+
340  command.motion_finished = true;
+
341  return command;
+
342 }
+
343 
+
353 inline CartesianVelocities MotionFinished( // NOLINT(readability-identifier-naming)
+
354  CartesianVelocities command) noexcept {
+
355  command.motion_finished = true;
+
356  return command;
+
357 }
+
358 
+
359 } // namespace franka
+
Stores values for Cartesian pose motion generation.
Definition: control_types.h:127
+
CartesianPose(const std::array< double, 16 > &cartesian_pose, const std::array< double, 2 > &elbow) noexcept
Creates a new CartesianPose instance.
+
std::array< double, 16 > O_T_EE
Homogeneous transformation , column major, that transforms from the end effector frame to base frame...
Definition: control_types.h:178
+
CartesianPose(const std::array< double, 16 > &cartesian_pose) noexcept
Creates a new CartesianPose instance.
+
bool hasElbow() const noexcept
Determines whether there is a stored elbow configuration.
+
CartesianPose(std::initializer_list< double > cartesian_pose)
Creates a new CartesianPose instance.
+
CartesianPose(std::initializer_list< double > cartesian_pose, std::initializer_list< double > elbow)
Creates a new CartesianPose instance.
+
std::array< double, 2 > elbow
Elbow configuration.
Definition: control_types.h:193
+
Stores values for Cartesian velocity motion generation.
Definition: control_types.h:211
+
CartesianVelocities(std::initializer_list< double > cartesian_velocities)
Creates a new CartesianVelocities instance.
+
bool hasElbow() const noexcept
Determines whether there is a stored elbow configuration.
+
CartesianVelocities(const std::array< double, 6 > &cartesian_velocities) noexcept
Creates a new CartesianVelocities instance.
+
CartesianVelocities(const std::array< double, 6 > &cartesian_velocities, const std::array< double, 2 > &elbow) noexcept
Creates a new CartesianVelocities instance.
+
CartesianVelocities(std::initializer_list< double > cartesian_velocities, std::initializer_list< double > elbow)
Creates a new CartesianVelocities instance.
+
Stores values for joint position motion generation.
Definition: control_types.h:72
+
JointPositions(std::initializer_list< double > joint_positions)
Creates a new JointPositions instance.
+
std::array< double, 7 > q
Desired joint angles in [rad].
Definition: control_types.h:93
+
JointPositions(const std::array< double, 7 > &joint_positions) noexcept
Creates a new JointPositions instance.
+
Stores values for joint velocity motion generation.
Definition: control_types.h:99
+
JointVelocities(const std::array< double, 7 > &joint_velocities) noexcept
Creates a new JointVelocities instance.
+
std::array< double, 7 > dq
Desired joint velocities in .
Definition: control_types.h:121
+
JointVelocities(std::initializer_list< double > joint_velocities)
Creates a new JointVelocities instance.
+
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
+
Torques(const std::array< double, 7 > &torques) noexcept
Creates a new Torques instance.
+
Torques(std::initializer_list< double > torques)
Creates a new Torques instance.
+
std::array< double, 7 > tau_J
Desired torques in [Nm].
Definition: control_types.h:66
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
ControllerMode
Available controller modes for a franka::Robot.
Definition: control_types.h:19
+
RealtimeConfig
Used to decide whether to enforce realtime mode for a control loop thread.
Definition: control_types.h:26
+
Helper type for control and motion generation loops.
Definition: control_types.h:35
+
bool motion_finished
Determines whether to finish a currently running motion.
Definition: control_types.h:39
+
+ + + + diff --git a/dir_000001_000002.html b/dir_000001_000002.html new file mode 100644 index 00000000..4db4fbbe --- /dev/null +++ b/dir_000001_000002.html @@ -0,0 +1,84 @@ + + + + + + + +libfranka: examples -> include Relation + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+

examples → include Relation

File in examplesIncludes file in include
cartesian_impedance_control.cppfranka / duration.h
cartesian_impedance_control.cppfranka / exception.h
cartesian_impedance_control.cppfranka / model.h
cartesian_impedance_control.cppfranka / robot.h
communication_test.cppfranka / active_control.h
communication_test.cppfranka / active_torque_control.h
communication_test.cppfranka / duration.h
communication_test.cppfranka / exception.h
communication_test.cppfranka / robot.h
echo_robot_state.cppfranka / exception.h
echo_robot_state.cppfranka / robot.h
examples_common.cppfranka / exception.h
examples_common.cppfranka / robot.h
examples_common.hfranka / control_types.h
examples_common.hfranka / duration.h
examples_common.hfranka / robot.h
examples_common.hfranka / robot_state.h
force_control.cppfranka / duration.h
force_control.cppfranka / exception.h
force_control.cppfranka / model.h
force_control.cppfranka / robot.h
generate_cartesian_pose_motion.cppfranka / exception.h
generate_cartesian_pose_motion.cppfranka / robot.h
generate_cartesian_pose_motion_external_control_loop.cppfranka / active_control.h
generate_cartesian_pose_motion_external_control_loop.cppfranka / active_motion_generator.h
generate_cartesian_pose_motion_external_control_loop.cppfranka / exception.h
generate_cartesian_pose_motion_external_control_loop.cppfranka / robot.h
generate_cartesian_velocity_motion.cppfranka / exception.h
generate_cartesian_velocity_motion.cppfranka / robot.h
generate_cartesian_velocity_motion_external_control_loop.cppfranka / active_control.h
generate_cartesian_velocity_motion_external_control_loop.cppfranka / active_motion_generator.h
generate_cartesian_velocity_motion_external_control_loop.cppfranka / exception.h
generate_cartesian_velocity_motion_external_control_loop.cppfranka / robot.h
generate_consecutive_motions.cppfranka / exception.h
generate_consecutive_motions.cppfranka / robot.h
generate_elbow_motion.cppfranka / exception.h
generate_elbow_motion.cppfranka / robot.h
generate_joint_position_motion.cppfranka / exception.h
generate_joint_position_motion.cppfranka / robot.h
generate_joint_position_motion_external_control_loop.cppfranka / active_control.h
generate_joint_position_motion_external_control_loop.cppfranka / active_motion_generator.h
generate_joint_position_motion_external_control_loop.cppfranka / exception.h
generate_joint_position_motion_external_control_loop.cppfranka / robot.h
generate_joint_velocity_motion.cppfranka / exception.h
generate_joint_velocity_motion.cppfranka / robot.h
generate_joint_velocity_motion_external_control_loop.cppfranka / active_control.h
generate_joint_velocity_motion_external_control_loop.cppfranka / active_motion_generator.h
generate_joint_velocity_motion_external_control_loop.cppfranka / exception.h
generate_joint_velocity_motion_external_control_loop.cppfranka / robot.h
grasp_object.cppfranka / exception.h
grasp_object.cppfranka / gripper.h
joint_impedance_control.cppfranka / duration.h
joint_impedance_control.cppfranka / exception.h
joint_impedance_control.cppfranka / model.h
joint_impedance_control.cppfranka / rate_limiting.h
joint_impedance_control.cppfranka / robot.h
joint_point_to_point_motion.cppfranka / exception.h
joint_point_to_point_motion.cppfranka / robot.h
motion_with_control.cppfranka / exception.h
motion_with_control.cppfranka / robot.h
motion_with_control_external_control_loop.cppfranka / active_control.h
motion_with_control_external_control_loop.cppfranka / active_motion_generator.h
motion_with_control_external_control_loop.cppfranka / exception.h
motion_with_control_external_control_loop.cppfranka / robot.h
print_joint_poses.cppfranka / exception.h
print_joint_poses.cppfranka / model.h
vacuum_object.cppfranka / exception.h
vacuum_object.cppfranka / vacuum_gripper.h
+ + + + diff --git a/dir_5f30c89189ebb3336d6b33aa932838ba.html b/dir_5f30c89189ebb3336d6b33aa932838ba.html new file mode 100644 index 00000000..d03d1853 --- /dev/null +++ b/dir_5f30c89189ebb3336d6b33aa932838ba.html @@ -0,0 +1,149 @@ + + + + + + + +libfranka: include/franka Directory Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
franka Directory Reference
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Files

file  active_control.h [code]
 Implements the ActiveControlBase abstract class.
 
file  active_control_base.h [code]
 Abstract interface class as the base of the active controllers.
 
file  active_motion_generator.h [code]
 Contains the franka::ActiveMotionGenerator type.
 
file  active_torque_control.h [code]
 Contains the franka::ActiveTorqueControl type.
 
file  control_tools.h [code]
 Contains helper functions for writing control loops.
 
file  control_types.h [code]
 Contains helper types for returning motion generation and joint-level torque commands.
 
file  duration.h [code]
 Contains the franka::Duration type.
 
file  errors.h [code]
 Contains the franka::Errors type.
 
file  exception.h [code]
 Contains exception definitions.
 
file  gripper.h [code]
 Contains the franka::Gripper type.
 
file  gripper_state.h [code]
 Contains the franka::GripperState type.
 
file  log.h [code]
 Contains helper types for logging sent commands and received robot states.
 
file  lowpass_filter.h [code]
 Contains functions for filtering signals with a low-pass filter.
 
file  model.h [code]
 Contains model library types.
 
file  rate_limiting.h [code]
 Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity.
 
file  robot.h [code]
 Contains the franka::Robot type.
 
file  robot_state.h [code]
 Contains the franka::RobotState types.
 
file  vacuum_gripper.h [code]
 Contains the franka::VacuumGripper type.
 
file  vacuum_gripper_state.h [code]
 Contains the franka::VacuumGripperState type.
 
+
+ + + + diff --git a/dir_d28a4824dc47e487b107a5db32ef43c4.html b/dir_d28a4824dc47e487b107a5db32ef43c4.html new file mode 100644 index 00000000..28ce1758 --- /dev/null +++ b/dir_d28a4824dc47e487b107a5db32ef43c4.html @@ -0,0 +1,105 @@ + + + + + + + +libfranka: examples Directory Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
examples Directory Reference
+
+
+
+Directory dependency graph for examples:
+
+
examples
+ + + + + +
+ + + + + +

+Files

file  examples_common.h [code]
 Contains common types and functions for the examples.
 
+
+ + + + diff --git a/dir_d28a4824dc47e487b107a5db32ef43c4_dep.map b/dir_d28a4824dc47e487b107a5db32ef43c4_dep.map new file mode 100644 index 00000000..c2f2d159 --- /dev/null +++ b/dir_d28a4824dc47e487b107a5db32ef43c4_dep.map @@ -0,0 +1,5 @@ + + + + + diff --git a/dir_d28a4824dc47e487b107a5db32ef43c4_dep.md5 b/dir_d28a4824dc47e487b107a5db32ef43c4_dep.md5 new file mode 100644 index 00000000..5580f58b --- /dev/null +++ b/dir_d28a4824dc47e487b107a5db32ef43c4_dep.md5 @@ -0,0 +1 @@ +dbaf728ccf1ad8afb7a971ae6be3e2c2 \ No newline at end of file diff --git a/dir_d28a4824dc47e487b107a5db32ef43c4_dep.png b/dir_d28a4824dc47e487b107a5db32ef43c4_dep.png new file mode 100644 index 00000000..b6ada0bd Binary files /dev/null and b/dir_d28a4824dc47e487b107a5db32ef43c4_dep.png differ diff --git a/dir_d44c64559bbebec7f509842c48db8b23.html b/dir_d44c64559bbebec7f509842c48db8b23.html new file mode 100644 index 00000000..0bb5ebef --- /dev/null +++ b/dir_d44c64559bbebec7f509842c48db8b23.html @@ -0,0 +1,92 @@ + + + + + + + +libfranka: include Directory Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
include Directory Reference
+
+
+ + +

+Directories

+
+ + + + diff --git a/dir_e68e8157741866f444e17edd764ebbae.html b/dir_e68e8157741866f444e17edd764ebbae.html new file mode 100644 index 00000000..4fef25cc --- /dev/null +++ b/dir_e68e8157741866f444e17edd764ebbae.html @@ -0,0 +1,88 @@ + + + + + + + +libfranka: doc Directory Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
doc Directory Reference
+
+
+
+ + + + diff --git a/doc.png b/doc.png new file mode 100644 index 00000000..17edabff Binary files /dev/null and b/doc.png differ diff --git a/doxygen.css b/doxygen.css new file mode 100644 index 00000000..ffbff022 --- /dev/null +++ b/doxygen.css @@ -0,0 +1,1793 @@ +/* The standard CSS for doxygen 1.9.1 */ + +body, table, div, p, dl { + font: 400 14px/22px Roboto,sans-serif; +} + +p.reference, p.definition { + font: 400 14px/22px Roboto,sans-serif; +} + +/* @group Heading Levels */ + +h1.groupheader { + font-size: 150%; +} + +.title { + font: 400 14px/28px Roboto,sans-serif; + font-size: 150%; + font-weight: bold; + margin: 10px 2px; +} + +h2.groupheader { + border-bottom: 1px solid #879ECB; + color: #354C7B; + font-size: 150%; + font-weight: normal; + margin-top: 1.75em; + padding-top: 8px; + padding-bottom: 4px; + width: 100%; +} + +h3.groupheader { + font-size: 100%; +} + +h1, h2, h3, h4, h5, h6 { + -webkit-transition: text-shadow 0.5s linear; + -moz-transition: text-shadow 0.5s linear; + -ms-transition: text-shadow 0.5s linear; + -o-transition: text-shadow 0.5s linear; + transition: text-shadow 0.5s linear; + margin-right: 15px; +} + +h1.glow, h2.glow, h3.glow, h4.glow, h5.glow, h6.glow { + text-shadow: 0 0 15px cyan; +} + +dt { + font-weight: bold; +} + +ul.multicol { + -moz-column-gap: 1em; + -webkit-column-gap: 1em; + column-gap: 1em; + -moz-column-count: 3; + -webkit-column-count: 3; + column-count: 3; +} + +p.startli, p.startdd { + margin-top: 2px; +} + +th p.starttd, th p.intertd, th p.endtd { + font-size: 100%; + font-weight: 700; +} + +p.starttd { + margin-top: 0px; +} + +p.endli { + margin-bottom: 0px; +} + +p.enddd { + margin-bottom: 4px; +} + +p.endtd { + margin-bottom: 2px; +} + +p.interli { +} + +p.interdd { +} + +p.intertd { +} + +/* @end */ + +caption { + font-weight: bold; +} + +span.legend { + font-size: 70%; + text-align: center; +} + +h3.version { + font-size: 90%; + text-align: center; +} + +div.navtab { + border-right: 1px solid #A3B4D7; + padding-right: 15px; + text-align: right; + line-height: 110%; +} + +div.navtab table { + border-spacing: 0; +} + +td.navtab { + padding-right: 6px; + padding-left: 6px; +} +td.navtabHL { + background-image: url('tab_a.png'); + background-repeat:repeat-x; + padding-right: 6px; + padding-left: 6px; +} + +td.navtabHL a, td.navtabHL a:visited { + color: #fff; + text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); +} + +a.navtab { + font-weight: bold; +} + +div.qindex{ + text-align: center; + width: 100%; + line-height: 140%; + font-size: 130%; + color: #A0A0A0; +} + +dt.alphachar{ + font-size: 180%; + font-weight: bold; +} + +.alphachar a{ + color: black; +} + +.alphachar a:hover, .alphachar a:visited{ + text-decoration: none; +} + +.classindex dl { + padding: 25px; + column-count:1 +} + +.classindex dd { + display:inline-block; + margin-left: 50px; + width: 90%; + line-height: 1.15em; +} + +.classindex dl.odd { + background-color: #F8F9FC; +} + +@media(min-width: 1120px) { + .classindex dl { + column-count:2 + } +} + +@media(min-width: 1320px) { + .classindex dl { + column-count:3 + } +} + + +/* @group Link Styling */ + +a { + color: #3D578C; + font-weight: normal; + text-decoration: none; +} + +.contents a:visited { + color: #4665A2; +} + +a:hover { + text-decoration: underline; +} + +.contents a.qindexHL:visited { + color: #FFFFFF; +} + +a.el { + font-weight: bold; +} + +a.elRef { +} + +a.code, a.code:visited, a.line, a.line:visited { + color: #4665A2; +} + +a.codeRef, a.codeRef:visited, a.lineRef, a.lineRef:visited { + color: #4665A2; +} + +/* @end */ + +dl.el { + margin-left: -1cm; +} + +ul { + overflow: hidden; /*Fixed: list item bullets overlap floating elements*/ +} + +#side-nav ul { + overflow: visible; /* reset ul rule for scroll bar in GENERATE_TREEVIEW window */ +} + +#main-nav ul { + overflow: visible; /* reset ul rule for the navigation bar drop down lists */ +} + +.fragment { + text-align: left; + direction: ltr; + overflow-x: auto; /*Fixed: fragment lines overlap floating elements*/ + overflow-y: hidden; +} + +pre.fragment { + border: 1px solid #C4CFE5; + background-color: #FBFCFD; + padding: 4px 6px; + margin: 4px 8px 4px 2px; + overflow: auto; + word-wrap: break-word; + font-size: 9pt; + line-height: 125%; + font-family: monospace, fixed; + font-size: 105%; +} + +div.fragment { + padding: 0 0 1px 0; /*Fixed: last line underline overlap border*/ + margin: 4px 8px 4px 2px; + background-color: #FBFCFD; + border: 1px solid #C4CFE5; +} + +div.line { + font-family: monospace, fixed; + font-size: 13px; + min-height: 13px; + line-height: 1.0; + text-wrap: unrestricted; + white-space: -moz-pre-wrap; /* Moz */ + white-space: -pre-wrap; /* Opera 4-6 */ + white-space: -o-pre-wrap; /* Opera 7 */ + white-space: pre-wrap; /* CSS3 */ + word-wrap: break-word; /* IE 5.5+ */ + text-indent: -53px; + padding-left: 53px; + padding-bottom: 0px; + margin: 0px; + -webkit-transition-property: background-color, box-shadow; + -webkit-transition-duration: 0.5s; + -moz-transition-property: background-color, box-shadow; + -moz-transition-duration: 0.5s; + -ms-transition-property: background-color, box-shadow; + -ms-transition-duration: 0.5s; + -o-transition-property: background-color, box-shadow; + -o-transition-duration: 0.5s; + transition-property: background-color, box-shadow; + transition-duration: 0.5s; +} + +div.line:after { + content:"\000A"; + white-space: pre; +} + +div.line.glow { + background-color: cyan; + box-shadow: 0 0 10px cyan; +} + + +span.lineno { + padding-right: 4px; + text-align: right; + border-right: 2px solid #0F0; + background-color: #E8E8E8; + white-space: pre; +} +span.lineno a { + background-color: #D8D8D8; +} + +span.lineno a:hover { + background-color: #C8C8C8; +} + +.lineno { + -webkit-touch-callout: none; + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; +} + +div.ah, span.ah { + background-color: black; + font-weight: bold; + color: #FFFFFF; + margin-bottom: 3px; + margin-top: 3px; + padding: 0.2em; + border: solid thin #333; + border-radius: 0.5em; + -webkit-border-radius: .5em; + -moz-border-radius: .5em; + box-shadow: 2px 2px 3px #999; + -webkit-box-shadow: 2px 2px 3px #999; + -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; + background-image: -webkit-gradient(linear, left top, left bottom, from(#eee), to(#000),color-stop(0.3, #444)); + background-image: -moz-linear-gradient(center top, #eee 0%, #444 40%, #000 110%); +} + +div.classindex ul { + list-style: none; + padding-left: 0; +} + +div.classindex span.ai { + display: inline-block; +} + +div.groupHeader { + margin-left: 16px; + margin-top: 12px; + font-weight: bold; +} + +div.groupText { + margin-left: 16px; + font-style: italic; +} + +body { + background-color: white; + color: black; + margin: 0; +} + +div.contents { + margin-top: 10px; + margin-left: 12px; + margin-right: 8px; +} + +td.indexkey { + background-color: #EBEFF6; + font-weight: bold; + border: 1px solid #C4CFE5; + margin: 2px 0px 2px 0; + padding: 2px 10px; + white-space: nowrap; + vertical-align: top; +} + +td.indexvalue { + background-color: #EBEFF6; + border: 1px solid #C4CFE5; + padding: 2px 10px; + margin: 2px 0px; +} + +tr.memlist { + background-color: #EEF1F7; +} + +p.formulaDsp { + text-align: center; +} + +img.formulaDsp { + +} + +img.formulaInl, img.inline { + vertical-align: middle; +} + +div.center { + text-align: center; + margin-top: 0px; + margin-bottom: 0px; + padding: 0px; +} + +div.center img { + border: 0px; +} + +address.footer { + text-align: right; + padding-right: 12px; +} + +img.footer { + border: 0px; + vertical-align: middle; +} + +/* @group Code Colorization */ + +span.keyword { + color: #008000 +} + +span.keywordtype { + color: #604020 +} + +span.keywordflow { + color: #e08000 +} + +span.comment { + color: #800000 +} + +span.preprocessor { + color: #806020 +} + +span.stringliteral { + color: #002080 +} + +span.charliteral { + color: #008080 +} + +span.vhdldigit { + color: #ff00ff +} + +span.vhdlchar { + color: #000000 +} + +span.vhdlkeyword { + color: #700070 +} + +span.vhdllogic { + color: #ff0000 +} + +blockquote { + background-color: #F7F8FB; + border-left: 2px solid #9CAFD4; + margin: 0 24px 0 4px; + padding: 0 12px 0 16px; +} + +blockquote.DocNodeRTL { + border-left: 0; + border-right: 2px solid #9CAFD4; + margin: 0 4px 0 24px; + padding: 0 16px 0 12px; +} + +/* @end */ + +/* +.search { + color: #003399; + font-weight: bold; +} + +form.search { + margin-bottom: 0px; + margin-top: 0px; +} + +input.search { + font-size: 75%; + color: #000080; + font-weight: normal; + background-color: #e8eef2; +} +*/ + +td.tiny { + font-size: 75%; +} + +.dirtab { + padding: 4px; + border-collapse: collapse; + border: 1px solid #A3B4D7; +} + +th.dirtab { + background: #EBEFF6; + font-weight: bold; +} + +hr { + height: 0px; + border: none; + border-top: 1px solid #4A6AAA; +} + +hr.footer { + height: 1px; +} + +/* @group Member Descriptions */ + +table.memberdecls { + border-spacing: 0px; + padding: 0px; +} + +.memberdecls td, .fieldtable tr { + -webkit-transition-property: background-color, box-shadow; + -webkit-transition-duration: 0.5s; + -moz-transition-property: background-color, box-shadow; + -moz-transition-duration: 0.5s; + -ms-transition-property: background-color, box-shadow; + -ms-transition-duration: 0.5s; + -o-transition-property: background-color, box-shadow; + -o-transition-duration: 0.5s; + transition-property: background-color, box-shadow; + transition-duration: 0.5s; +} + +.memberdecls td.glow, .fieldtable tr.glow { + background-color: cyan; + box-shadow: 0 0 15px cyan; +} + +.mdescLeft, .mdescRight, +.memItemLeft, .memItemRight, +.memTemplItemLeft, .memTemplItemRight, .memTemplParams { + background-color: #F9FAFC; + border: none; + margin: 4px; + padding: 1px 0 0 8px; +} + +.mdescLeft, .mdescRight { + padding: 0px 8px 4px 8px; + color: #555; +} + +.memSeparator { + border-bottom: 1px solid #DEE4F0; + line-height: 1px; + margin: 0px; + padding: 0px; +} + +.memItemLeft, .memTemplItemLeft { + white-space: nowrap; +} + +.memItemRight, .memTemplItemRight { + width: 100%; +} + +.memTemplParams { + color: #4665A2; + white-space: nowrap; + font-size: 80%; +} + +/* @end */ + +/* @group Member Details */ + +/* Styles for detailed member documentation */ + +.memtitle { + padding: 8px; + border-top: 1px solid #A8B8D9; + border-left: 1px solid #A8B8D9; + border-right: 1px solid #A8B8D9; + border-top-right-radius: 4px; + border-top-left-radius: 4px; + margin-bottom: -1px; + background-image: url('nav_f.png'); + background-repeat: repeat-x; + background-color: #E2E8F2; + line-height: 1.25; + font-weight: 300; + float:left; +} + +.permalink +{ + font-size: 65%; + display: inline-block; + vertical-align: middle; +} + +.memtemplate { + font-size: 80%; + color: #4665A2; + font-weight: normal; + margin-left: 9px; +} + +.memnav { + background-color: #EBEFF6; + border: 1px solid #A3B4D7; + text-align: center; + margin: 2px; + margin-right: 15px; + padding: 2px; +} + +.mempage { + width: 100%; +} + +.memitem { + padding: 0; + margin-bottom: 10px; + margin-right: 5px; + -webkit-transition: box-shadow 0.5s linear; + -moz-transition: box-shadow 0.5s linear; + -ms-transition: box-shadow 0.5s linear; + -o-transition: box-shadow 0.5s linear; + transition: box-shadow 0.5s linear; + display: table !important; + width: 100%; +} + +.memitem.glow { + box-shadow: 0 0 15px cyan; +} + +.memname { + font-weight: 400; + margin-left: 6px; +} + +.memname td { + vertical-align: bottom; +} + +.memproto, dl.reflist dt { + border-top: 1px solid #A8B8D9; + border-left: 1px solid #A8B8D9; + border-right: 1px solid #A8B8D9; + padding: 6px 0px 6px 0px; + color: #253555; + font-weight: bold; + text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); + background-color: #DFE5F1; + /* opera specific markup */ + box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + border-top-right-radius: 4px; + /* firefox specific markup */ + -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; + -moz-border-radius-topright: 4px; + /* webkit specific markup */ + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + -webkit-border-top-right-radius: 4px; + +} + +.overload { + font-family: "courier new",courier,monospace; + font-size: 65%; +} + +.memdoc, dl.reflist dd { + border-bottom: 1px solid #A8B8D9; + border-left: 1px solid #A8B8D9; + border-right: 1px solid #A8B8D9; + padding: 6px 10px 2px 10px; + background-color: #FBFCFD; + border-top-width: 0; + background-image:url('nav_g.png'); + background-repeat:repeat-x; + background-color: #FFFFFF; + /* opera specific markup */ + border-bottom-left-radius: 4px; + border-bottom-right-radius: 4px; + box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + /* firefox specific markup */ + -moz-border-radius-bottomleft: 4px; + -moz-border-radius-bottomright: 4px; + -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; + /* webkit specific markup */ + -webkit-border-bottom-left-radius: 4px; + -webkit-border-bottom-right-radius: 4px; + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); +} + +dl.reflist dt { + padding: 5px; +} + +dl.reflist dd { + margin: 0px 0px 10px 0px; + padding: 5px; +} + +.paramkey { + text-align: right; +} + +.paramtype { + white-space: nowrap; +} + +.paramname { + color: #602020; + white-space: nowrap; +} +.paramname em { + font-style: normal; +} +.paramname code { + line-height: 14px; +} + +.params, .retval, .exception, .tparams { + margin-left: 0px; + padding-left: 0px; +} + +.params .paramname, .retval .paramname, .tparams .paramname, .exception .paramname { + font-weight: bold; + vertical-align: top; +} + +.params .paramtype, .tparams .paramtype { + font-style: italic; + vertical-align: top; +} + +.params .paramdir, .tparams .paramdir { + font-family: "courier new",courier,monospace; + vertical-align: top; +} + +table.mlabels { + border-spacing: 0px; +} + +td.mlabels-left { + width: 100%; + padding: 0px; +} + +td.mlabels-right { + vertical-align: bottom; + padding: 0px; + white-space: nowrap; +} + +span.mlabels { + margin-left: 8px; +} + +span.mlabel { + background-color: #728DC1; + border-top:1px solid #5373B4; + border-left:1px solid #5373B4; + border-right:1px solid #C4CFE5; + border-bottom:1px solid #C4CFE5; + text-shadow: none; + color: white; + margin-right: 4px; + padding: 2px 3px; + border-radius: 3px; + font-size: 7pt; + white-space: nowrap; + vertical-align: middle; +} + + + +/* @end */ + +/* these are for tree view inside a (index) page */ + +div.directory { + margin: 10px 0px; + border-top: 1px solid #9CAFD4; + border-bottom: 1px solid #9CAFD4; + width: 100%; +} + +.directory table { + border-collapse:collapse; +} + +.directory td { + margin: 0px; + padding: 0px; + vertical-align: top; +} + +.directory td.entry { + white-space: nowrap; + padding-right: 6px; + padding-top: 3px; +} + +.directory td.entry a { + outline:none; +} + +.directory td.entry a img { + border: none; +} + +.directory td.desc { + width: 100%; + padding-left: 6px; + padding-right: 6px; + padding-top: 3px; + border-left: 1px solid rgba(0,0,0,0.05); +} + +.directory tr.even { + padding-left: 6px; + background-color: #F7F8FB; +} + +.directory img { + vertical-align: -30%; +} + +.directory .levels { + white-space: nowrap; + width: 100%; + text-align: right; + font-size: 9pt; +} + +.directory .levels span { + cursor: pointer; + padding-left: 2px; + padding-right: 2px; + color: #3D578C; +} + +.arrow { + color: #9CAFD4; + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; + cursor: pointer; + font-size: 80%; + display: inline-block; + width: 16px; + height: 22px; +} + +.icon { + font-family: Arial, Helvetica; + font-weight: bold; + font-size: 12px; + height: 14px; + width: 16px; + display: inline-block; + background-color: #728DC1; + color: white; + text-align: center; + border-radius: 4px; + margin-left: 2px; + margin-right: 2px; +} + +.icona { + width: 24px; + height: 22px; + display: inline-block; +} + +.iconfopen { + width: 24px; + height: 18px; + margin-bottom: 4px; + background-image:url('folderopen.png'); + background-position: 0px -4px; + background-repeat: repeat-y; + vertical-align:top; + display: inline-block; +} + +.iconfclosed { + width: 24px; + height: 18px; + margin-bottom: 4px; + background-image:url('folderclosed.png'); + background-position: 0px -4px; + background-repeat: repeat-y; + vertical-align:top; + display: inline-block; +} + +.icondoc { + width: 24px; + height: 18px; + margin-bottom: 4px; + background-image:url('doc.png'); + background-position: 0px -4px; + background-repeat: repeat-y; + vertical-align:top; + display: inline-block; +} + +table.directory { + font: 400 14px Roboto,sans-serif; +} + +/* @end */ + +div.dynheader { + margin-top: 8px; + -webkit-touch-callout: none; + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; +} + +address { + font-style: normal; + color: #2A3D61; +} + +table.doxtable caption { + caption-side: top; +} + +table.doxtable { + border-collapse:collapse; + margin-top: 4px; + margin-bottom: 4px; +} + +table.doxtable td, table.doxtable th { + border: 1px solid #2D4068; + padding: 3px 7px 2px; +} + +table.doxtable th { + background-color: #374F7F; + color: #FFFFFF; + font-size: 110%; + padding-bottom: 4px; + padding-top: 5px; +} + +table.fieldtable { + /*width: 100%;*/ + margin-bottom: 10px; + border: 1px solid #A8B8D9; + border-spacing: 0px; + -moz-border-radius: 4px; + -webkit-border-radius: 4px; + border-radius: 4px; + -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; + -webkit-box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); + box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); +} + +.fieldtable td, .fieldtable th { + padding: 3px 7px 2px; +} + +.fieldtable td.fieldtype, .fieldtable td.fieldname { + white-space: nowrap; + border-right: 1px solid #A8B8D9; + border-bottom: 1px solid #A8B8D9; + vertical-align: top; +} + +.fieldtable td.fieldname { + padding-top: 3px; +} + +.fieldtable td.fielddoc { + border-bottom: 1px solid #A8B8D9; + /*width: 100%;*/ +} + +.fieldtable td.fielddoc p:first-child { + margin-top: 0px; +} + +.fieldtable td.fielddoc p:last-child { + margin-bottom: 2px; +} + +.fieldtable tr:last-child td { + border-bottom: none; +} + +.fieldtable th { + background-image:url('nav_f.png'); + background-repeat:repeat-x; + background-color: #E2E8F2; + font-size: 90%; + color: #253555; + padding-bottom: 4px; + padding-top: 5px; + text-align:left; + font-weight: 400; + -moz-border-radius-topleft: 4px; + -moz-border-radius-topright: 4px; + -webkit-border-top-left-radius: 4px; + -webkit-border-top-right-radius: 4px; + border-top-left-radius: 4px; + border-top-right-radius: 4px; + border-bottom: 1px solid #A8B8D9; +} + + +.tabsearch { + top: 0px; + left: 10px; + height: 36px; + background-image: url('tab_b.png'); + z-index: 101; + overflow: hidden; + font-size: 13px; +} + +.navpath ul +{ + font-size: 11px; + background-image:url('tab_b.png'); + background-repeat:repeat-x; + background-position: 0 -5px; + height:30px; + line-height:30px; + color:#8AA0CC; + border:solid 1px #C2CDE4; + overflow:hidden; + margin:0px; + padding:0px; +} + +.navpath li +{ + list-style-type:none; + float:left; + padding-left:10px; + padding-right:15px; + background-image:url('bc_s.png'); + background-repeat:no-repeat; + background-position:right; + color:#364D7C; +} + +.navpath li.navelem a +{ + height:32px; + display:block; + text-decoration: none; + outline: none; + color: #283A5D; + font-family: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; + text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); + text-decoration: none; +} + +.navpath li.navelem a:hover +{ + color:#6884BD; +} + +.navpath li.footer +{ + list-style-type:none; + float:right; + padding-left:10px; + padding-right:15px; + background-image:none; + background-repeat:no-repeat; + background-position:right; + color:#364D7C; + font-size: 8pt; +} + + +div.summary +{ + float: right; + font-size: 8pt; + padding-right: 5px; + width: 50%; + text-align: right; +} + +div.summary a +{ + white-space: nowrap; +} + +table.classindex +{ + margin: 10px; + white-space: nowrap; + margin-left: 3%; + margin-right: 3%; + width: 94%; + border: 0; + border-spacing: 0; + padding: 0; +} + +div.ingroups +{ + font-size: 8pt; + width: 50%; + text-align: left; +} + +div.ingroups a +{ + white-space: nowrap; +} + +div.header +{ + background-image:url('nav_h.png'); + background-repeat:repeat-x; + background-color: #F9FAFC; + margin: 0px; + border-bottom: 1px solid #C4CFE5; +} + +div.headertitle +{ + padding: 5px 5px 5px 10px; +} + +.PageDocRTL-title div.headertitle { + text-align: right; + direction: rtl; +} + +dl { + padding: 0 0 0 0; +} + +/* dl.note, dl.warning, dl.attention, dl.pre, dl.post, dl.invariant, dl.deprecated, dl.todo, dl.test, dl.bug, dl.examples */ +dl.section { + margin-left: 0px; + padding-left: 0px; +} + +dl.section.DocNodeRTL { + margin-right: 0px; + padding-right: 0px; +} + +dl.note { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #D0C000; +} + +dl.note.DocNodeRTL { + margin-left: 0; + padding-left: 0; + border-left: 0; + margin-right: -7px; + padding-right: 3px; + border-right: 4px solid; + border-color: #D0C000; +} + +dl.warning, dl.attention { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #FF0000; +} + +dl.warning.DocNodeRTL, dl.attention.DocNodeRTL { + margin-left: 0; + padding-left: 0; + border-left: 0; + margin-right: -7px; + padding-right: 3px; + border-right: 4px solid; + border-color: #FF0000; +} + +dl.pre, dl.post, dl.invariant { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #00D000; +} + +dl.pre.DocNodeRTL, dl.post.DocNodeRTL, dl.invariant.DocNodeRTL { + margin-left: 0; + padding-left: 0; + border-left: 0; + margin-right: -7px; + padding-right: 3px; + border-right: 4px solid; + border-color: #00D000; +} + +dl.deprecated { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #505050; +} + +dl.deprecated.DocNodeRTL { + margin-left: 0; + padding-left: 0; + border-left: 0; + margin-right: -7px; + padding-right: 3px; + border-right: 4px solid; + border-color: #505050; +} + +dl.todo { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #00C0E0; +} + +dl.todo.DocNodeRTL { + margin-left: 0; + padding-left: 0; + border-left: 0; + margin-right: -7px; + padding-right: 3px; + border-right: 4px solid; + border-color: #00C0E0; +} + +dl.test { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #3030E0; +} + +dl.test.DocNodeRTL { + margin-left: 0; + padding-left: 0; + border-left: 0; + margin-right: -7px; + padding-right: 3px; + border-right: 4px solid; + border-color: #3030E0; +} + +dl.bug { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #C08050; +} + +dl.bug.DocNodeRTL { + margin-left: 0; + padding-left: 0; + border-left: 0; + margin-right: -7px; + padding-right: 3px; + border-right: 4px solid; + border-color: #C08050; +} + +dl.section dd { + margin-bottom: 6px; +} + + +#projectlogo +{ + text-align: center; + vertical-align: bottom; + border-collapse: separate; +} + +#projectlogo img +{ + border: 0px none; +} + +#projectalign +{ + vertical-align: middle; +} + +#projectname +{ + font: 300% Tahoma, Arial,sans-serif; + margin: 0px; + padding: 2px 0px; +} + +#projectbrief +{ + font: 120% Tahoma, Arial,sans-serif; + margin: 0px; + padding: 0px; +} + +#projectnumber +{ + font: 50% Tahoma, Arial,sans-serif; + margin: 0px; + padding: 0px; +} + +#titlearea +{ + padding: 0px; + margin: 0px; + width: 100%; + border-bottom: 1px solid #5373B4; +} + +.image +{ + text-align: center; +} + +.dotgraph +{ + text-align: center; +} + +.mscgraph +{ + text-align: center; +} + +.plantumlgraph +{ + text-align: center; +} + +.diagraph +{ + text-align: center; +} + +.caption +{ + font-weight: bold; +} + +div.zoom +{ + border: 1px solid #90A5CE; +} + +dl.citelist { + margin-bottom:50px; +} + +dl.citelist dt { + color:#334975; + float:left; + font-weight:bold; + margin-right:10px; + padding:5px; + text-align:right; + width:52px; +} + +dl.citelist dd { + margin:2px 0 2px 72px; + padding:5px 0; +} + +div.toc { + padding: 14px 25px; + background-color: #F4F6FA; + border: 1px solid #D8DFEE; + border-radius: 7px 7px 7px 7px; + float: right; + height: auto; + margin: 0 8px 10px 10px; + width: 200px; +} + +.PageDocRTL-title div.toc { + float: left !important; + text-align: right; +} + +div.toc li { + background: url("bdwn.png") no-repeat scroll 0 5px transparent; + font: 10px/1.2 Verdana,DejaVu Sans,Geneva,sans-serif; + margin-top: 5px; + padding-left: 10px; + padding-top: 2px; +} + +.PageDocRTL-title div.toc li { + background-position-x: right !important; + padding-left: 0 !important; + padding-right: 10px; +} + +div.toc h3 { + font: bold 12px/1.2 Arial,FreeSans,sans-serif; + color: #4665A2; + border-bottom: 0 none; + margin: 0; +} + +div.toc ul { + list-style: none outside none; + border: medium none; + padding: 0px; +} + +div.toc li.level1 { + margin-left: 0px; +} + +div.toc li.level2 { + margin-left: 15px; +} + +div.toc li.level3 { + margin-left: 30px; +} + +div.toc li.level4 { + margin-left: 45px; +} + +span.emoji { + /* font family used at the site: https://unicode.org/emoji/charts/full-emoji-list.html + * font-family: "Noto Color Emoji", "Apple Color Emoji", "Segoe UI Emoji", Times, Symbola, Aegyptus, Code2000, Code2001, Code2002, Musica, serif, LastResort; + */ +} + +.PageDocRTL-title div.toc li.level1 { + margin-left: 0 !important; + margin-right: 0; +} + +.PageDocRTL-title div.toc li.level2 { + margin-left: 0 !important; + margin-right: 15px; +} + +.PageDocRTL-title div.toc li.level3 { + margin-left: 0 !important; + margin-right: 30px; +} + +.PageDocRTL-title div.toc li.level4 { + margin-left: 0 !important; + margin-right: 45px; +} + +.inherit_header { + font-weight: bold; + color: gray; + cursor: pointer; + -webkit-touch-callout: none; + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; +} + +.inherit_header td { + padding: 6px 0px 2px 5px; +} + +.inherit { + display: none; +} + +tr.heading h2 { + margin-top: 12px; + margin-bottom: 4px; +} + +/* tooltip related style info */ + +.ttc { + position: absolute; + display: none; +} + +#powerTip { + cursor: default; + white-space: nowrap; + background-color: white; + border: 1px solid gray; + border-radius: 4px 4px 4px 4px; + box-shadow: 1px 1px 7px gray; + display: none; + font-size: smaller; + max-width: 80%; + opacity: 0.9; + padding: 1ex 1em 1em; + position: absolute; + z-index: 2147483647; +} + +#powerTip div.ttdoc { + color: grey; + font-style: italic; +} + +#powerTip div.ttname a { + font-weight: bold; +} + +#powerTip div.ttname { + font-weight: bold; +} + +#powerTip div.ttdeci { + color: #006318; +} + +#powerTip div { + margin: 0px; + padding: 0px; + font: 12px/16px Roboto,sans-serif; +} + +#powerTip:before, #powerTip:after { + content: ""; + position: absolute; + margin: 0px; +} + +#powerTip.n:after, #powerTip.n:before, +#powerTip.s:after, #powerTip.s:before, +#powerTip.w:after, #powerTip.w:before, +#powerTip.e:after, #powerTip.e:before, +#powerTip.ne:after, #powerTip.ne:before, +#powerTip.se:after, #powerTip.se:before, +#powerTip.nw:after, #powerTip.nw:before, +#powerTip.sw:after, #powerTip.sw:before { + border: solid transparent; + content: " "; + height: 0; + width: 0; + position: absolute; +} + +#powerTip.n:after, #powerTip.s:after, +#powerTip.w:after, #powerTip.e:after, +#powerTip.nw:after, #powerTip.ne:after, +#powerTip.sw:after, #powerTip.se:after { + border-color: rgba(255, 255, 255, 0); +} + +#powerTip.n:before, #powerTip.s:before, +#powerTip.w:before, #powerTip.e:before, +#powerTip.nw:before, #powerTip.ne:before, +#powerTip.sw:before, #powerTip.se:before { + border-color: rgba(128, 128, 128, 0); +} + +#powerTip.n:after, #powerTip.n:before, +#powerTip.ne:after, #powerTip.ne:before, +#powerTip.nw:after, #powerTip.nw:before { + top: 100%; +} + +#powerTip.n:after, #powerTip.ne:after, #powerTip.nw:after { + border-top-color: #FFFFFF; + border-width: 10px; + margin: 0px -10px; +} +#powerTip.n:before { + border-top-color: #808080; + border-width: 11px; + margin: 0px -11px; +} +#powerTip.n:after, #powerTip.n:before { + left: 50%; +} + +#powerTip.nw:after, #powerTip.nw:before { + right: 14px; +} + +#powerTip.ne:after, #powerTip.ne:before { + left: 14px; +} + +#powerTip.s:after, #powerTip.s:before, +#powerTip.se:after, #powerTip.se:before, +#powerTip.sw:after, #powerTip.sw:before { + bottom: 100%; +} + +#powerTip.s:after, #powerTip.se:after, #powerTip.sw:after { + border-bottom-color: #FFFFFF; + border-width: 10px; + margin: 0px -10px; +} + +#powerTip.s:before, #powerTip.se:before, #powerTip.sw:before { + border-bottom-color: #808080; + border-width: 11px; + margin: 0px -11px; +} + +#powerTip.s:after, #powerTip.s:before { + left: 50%; +} + +#powerTip.sw:after, #powerTip.sw:before { + right: 14px; +} + +#powerTip.se:after, #powerTip.se:before { + left: 14px; +} + +#powerTip.e:after, #powerTip.e:before { + left: 100%; +} +#powerTip.e:after { + border-left-color: #FFFFFF; + border-width: 10px; + top: 50%; + margin-top: -10px; +} +#powerTip.e:before { + border-left-color: #808080; + border-width: 11px; + top: 50%; + margin-top: -11px; +} + +#powerTip.w:after, #powerTip.w:before { + right: 100%; +} +#powerTip.w:after { + border-right-color: #FFFFFF; + border-width: 10px; + top: 50%; + margin-top: -10px; +} +#powerTip.w:before { + border-right-color: #808080; + border-width: 11px; + top: 50%; + margin-top: -11px; +} + +@media print +{ + #top { display: none; } + #side-nav { display: none; } + #nav-path { display: none; } + body { overflow:visible; } + h1, h2, h3, h4, h5, h6 { page-break-after: avoid; } + .summary { display: none; } + .memitem { page-break-inside: avoid; } + #doc-content + { + margin-left:0 !important; + height:auto !important; + width:auto !important; + overflow:inherit; + display:inline; + } +} + +/* @group Markdown */ + +table.markdownTable { + border-collapse:collapse; + margin-top: 4px; + margin-bottom: 4px; +} + +table.markdownTable td, table.markdownTable th { + border: 1px solid #2D4068; + padding: 3px 7px 2px; +} + +table.markdownTable tr { +} + +th.markdownTableHeadLeft, th.markdownTableHeadRight, th.markdownTableHeadCenter, th.markdownTableHeadNone { + background-color: #374F7F; + color: #FFFFFF; + font-size: 110%; + padding-bottom: 4px; + padding-top: 5px; +} + +th.markdownTableHeadLeft, td.markdownTableBodyLeft { + text-align: left +} + +th.markdownTableHeadRight, td.markdownTableBodyRight { + text-align: right +} + +th.markdownTableHeadCenter, td.markdownTableBodyCenter { + text-align: center +} + +.DocNodeRTL { + text-align: right; + direction: rtl; +} + +.DocNodeLTR { + text-align: left; + direction: ltr; +} + +table.DocNodeRTL { + width: auto; + margin-right: 0; + margin-left: auto; +} + +table.DocNodeLTR { + width: auto; + margin-right: auto; + margin-left: 0; +} + +tt, code, kbd, samp +{ + display: inline-block; + direction:ltr; +} +/* @end */ + +u { + text-decoration: underline; +} + diff --git a/doxygen.svg b/doxygen.svg new file mode 100644 index 00000000..d42dad52 --- /dev/null +++ b/doxygen.svg @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/duration_8h.html b/duration_8h.html new file mode 100644 index 00000000..9701ebb4 --- /dev/null +++ b/duration_8h.html @@ -0,0 +1,194 @@ + + + + + + + +libfranka: include/franka/duration.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+Classes | +Functions
+
+
duration.h File Reference
+
+
+ +

Contains the franka::Duration type. +More...

+
#include <chrono>
+#include <cstdint>
+#include <ratio>
+
+Include dependency graph for duration.h:
+
+
+ + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  franka::Duration
 Represents a duration with millisecond resolution. More...
 
+ + + + +

+Functions

Duration franka::operator* (uint64_t lhs, const Duration &rhs) noexcept
 Performs multiplication. More...
 
+

Detailed Description

+

Contains the franka::Duration type.

+

Function Documentation

+ +

◆ operator*()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
Duration franka::operator* (uint64_t lhs,
const Durationrhs 
)
+
+noexcept
+
+ +

Performs multiplication.

+
Parameters
+ + + +
[in]lhsLeft-hand side of the multiplication.
[in]rhsRight-hand side of the multiplication.
+
+
+
Returns
Result of the multiplication.
+ +
+
+
+ + + + diff --git a/duration_8h__dep__incl.map b/duration_8h__dep__incl.map new file mode 100644 index 00000000..1b334f46 --- /dev/null +++ b/duration_8h__dep__incl.map @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/duration_8h__dep__incl.md5 b/duration_8h__dep__incl.md5 new file mode 100644 index 00000000..3e14ebbb --- /dev/null +++ b/duration_8h__dep__incl.md5 @@ -0,0 +1 @@ +2419ea66674e4bc3b2d7066dd96a693e \ No newline at end of file diff --git a/duration_8h__dep__incl.png b/duration_8h__dep__incl.png new file mode 100644 index 00000000..9de4eabf Binary files /dev/null and b/duration_8h__dep__incl.png differ diff --git a/duration_8h__incl.map b/duration_8h__incl.map new file mode 100644 index 00000000..601f0873 --- /dev/null +++ b/duration_8h__incl.map @@ -0,0 +1,6 @@ + + + + + + diff --git a/duration_8h__incl.md5 b/duration_8h__incl.md5 new file mode 100644 index 00000000..6291b3a5 --- /dev/null +++ b/duration_8h__incl.md5 @@ -0,0 +1 @@ +17d6f6b2b66c0cba191e8e5ca030e1d5 \ No newline at end of file diff --git a/duration_8h__incl.png b/duration_8h__incl.png new file mode 100644 index 00000000..ff73d48a Binary files /dev/null and b/duration_8h__incl.png differ diff --git a/duration_8h_source.html b/duration_8h_source.html new file mode 100644 index 00000000..92ba78c7 --- /dev/null +++ b/duration_8h_source.html @@ -0,0 +1,154 @@ + + + + + + + +libfranka: include/franka/duration.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
duration.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <chrono>
+
6 #include <cstdint>
+
7 #include <ratio>
+
8 
+
14 namespace franka {
+
15 
+
19 class Duration {
+
20  public:
+
24  Duration() noexcept;
+
25 
+
31  explicit Duration(uint64_t milliseconds) noexcept;
+
32 
+
38  Duration(std::chrono::duration<uint64_t, std::milli> duration) noexcept;
+
39 
+
43  Duration(const Duration&) = default;
+
44 
+
50  Duration& operator=(const Duration&) = default;
+
51 
+
57  operator std::chrono::duration<uint64_t, std::milli>() const noexcept;
+
58 
+
64  double toSec() const noexcept;
+
65 
+
71  uint64_t toMSec() const noexcept;
+
72 
+
85  Duration operator+(const Duration& rhs) const noexcept;
+
93  Duration& operator+=(const Duration& rhs) noexcept;
+
94 
+
102  Duration operator-(const Duration& rhs) const noexcept;
+
110  Duration& operator-=(const Duration& rhs) noexcept;
+
111 
+
119  Duration operator*(uint64_t rhs) const noexcept;
+
127  Duration& operator*=(uint64_t rhs) noexcept;
+
128 
+
136  uint64_t operator/(const Duration& rhs) const noexcept;
+
144  Duration operator/(uint64_t rhs) const noexcept;
+
152  Duration& operator/=(uint64_t rhs) noexcept;
+
153 
+
161  Duration operator%(const Duration& rhs) const noexcept;
+
169  Duration operator%(uint64_t rhs) const noexcept;
+
177  Duration& operator%=(const Duration& rhs) noexcept;
+
185  Duration& operator%=(uint64_t rhs) noexcept;
+
186 
+
203  bool operator==(const Duration& rhs) const noexcept;
+
211  bool operator!=(const Duration& rhs) const noexcept;
+
212 
+
220  bool operator<(const Duration& rhs) const noexcept;
+
228  bool operator<=(const Duration& rhs) const noexcept;
+
229 
+
237  bool operator>(const Duration& rhs) const noexcept;
+
245  bool operator>=(const Duration& rhs) const noexcept;
+
246 
+
251  private:
+
252  std::chrono::duration<uint64_t, std::milli> duration_;
+
253 };
+
254 
+
263 Duration operator*(uint64_t lhs, const Duration& rhs) noexcept;
+
264 
+
265 } // namespace franka
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
uint64_t toMSec() const noexcept
Returns the stored duration in .
+
double toSec() const noexcept
Returns the stored duration in .
+
Duration() noexcept
Creates a new Duration instance with zero milliseconds.
+
+ + + + diff --git a/dynsections.js b/dynsections.js new file mode 100644 index 00000000..3174bd7b --- /dev/null +++ b/dynsections.js @@ -0,0 +1,121 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file + */ +function toggleVisibility(linkObj) +{ + var base = $(linkObj).attr('id'); + var summary = $('#'+base+'-summary'); + var content = $('#'+base+'-content'); + var trigger = $('#'+base+'-trigger'); + var src=$(trigger).attr('src'); + if (content.is(':visible')===true) { + content.hide(); + summary.show(); + $(linkObj).addClass('closed').removeClass('opened'); + $(trigger).attr('src',src.substring(0,src.length-8)+'closed.png'); + } else { + content.show(); + summary.hide(); + $(linkObj).removeClass('closed').addClass('opened'); + $(trigger).attr('src',src.substring(0,src.length-10)+'open.png'); + } + return false; +} + +function updateStripes() +{ + $('table.directory tr'). + removeClass('even').filter(':visible:even').addClass('even'); +} + +function toggleLevel(level) +{ + $('table.directory tr').each(function() { + var l = this.id.split('_').length-1; + var i = $('#img'+this.id.substring(3)); + var a = $('#arr'+this.id.substring(3)); + if (l + + + + + + +libfranka: echo_robot_state.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
echo_robot_state.cpp
+
+
+

An example showing how to continuously read the robot state.

+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <iostream>
+
+ +
#include <franka/robot.h>
+
+
int main(int argc, char** argv) {
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
+
try {
+
franka::Robot robot(argv[1]);
+
+
size_t count = 0;
+
robot.read([&count](const franka::RobotState& robot_state) {
+
// Printing to std::cout adds a delay. This is acceptable for a read loop such as this, but
+
// should not be done in a control loop.
+
std::cout << robot_state << std::endl;
+
return count++ < 100;
+
});
+
+
std::cout << "Done." << std::endl;
+
} catch (franka::Exception const& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void read(std::function< bool(const RobotState &)> read_callback)
Starts a loop for reading the current robot state.
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/errors_8h.html b/errors_8h.html new file mode 100644 index 00000000..c0e530de --- /dev/null +++ b/errors_8h.html @@ -0,0 +1,182 @@ + + + + + + + +libfranka: include/franka/errors.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+ +
+
errors.h File Reference
+
+
+ +

Contains the franka::Errors type. +More...

+
#include <array>
+#include <ostream>
+
+Include dependency graph for errors.h:
+
+
+ + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

struct  franka::Errors
 Enumerates errors that can occur while controlling a franka::Robot. More...
 
+ + + + +

+Functions

std::ostream & franka::operator<< (std::ostream &ostream, const Errors &errors)
 Streams the errors as JSON array. More...
 
+

Detailed Description

+

Contains the franka::Errors type.

+

Function Documentation

+ +

◆ operator<<()

+ +
+
+ + + + + + + + + + + + + + + + + + +
std::ostream& franka::operator<< (std::ostream & ostream,
const Errorserrors 
)
+
+ +

Streams the errors as JSON array.

+
Parameters
+ + + +
[in]ostreamOstream instance
[in]errorsErrors struct instance to stream
+
+
+
Returns
Ostream instance
+
Examples
joint_impedance_control.cpp, and print_joint_poses.cpp.
+
+ +
+
+
+ + + + diff --git a/errors_8h__dep__incl.map b/errors_8h__dep__incl.map new file mode 100644 index 00000000..d4c26bdd --- /dev/null +++ b/errors_8h__dep__incl.map @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/errors_8h__dep__incl.md5 b/errors_8h__dep__incl.md5 new file mode 100644 index 00000000..c68b6158 --- /dev/null +++ b/errors_8h__dep__incl.md5 @@ -0,0 +1 @@ +ae1c8cd80573cbcca5d80dc0c9cb59e1 \ No newline at end of file diff --git a/errors_8h__dep__incl.png b/errors_8h__dep__incl.png new file mode 100644 index 00000000..62c6e155 Binary files /dev/null and b/errors_8h__dep__incl.png differ diff --git a/errors_8h__incl.map b/errors_8h__incl.map new file mode 100644 index 00000000..fca5a0a0 --- /dev/null +++ b/errors_8h__incl.map @@ -0,0 +1,5 @@ + + + + + diff --git a/errors_8h__incl.md5 b/errors_8h__incl.md5 new file mode 100644 index 00000000..46fb1616 --- /dev/null +++ b/errors_8h__incl.md5 @@ -0,0 +1 @@ +126f684209a4eb6c33d6469d1dee996f \ No newline at end of file diff --git a/errors_8h__incl.png b/errors_8h__incl.png new file mode 100644 index 00000000..04dad9ed Binary files /dev/null and b/errors_8h__incl.png differ diff --git a/errors_8h_source.html b/errors_8h_source.html new file mode 100644 index 00000000..c5698887 --- /dev/null +++ b/errors_8h_source.html @@ -0,0 +1,206 @@ + + + + + + + +libfranka: include/franka/errors.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
errors.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <array>
+
6 #include <ostream>
+
7 
+
13 namespace franka {
+
14 
+
18 struct Errors {
+
19  private:
+
20  std::array<bool, 41> errors_{};
+
21 
+
22  public:
+
26  Errors();
+
27 
+
33  Errors(const Errors& other);
+
34 
+ +
43 
+
49  Errors(const std::array<bool, 41>& errors);
+
50 
+
56  explicit operator bool() const noexcept;
+
57 
+
65  explicit operator std::string() const;
+
66 
+ + + + + + +
95  const bool& joint_reflex;
+
100  const bool& cartesian_reflex;
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
224  const bool& instability_detected;
+ + + + + +
246 };
+
247 
+
256 std::ostream& operator<<(std::ostream& ostream, const Errors& errors);
+
257 
+
258 } // namespace franka
+
Enumerates errors that can occur while controlling a franka::Robot.
Definition: errors.h:18
+
const bool & cartesian_motion_generator_acceleration_discontinuity
True if commanded acceleration in Cartesian motion generators is discontinuous (target values are too...
Definition: errors.h:158
+
const bool & tau_j_range_violation
True if the measured torque signal is out of the safe range.
Definition: errors.h:220
+
const bool & cartesian_motion_generator_velocity_discontinuity
True if commanded velocity in Cartesian motion generators is discontinuous (target values are too far...
Definition: errors.h:153
+
const bool & joint_p2p_insufficient_torque_for_planning
True if the robot is overloaded for the required motion.
Definition: errors.h:216
+
const bool & cartesian_motion_generator_joint_velocity_discontinuity
True if the joint velocity in Cartesian motion generators is discontinuous after IK calculation.
Definition: errors.h:179
+
const bool & cartesian_motion_generator_joint_acceleration_discontinuity
True if the joint acceleration in Cartesian motion generators is discontinuous after IK calculation.
Definition: errors.h:184
+
const bool & cartesian_velocity_violation
True if the robot exceeded Cartesian velocity limits.
Definition: errors.h:86
+
const bool & cartesian_position_limits_violation
True if the robot moved past any of the virtual walls.
Definition: errors.h:74
+
const bool & cartesian_motion_generator_joint_velocity_limits_violation
True if the joint velocity limits would be exceeded after IK calculation.
Definition: errors.h:174
+
const bool & joint_position_limits_violation
True if the robot moved past the joint limits.
Definition: errors.h:70
+
Errors(const Errors &other)
Copy constructs a new Errors instance.
+
const bool & cartesian_reflex
True if a collision was detected, i.e. the robot exceeded a torque threshold in a Cartesian motion.
Definition: errors.h:100
+
const bool & communication_constraints_violation
True if minimum network communication quality could not be held during a motion.
Definition: errors.h:206
+
const bool & base_acceleration_initialization_timeout
True if the gravity vector could not be initialized by measureing the base acceleration.
Definition: errors.h:241
+
const bool & cartesian_spline_motion_generator_violation
True if the generated motion violates a joint limit.
Definition: errors.h:233
+
const bool & cartesian_motion_generator_elbow_sign_inconsistent
True if commanded elbow values in Cartesian motion generators are inconsistent.
Definition: errors.h:162
+
const bool & joint_motion_generator_acceleration_discontinuity
True if commanded acceleration in joint motion generators is discontinuous (target values are too far...
Definition: errors.h:135
+
const bool & power_limit_violation
True if commanded values would result in exceeding the power limit.
Definition: errors.h:210
+
const bool & cartesian_motion_generator_start_elbow_invalid
True if the first elbow value in Cartesian motion generators is too far from initial one.
Definition: errors.h:166
+
Errors & operator=(Errors other)
Assigns this Errors instance from another Errors value.
+
const bool & cartesian_motion_generator_joint_position_limits_violation
True if the joint position limits would be exceeded after IK calculation.
Definition: errors.h:170
+
const bool & joint_position_motion_generator_start_pose_invalid
True if an external joint position motion generator was started with a pose too far from the current ...
Definition: errors.h:117
+
const bool & joint_move_in_wrong_direction
True if the robot is in joint position limits violation error and the user guides the robot further t...
Definition: errors.h:229
+
const bool & joint_velocity_violation
True if the robot exceeded joint velocity limits.
Definition: errors.h:82
+
const bool & base_acceleration_invalid_reading
True if the base acceleration O_ddP_O cannot be determined.
Definition: errors.h:245
+
const bool & cartesian_motion_generator_velocity_limits_violation
True if an external Cartesian motion generator would move with too high velocity.
Definition: errors.h:148
+
const bool & joint_motion_generator_position_limits_violation
True if an external joint motion generator would move into a joint limit.
Definition: errors.h:121
+
const bool & cartesian_position_motion_generator_invalid_frame
True if the Cartesian pose is not a valid transformation matrix.
Definition: errors.h:188
+
const bool & start_elbow_sign_inconsistent
True if the start elbow sign was inconsistent.
Definition: errors.h:202
+
const bool & cartesian_position_motion_generator_start_pose_invalid
True if an external Cartesian position motion generator was started with a pose too far from the curr...
Definition: errors.h:140
+
const bool & joint_motion_generator_velocity_discontinuity
True if commanded velocity in joint motion generators is discontinuous (target values are too far apa...
Definition: errors.h:130
+
const bool & cartesian_motion_generator_elbow_limit_violation
True if an external Cartesian motion generator would move into an elbow limit.
Definition: errors.h:144
+
const bool & max_goal_pose_deviation_violation
True if internal motion generator did not reach the goal pose.
Definition: errors.h:104
+
const bool & max_path_pose_deviation_violation
True if internal motion generator deviated from the path.
Definition: errors.h:108
+
const bool & self_collision_avoidance_violation
True if the robot would have collided with itself.
Definition: errors.h:78
+
Errors(const std::array< bool, 41 > &errors)
Creates a new Errors instance from the given array.
+
const bool & joint_motion_generator_velocity_limits_violation
True if an external joint motion generator exceeded velocity limits.
Definition: errors.h:125
+
const bool & force_controller_desired_force_tolerance_violation
True if desired force exceeds the safety thresholds.
Definition: errors.h:192
+
const bool & force_control_safety_violation
True if the robot exceeded safety threshold during force control.
Definition: errors.h:90
+
const bool & instability_detected
True if an instability is detected.
Definition: errors.h:224
+
Errors()
Creates an empty Errors instance.
+
const bool & joint_via_motion_generator_planning_joint_limit_violation
True if the generated motion violates a joint limit.
Definition: errors.h:237
+
const bool & controller_torque_discontinuity
True if the torque set by the external controller is discontinuous.
Definition: errors.h:196
+
const bool & joint_reflex
True if a collision was detected, i.e. the robot exceeded a torque threshold in a joint motion.
Definition: errors.h:95
+
const bool & cartesian_velocity_profile_safety_violation
True if Cartesian velocity profile for internal motions was exceeded.
Definition: errors.h:112
+
+ + + + diff --git a/examples.html b/examples.html new file mode 100644 index 00000000..7f8935ea --- /dev/null +++ b/examples.html @@ -0,0 +1,128 @@ + + + + + + + +libfranka: Examples + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
Examples
+
+
+
Here is a list of all examples:
+
+ + + + diff --git a/examples__common_8h.html b/examples__common_8h.html new file mode 100644 index 00000000..5b4081a7 --- /dev/null +++ b/examples__common_8h.html @@ -0,0 +1,175 @@ + + + + + + + +libfranka: examples/examples_common.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+ +
+
examples_common.h File Reference
+
+
+ +

Contains common types and functions for the examples. +More...

+
#include <array>
+#include <Eigen/Core>
+#include <franka/control_types.h>
+#include <franka/duration.h>
+#include <franka/robot.h>
+#include <franka/robot_state.h>
+
+Include dependency graph for examples_common.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MotionGenerator
 An example showing how to generate a joint pose motion to a goal position. More...
 
+ + + + +

+Functions

void setDefaultBehavior (franka::Robot &robot)
 Sets a default collision behavior, joint impedance and Cartesian impedance. More...
 
+

Detailed Description

+

Contains common types and functions for the examples.

+

Function Documentation

+ +

◆ setDefaultBehavior()

+ + +
+ + + + diff --git a/examples__common_8h__incl.map b/examples__common_8h__incl.map new file mode 100644 index 00000000..398dae64 --- /dev/null +++ b/examples__common_8h__incl.map @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples__common_8h__incl.md5 b/examples__common_8h__incl.md5 new file mode 100644 index 00000000..52b83dd0 --- /dev/null +++ b/examples__common_8h__incl.md5 @@ -0,0 +1 @@ +08064b584744cdb2a467696989af3459 \ No newline at end of file diff --git a/examples__common_8h__incl.png b/examples__common_8h__incl.png new file mode 100644 index 00000000..e3ee3aed Binary files /dev/null and b/examples__common_8h__incl.png differ diff --git a/examples__common_8h_source.html b/examples__common_8h_source.html new file mode 100644 index 00000000..686a69c1 --- /dev/null +++ b/examples__common_8h_source.html @@ -0,0 +1,146 @@ + + + + + + + +libfranka: examples/examples_common.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
examples_common.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <array>
+
6 
+
7 #include <Eigen/Core>
+
8 
+
9 #include <franka/control_types.h>
+
10 #include <franka/duration.h>
+
11 #include <franka/robot.h>
+
12 #include <franka/robot_state.h>
+
13 
+ +
25 
+ +
32  public:
+
39  MotionGenerator(double speed_factor, const std::array<double, 7> q_goal);
+
40 
+ +
50 
+
51  private:
+
52  using Vector7d = Eigen::Matrix<double, 7, 1, Eigen::ColMajor>;
+
53  using Vector7i = Eigen::Matrix<int, 7, 1, Eigen::ColMajor>;
+
54 
+
55  bool calculateDesiredValues(double t, Vector7d* delta_q_d) const;
+
56  void calculateSynchronizedValues();
+
57 
+
58  static constexpr double kDeltaQMotionFinished = 1e-6;
+
59  const Vector7d q_goal_;
+
60 
+
61  Vector7d q_start_;
+
62  Vector7d delta_q_;
+
63 
+
64  Vector7d dq_max_sync_;
+
65  Vector7d t_1_sync_;
+
66  Vector7d t_2_sync_;
+
67  Vector7d t_f_sync_;
+
68  Vector7d q_1_;
+
69 
+
70  double time_ = 0.0;
+
71 
+
72  Vector7d dq_max_ = (Vector7d() << 2.0, 2.0, 2.0, 2.0, 2.5, 2.5, 2.5).finished();
+
73  Vector7d ddq_max_start_ = (Vector7d() << 5, 5, 5, 5, 5, 5, 5).finished();
+
74  Vector7d ddq_max_goal_ = (Vector7d() << 5, 5, 5, 5, 5, 5, 5).finished();
+
75 };
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
MotionGenerator(double speed_factor, const std::array< double, 7 > q_goal)
Creates a new MotionGenerator instance for a target q.
Definition: examples_common.cpp:22
+
franka::JointPositions operator()(const franka::RobotState &robot_state, franka::Duration period)
Sends joint position calculations.
Definition: examples_common.cpp:114
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Stores values for joint position motion generation.
Definition: control_types.h:72
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
Contains helper types for returning motion generation and joint-level torque commands.
+
Contains the franka::Duration type.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains the franka::Robot type.
+
Contains the franka::RobotState types.
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/exception_8h.html b/exception_8h.html new file mode 100644 index 00000000..baf268a8 --- /dev/null +++ b/exception_8h.html @@ -0,0 +1,166 @@ + + + + + + + +libfranka: include/franka/exception.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+ +
+
exception.h File Reference
+
+
+ +

Contains exception definitions. +More...

+
#include <stdexcept>
+#include <string>
+#include <franka/log.h>
+
+Include dependency graph for exception.h:
+
+
+ + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Classes

struct  franka::Exception
 Base class for all exceptions used by libfranka. More...
 
struct  franka::ModelException
 ModelException is thrown if an error occurs when loading the model library. More...
 
struct  franka::NetworkException
 NetworkException is thrown if a connection to the robot cannot be established, or when a timeout occurs. More...
 
struct  franka::ProtocolException
 ProtocolException is thrown if the robot returns an incorrect message. More...
 
struct  franka::IncompatibleVersionException
 IncompatibleVersionException is thrown if the robot does not support this version of libfranka. More...
 
struct  franka::ControlException
 ControlException is thrown if an error occurs during motion generation or torque control. More...
 
struct  franka::CommandException
 CommandException is thrown if an error occurs during command execution. More...
 
struct  franka::RealtimeException
 RealtimeException is thrown if realtime priority cannot be set. More...
 
struct  franka::InvalidOperationException
 InvalidOperationException is thrown if an operation cannot be performed. More...
 
+

Detailed Description

+

Contains exception definitions.

+
+ + + + diff --git a/exception_8h__dep__incl.map b/exception_8h__dep__incl.map new file mode 100644 index 00000000..43bc041c --- /dev/null +++ b/exception_8h__dep__incl.map @@ -0,0 +1,7 @@ + + + + + + + diff --git a/exception_8h__dep__incl.md5 b/exception_8h__dep__incl.md5 new file mode 100644 index 00000000..818e154d --- /dev/null +++ b/exception_8h__dep__incl.md5 @@ -0,0 +1 @@ +2ffd2591379374f70dc19ebccd93ac68 \ No newline at end of file diff --git a/exception_8h__dep__incl.png b/exception_8h__dep__incl.png new file mode 100644 index 00000000..1895cacd Binary files /dev/null and b/exception_8h__dep__incl.png differ diff --git a/exception_8h__incl.map b/exception_8h__incl.map new file mode 100644 index 00000000..b00adbe3 --- /dev/null +++ b/exception_8h__incl.map @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/exception_8h__incl.md5 b/exception_8h__incl.md5 new file mode 100644 index 00000000..8c1ff872 --- /dev/null +++ b/exception_8h__incl.md5 @@ -0,0 +1 @@ +436dc167aa9795891fa28cd8e52233aa \ No newline at end of file diff --git a/exception_8h__incl.png b/exception_8h__incl.png new file mode 100644 index 00000000..b04e4ccd Binary files /dev/null and b/exception_8h__incl.png differ diff --git a/exception_8h_source.html b/exception_8h_source.html new file mode 100644 index 00000000..66ca6829 --- /dev/null +++ b/exception_8h_source.html @@ -0,0 +1,156 @@ + + + + + + + +libfranka: include/franka/exception.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
exception.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <stdexcept>
+
6 #include <string>
+
7 
+
8 #include <franka/log.h>
+
9 
+
15 namespace franka {
+
16 
+
20 struct Exception : public std::runtime_error {
+
21  using std::runtime_error::runtime_error;
+
22 };
+
23 
+
27 struct ModelException : public Exception {
+
28  using Exception::Exception;
+
29 };
+
30 
+
35 struct NetworkException : public Exception {
+
36  using Exception::Exception;
+
37 };
+
38 
+
42 struct ProtocolException : public Exception {
+
43  using Exception::Exception;
+
44 };
+
45 
+ + +
56 
+
60  const uint16_t server_version;
+
64  const uint16_t library_version;
+
65 };
+
66 
+
73 struct ControlException : public Exception {
+
80  explicit ControlException(const std::string& what, std::vector<franka::Record> log = {}) noexcept;
+
81 
+
85  const std::vector<franka::Record> log;
+
86 };
+
87 
+
91 struct CommandException : public Exception {
+
92  using Exception::Exception;
+
93 };
+
94 
+
98 struct RealtimeException : public Exception {
+
99  using Exception::Exception;
+
100 };
+
101 
+ +
106  using Exception::Exception;
+
107 };
+
108 
+
109 } // namespace franka
+
Contains helper types for logging sent commands and received robot states.
+
CommandException is thrown if an error occurs during command execution.
Definition: exception.h:91
+
ControlException is thrown if an error occurs during motion generation or torque control.
Definition: exception.h:73
+
ControlException(const std::string &what, std::vector< franka::Record > log={}) noexcept
Creates the exception with an explanatory string and a Log object.
+
const std::vector< franka::Record > log
Vector of states and commands logged just before the exception occurred.
Definition: exception.h:85
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
IncompatibleVersionException is thrown if the robot does not support this version of libfranka.
Definition: exception.h:49
+
const uint16_t server_version
Control's protocol version.
Definition: exception.h:60
+
IncompatibleVersionException(uint16_t server_version, uint16_t library_version) noexcept
Creates the exception using the two different protocol versions.
+
const uint16_t library_version
libfranka protocol version.
Definition: exception.h:64
+
InvalidOperationException is thrown if an operation cannot be performed.
Definition: exception.h:105
+
ModelException is thrown if an error occurs when loading the model library.
Definition: exception.h:27
+
NetworkException is thrown if a connection to the robot cannot be established, or when a timeout occu...
Definition: exception.h:35
+
ProtocolException is thrown if the robot returns an incorrect message.
Definition: exception.h:42
+
RealtimeException is thrown if realtime priority cannot be set.
Definition: exception.h:98
+
+ + + + diff --git a/files.html b/files.html new file mode 100644 index 00000000..a21693b8 --- /dev/null +++ b/files.html @@ -0,0 +1,113 @@ + + + + + + + +libfranka: File List + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
File List
+
+
+
Here is a list of all documented files with brief descriptions:
+
[detail level 123]
+ + + + + + + + + + + + + + + + + + + + + + + + + +
  examples
 examples_common.hContains common types and functions for the examples
  include
  franka
 active_control.hImplements the ActiveControlBase abstract class
 active_control_base.hAbstract interface class as the base of the active controllers
 active_motion_generator.hContains the franka::ActiveMotionGenerator type
 active_torque_control.hContains the franka::ActiveTorqueControl type
 control_tools.hContains helper functions for writing control loops
 control_types.hContains helper types for returning motion generation and joint-level torque commands
 duration.hContains the franka::Duration type
 errors.hContains the franka::Errors type
 exception.hContains exception definitions
 gripper.hContains the franka::Gripper type
 gripper_state.hContains the franka::GripperState type
 log.hContains helper types for logging sent commands and received robot states
 lowpass_filter.hContains functions for filtering signals with a low-pass filter
 model.hContains model library types
 rate_limiting.hContains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity
 robot.hContains the franka::Robot type
 robot_model.h
 robot_model_base.h
 robot_state.hContains the franka::RobotState types
 vacuum_gripper.hContains the franka::VacuumGripper type
 vacuum_gripper_state.hContains the franka::VacuumGripperState type
+
+
+ + + + diff --git a/folderclosed.png b/folderclosed.png new file mode 100644 index 00000000..bb8ab35e Binary files /dev/null and b/folderclosed.png differ diff --git a/folderopen.png b/folderopen.png new file mode 100644 index 00000000..d6c7f676 Binary files /dev/null and b/folderopen.png differ diff --git a/force_control_8cpp-example.html b/force_control_8cpp-example.html new file mode 100644 index 00000000..378f8547 --- /dev/null +++ b/force_control_8cpp-example.html @@ -0,0 +1,214 @@ + + + + + + + +libfranka: force_control.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
force_control.cpp
+
+
+

A simple PI force controller that renders in the Z axis the gravitational force corresponding to a target mass of 1 kg.

Warning
: make sure that no endeffector is mounted and that the robot's last joint is in contact with a horizontal rigid surface before starting.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <array>
+
#include <iostream>
+
+
#include <Eigen/Core>
+
+ + +
#include <franka/model.h>
+
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
// Check whether the required arguments were passed
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
// parameters
+
double desired_mass{0.0};
+
constexpr double target_mass{1.0}; // NOLINT(readability-identifier-naming)
+
constexpr double k_p{1.0}; // NOLINT(readability-identifier-naming)
+
constexpr double k_i{2.0}; // NOLINT(readability-identifier-naming)
+
constexpr double filter_gain{0.001}; // NOLINT(readability-identifier-naming)
+
+
try {
+
// connect to robot
+
franka::Robot robot(argv[1]);
+ +
// load the kinematics and dynamics model
+
franka::Model model = robot.loadModel();
+
+
// set collision behavior
+
robot.setCollisionBehavior({{100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}},
+
{{100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}},
+
{{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}},
+
{{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}});
+
+
franka::RobotState initial_state = robot.readOnce();
+
+
Eigen::VectorXd initial_tau_ext(7), tau_error_integral(7);
+
// Bias torque sensor
+
std::array<double, 7> gravity_array = model.gravity(initial_state);
+
Eigen::Map<Eigen::Matrix<double, 7, 1>> initial_tau_measured(initial_state.tau_J.data());
+
Eigen::Map<Eigen::Matrix<double, 7, 1>> initial_gravity(gravity_array.data());
+
initial_tau_ext = initial_tau_measured - initial_gravity;
+
+
// init integrator
+
tau_error_integral.setZero();
+
+
// define callback for the torque control loop
+
Eigen::Vector3d initial_position;
+
double time = 0.0;
+
auto get_position = [](const franka::RobotState& robot_state) {
+
return Eigen::Vector3d(robot_state.O_T_EE[12], robot_state.O_T_EE[13],
+
robot_state.O_T_EE[14]);
+
};
+
auto force_control_callback = [&](const franka::RobotState& robot_state,
+ +
time += period.toSec();
+
+
if (time == 0.0) {
+
initial_position = get_position(robot_state);
+
}
+
+
if (time > 0 && (get_position(robot_state) - initial_position).norm() > 0.01) {
+
throw std::runtime_error("Aborting; too far away from starting pose!");
+
}
+
+
// get state variables
+
std::array<double, 42> jacobian_array =
+
model.zeroJacobian(franka::Frame::kEndEffector, robot_state);
+
+
Eigen::Map<const Eigen::Matrix<double, 6, 7>> jacobian(jacobian_array.data());
+
Eigen::Map<const Eigen::Matrix<double, 7, 1>> tau_measured(robot_state.tau_J.data());
+
Eigen::Map<const Eigen::Matrix<double, 7, 1>> gravity(gravity_array.data());
+
+
Eigen::VectorXd tau_d(7), desired_force_torque(6), tau_cmd(7), tau_ext(7);
+
desired_force_torque.setZero();
+
desired_force_torque(2) = desired_mass * -9.81;
+
tau_ext << tau_measured - gravity - initial_tau_ext;
+
tau_d << jacobian.transpose() * desired_force_torque;
+
tau_error_integral += period.toSec() * (tau_d - tau_ext);
+
// FF + PI control
+
tau_cmd << tau_d + k_p * (tau_d - tau_ext) + k_i * tau_error_integral;
+
+
// Smoothly update the mass to reach the desired target value
+
desired_mass = filter_gain * target_mass + (1 - filter_gain) * desired_mass;
+
+
std::array<double, 7> tau_d_array{};
+
Eigen::VectorXd::Map(&tau_d_array[0], 7) = tau_cmd;
+
return tau_d_array;
+
};
+
std::cout << "WARNING: Make sure sure that no endeffector is mounted and that the robot's last "
+
"joint is "
+
"in contact with a horizontal rigid surface before starting. Keep in mind that "
+
"collision thresholds are set to high values."
+
<< std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
// start real-time control loop
+
robot.control(force_control_callback);
+
+
} catch (const std::exception& ex) {
+
// print exception
+
std::cout << ex.what() << std::endl;
+
}
+
return 0;
+
}
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Calculates poses of joints and dynamic properties of the robot.
Definition: model.h:52
+
std::array< double, 42 > zeroJacobian(Frame frame, const franka::RobotState &robot_state) const
Gets the 6x7 Jacobian for the given joint relative to the base frame.
+
std::array< double, 7 > gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexcept
Calculates the gravity vector.
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
Model loadModel()
Loads the model library from the robot.
+
virtual RobotState readOnce()
Waits for a robot state update and returns it.
+
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
+
Contains the franka::Duration type.
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains model library types.
+
Contains the franka::Robot type.
+
Describes the robot state.
Definition: robot_state.h:34
+
std::array< double, 7 > tau_J
Measured link-side joint torque sensor signals.
Definition: robot_state.h:215
+
+ + + + diff --git a/functions.html b/functions.html new file mode 100644 index 00000000..4cfb976b --- /dev/null +++ b/functions.html @@ -0,0 +1,93 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- a -

+
+ + + + diff --git a/functions_b.html b/functions_b.html new file mode 100644 index 00000000..076bcc97 --- /dev/null +++ b/functions_b.html @@ -0,0 +1,93 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- b -

+
+ + + + diff --git a/functions_c.html b/functions_c.html new file mode 100644 index 00000000..8e77768a --- /dev/null +++ b/functions_c.html @@ -0,0 +1,185 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- c -

+
+ + + + diff --git a/functions_d.html b/functions_d.html new file mode 100644 index 00000000..55c21c5e --- /dev/null +++ b/functions_d.html @@ -0,0 +1,115 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- d -

+
+ + + + diff --git a/functions_e.html b/functions_e.html new file mode 100644 index 00000000..b2b5ee9a --- /dev/null +++ b/functions_e.html @@ -0,0 +1,101 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- e -

+
+ + + + diff --git a/functions_enum.html b/functions_enum.html new file mode 100644 index 00000000..0cadca6d --- /dev/null +++ b/functions_enum.html @@ -0,0 +1,85 @@ + + + + + + + +libfranka: Class Members - Enumerations + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+ + + + diff --git a/functions_f.html b/functions_f.html new file mode 100644 index 00000000..ba558138 --- /dev/null +++ b/functions_f.html @@ -0,0 +1,105 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- f -

+
+ + + + diff --git a/functions_func.html b/functions_func.html new file mode 100644 index 00000000..5f7267fa --- /dev/null +++ b/functions_func.html @@ -0,0 +1,408 @@ + + + + + + + +libfranka: Class Members - Functions + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+  + +

- a -

+ + +

- b -

+ + +

- c -

+ + +

- d -

+ + +

- e -

+ + +

- g -

+ + +

- h -

+ + +

- i -

+ + +

- j -

+ + +

- l -

+ + +

- m -

+ + +

- o -

+ + +

- p -

+ + +

- r -

+ + +

- s -

+ + +

- t -

+ + +

- v -

+ + +

- w -

+ + +

- z -

+ + +

- ~ -

+
+ + + + diff --git a/functions_g.html b/functions_g.html new file mode 100644 index 00000000..ff436d92 --- /dev/null +++ b/functions_g.html @@ -0,0 +1,98 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- g -

+
+ + + + diff --git a/functions_h.html b/functions_h.html new file mode 100644 index 00000000..098f7e07 --- /dev/null +++ b/functions_h.html @@ -0,0 +1,91 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- h -

+
+ + + + diff --git a/functions_i.html b/functions_i.html new file mode 100644 index 00000000..fcb96354 --- /dev/null +++ b/functions_i.html @@ -0,0 +1,105 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- i -

+
+ + + + diff --git a/functions_j.html b/functions_j.html new file mode 100644 index 00000000..b235bfa3 --- /dev/null +++ b/functions_j.html @@ -0,0 +1,135 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- j -

+
+ + + + diff --git a/functions_k.html b/functions_k.html new file mode 100644 index 00000000..76fac80a --- /dev/null +++ b/functions_k.html @@ -0,0 +1,87 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- k -

+
+ + + + diff --git a/functions_l.html b/functions_l.html new file mode 100644 index 00000000..dc8d5980 --- /dev/null +++ b/functions_l.html @@ -0,0 +1,99 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- l -

+
+ + + + diff --git a/functions_m.html b/functions_m.html new file mode 100644 index 00000000..1bd32f0d --- /dev/null +++ b/functions_m.html @@ -0,0 +1,122 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- m -

+
+ + + + diff --git a/functions_n.html b/functions_n.html new file mode 100644 index 00000000..3c0956e6 --- /dev/null +++ b/functions_n.html @@ -0,0 +1,87 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- n -

+
+ + + + diff --git a/functions_o.html b/functions_o.html new file mode 100644 index 00000000..70c68e9d --- /dev/null +++ b/functions_o.html @@ -0,0 +1,180 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- o -

+
+ + + + diff --git a/functions_p.html b/functions_p.html new file mode 100644 index 00000000..2a2a2186 --- /dev/null +++ b/functions_p.html @@ -0,0 +1,99 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- p -

+
+ + + + diff --git a/functions_q.html b/functions_q.html new file mode 100644 index 00000000..c7e33b23 --- /dev/null +++ b/functions_q.html @@ -0,0 +1,91 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- q -

+
+ + + + diff --git a/functions_r.html b/functions_r.html new file mode 100644 index 00000000..81e9fd36 --- /dev/null +++ b/functions_r.html @@ -0,0 +1,105 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- r -

+
+ + + + diff --git a/functions_rela.html b/functions_rela.html new file mode 100644 index 00000000..19d3308d --- /dev/null +++ b/functions_rela.html @@ -0,0 +1,86 @@ + + + + + + + +libfranka: Class Members - Related Functions + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+ + + + diff --git a/functions_s.html b/functions_s.html new file mode 100644 index 00000000..ec19951e --- /dev/null +++ b/functions_s.html @@ -0,0 +1,155 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- s -

+
+ + + + diff --git a/functions_t.html b/functions_t.html new file mode 100644 index 00000000..61cbbbc2 --- /dev/null +++ b/functions_t.html @@ -0,0 +1,120 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- t -

+
+ + + + diff --git a/functions_type.html b/functions_type.html new file mode 100644 index 00000000..603e4bea --- /dev/null +++ b/functions_type.html @@ -0,0 +1,87 @@ + + + + + + + +libfranka: Class Members - Typedefs + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+ + + + diff --git a/functions_v.html b/functions_v.html new file mode 100644 index 00000000..fa019bd8 --- /dev/null +++ b/functions_v.html @@ -0,0 +1,91 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- v -

+
+ + + + diff --git a/functions_vars.html b/functions_vars.html new file mode 100644 index 00000000..3e466467 --- /dev/null +++ b/functions_vars.html @@ -0,0 +1,513 @@ + + + + + + + +libfranka: Class Members - Variables + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+  + +

- a -

+ + +

- b -

+ + +

- c -

+ + +

- d -

+ + +

- e -

+ + +

- f -

+ + +

- i -

+ + +

- j -

+ + +

- k -

+ + +

- l -

+ + +

- m -

+ + +

- n -

+ + +

- o -

+ + +

- p -

+ + +

- q -

+ + +

- r -

+ + +

- s -

+ + +

- t -

+ + +

- v -

+ + +

- w -

+
+ + + + diff --git a/functions_w.html b/functions_w.html new file mode 100644 index 00000000..59bde6e3 --- /dev/null +++ b/functions_w.html @@ -0,0 +1,93 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- w -

+
+ + + + diff --git a/functions_z.html b/functions_z.html new file mode 100644 index 00000000..b3d5a609 --- /dev/null +++ b/functions_z.html @@ -0,0 +1,87 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- z -

+
+ + + + diff --git a/functions_~.html b/functions_~.html new file mode 100644 index 00000000..7b2c392c --- /dev/null +++ b/functions_~.html @@ -0,0 +1,96 @@ + + + + + + + +libfranka: Class Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- ~ -

+
+ + + + diff --git a/generate_cartesian_pose_motion_8cpp-example.html b/generate_cartesian_pose_motion_8cpp-example.html new file mode 100644 index 00000000..bee11474 --- /dev/null +++ b/generate_cartesian_pose_motion_8cpp-example.html @@ -0,0 +1,169 @@ + + + + + + + +libfranka: generate_cartesian_pose_motion.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_cartesian_pose_motion.cpp
+
+
+

An example showing how to generate a Cartesian motion.

Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+ +
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
+
+
std::array<double, 16> initial_pose;
+
double time = 0.0;
+
robot.control([&time, &initial_pose](const franka::RobotState& robot_state,
+ +
time += period.toSec();
+
+
if (time == 0.0) {
+
initial_pose = robot_state.O_T_EE;
+
}
+
+
constexpr double kRadius = 0.3;
+
double angle = M_PI / 4 * (1 - std::cos(M_PI / 5.0 * time));
+
double delta_x = kRadius * std::sin(angle);
+
double delta_z = kRadius * (std::cos(angle) - 1);
+
+
std::array<double, 16> new_pose = initial_pose;
+
new_pose[12] += delta_x;
+
new_pose[14] += delta_z;
+
+
if (time >= 10.0) {
+
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
+
return franka::MotionFinished(new_pose);
+
}
+
return new_pose;
+
});
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Stores values for Cartesian pose motion generation.
Definition: control_types.h:127
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
double toSec() const noexcept
Returns the stored duration in .
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
std::array< double, 16 > O_T_EE
Measured end effector pose in base frame.
Definition: robot_state.h:40
+
+ + + + diff --git a/generate_cartesian_pose_motion_external_control_loop_8cpp-example.html b/generate_cartesian_pose_motion_external_control_loop_8cpp-example.html new file mode 100644 index 00000000..b2e2d70d --- /dev/null +++ b/generate_cartesian_pose_motion_external_control_loop_8cpp-example.html @@ -0,0 +1,188 @@ + + + + + + + +libfranka: generate_cartesian_pose_motion_external_control_loop.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_cartesian_pose_motion_external_control_loop.cpp
+
+
+

An example showing how to generate a Cartesian motion with an external control loop.

Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ + + +
#include <franka/robot.h>
+ +
+
int main(int argc, char** argv) {
+
// Check whether the required arguments were passed
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+ +
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
+
+
std::array<double, 16> initial_pose;
+
double time = 0.0;
+
+
auto callback_control = [&time, &initial_pose](
+
const franka::RobotState& robot_state,
+ +
time += period.toSec();
+
+
if (time == 0.0) {
+
initial_pose = robot_state.O_T_EE_c;
+
}
+
+
constexpr double kRadius = 0.3;
+
double angle = M_PI / 4 * (1 - std::cos(M_PI / 5.0 * time));
+
double delta_x = kRadius * std::sin(angle);
+
double delta_z = kRadius * (std::cos(angle) - 1);
+
+
std::array<double, 16> new_pose = initial_pose;
+
new_pose[12] += delta_x;
+
new_pose[14] += delta_z;
+
+
if (time >= 10.0) {
+
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
+
return franka::MotionFinished(new_pose);
+
}
+
return new_pose;
+
};
+
+
bool motion_finished = false;
+
auto active_control = robot.startCartesianPoseControl(
+
research_interface::robot::Move::ControllerMode::kJointImpedance);
+
while (!motion_finished) {
+
auto read_once_return = active_control->readOnce();
+
auto robot_state = read_once_return.first;
+
auto duration = read_once_return.second;
+
auto cartesian_positions = callback_control(robot_state, duration);
+
motion_finished = cartesian_positions.motion_finished;
+
active_control->writeOnce(cartesian_positions);
+
}
+
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
Implements the ActiveControlBase abstract class.
+
Contains the franka::ActiveMotionGenerator type.
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Stores values for Cartesian pose motion generation.
Definition: control_types.h:127
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
virtual std::unique_ptr< ActiveControlBase > startCartesianPoseControl(const research_interface::robot::Move::ControllerMode &control_type)
Starts a new cartesian position motion generator.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/generate_cartesian_velocity_motion_8cpp-example.html b/generate_cartesian_velocity_motion_8cpp-example.html new file mode 100644 index 00000000..3b3651c8 --- /dev/null +++ b/generate_cartesian_velocity_motion_8cpp-example.html @@ -0,0 +1,179 @@ + + + + + + + +libfranka: generate_cartesian_velocity_motion.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_cartesian_velocity_motion.cpp
+
+
+

An example showing how to generate a Cartesian velocity motion.

Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set the joint impedance.
+
robot.setJointImpedance({{3000, 3000, 3000, 2500, 2500, 2000, 2000}});
+
+
// Set the collision behavior.
+
std::array<double, 7> lower_torque_thresholds_nominal{
+
{25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.}};
+
std::array<double, 7> upper_torque_thresholds_nominal{
+
{35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0}};
+
std::array<double, 7> lower_torque_thresholds_acceleration{
+
{25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.0}};
+
std::array<double, 7> upper_torque_thresholds_acceleration{
+
{35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0}};
+
std::array<double, 6> lower_force_thresholds_nominal{{30.0, 30.0, 30.0, 25.0, 25.0, 25.0}};
+
std::array<double, 6> upper_force_thresholds_nominal{{40.0, 40.0, 40.0, 35.0, 35.0, 35.0}};
+
std::array<double, 6> lower_force_thresholds_acceleration{{30.0, 30.0, 30.0, 25.0, 25.0, 25.0}};
+
std::array<double, 6> upper_force_thresholds_acceleration{{40.0, 40.0, 40.0, 35.0, 35.0, 35.0}};
+ +
lower_torque_thresholds_acceleration, upper_torque_thresholds_acceleration,
+
lower_torque_thresholds_nominal, upper_torque_thresholds_nominal,
+
lower_force_thresholds_acceleration, upper_force_thresholds_acceleration,
+
lower_force_thresholds_nominal, upper_force_thresholds_nominal);
+
+
double time_max = 4.0;
+
double v_max = 0.1;
+
double angle = M_PI / 4.0;
+
double time = 0.0;
+
robot.control([=, &time](const franka::RobotState&,
+ +
time += period.toSec();
+
+
double cycle = std::floor(pow(-1.0, (time - std::fmod(time, time_max)) / time_max));
+
double v = cycle * v_max / 2.0 * (1.0 - std::cos(2.0 * M_PI / time_max * time));
+
double v_x = std::cos(angle) * v;
+
double v_z = -std::sin(angle) * v;
+
+
franka::CartesianVelocities output = {{v_x, 0.0, v_z, 0.0, 0.0, 0.0}};
+
if (time >= 2 * time_max) {
+
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
+
return franka::MotionFinished(output);
+
}
+
return output;
+
});
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Stores values for Cartesian velocity motion generation.
Definition: control_types.h:211
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
double toSec() const noexcept
Returns the stored duration in .
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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 setJointImpedance(const std::array< double, 7 > &K_theta)
Sets the impedance for each joint in the internal controller.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/generate_cartesian_velocity_motion_external_control_loop_8cpp-example.html b/generate_cartesian_velocity_motion_external_control_loop_8cpp-example.html new file mode 100644 index 00000000..aa88b888 --- /dev/null +++ b/generate_cartesian_velocity_motion_external_control_loop_8cpp-example.html @@ -0,0 +1,199 @@ + + + + + + + +libfranka: generate_cartesian_velocity_motion_external_control_loop.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_cartesian_velocity_motion_external_control_loop.cpp
+
+
+

An example showing how to generate a Cartesian velocity motion with an external control loop.

Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ + + +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
// Check whether the required arguments were passed
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set the joint impedance.
+
robot.setJointImpedance({{3000, 3000, 3000, 2500, 2500, 2000, 2000}});
+
+
// Set the collision behavior.
+
std::array<double, 7> lower_torque_thresholds_nominal{
+
{25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.}};
+
std::array<double, 7> upper_torque_thresholds_nominal{
+
{35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0}};
+
std::array<double, 7> lower_torque_thresholds_acceleration{
+
{25.0, 25.0, 22.0, 20.0, 19.0, 17.0, 14.0}};
+
std::array<double, 7> upper_torque_thresholds_acceleration{
+
{35.0, 35.0, 32.0, 30.0, 29.0, 27.0, 24.0}};
+
std::array<double, 6> lower_force_thresholds_nominal{{30.0, 30.0, 30.0, 25.0, 25.0, 25.0}};
+
std::array<double, 6> upper_force_thresholds_nominal{{40.0, 40.0, 40.0, 35.0, 35.0, 35.0}};
+
std::array<double, 6> lower_force_thresholds_acceleration{{30.0, 30.0, 30.0, 25.0, 25.0, 25.0}};
+
std::array<double, 6> upper_force_thresholds_acceleration{{40.0, 40.0, 40.0, 35.0, 35.0, 35.0}};
+ +
lower_torque_thresholds_acceleration, upper_torque_thresholds_acceleration,
+
lower_torque_thresholds_nominal, upper_torque_thresholds_nominal,
+
lower_force_thresholds_acceleration, upper_force_thresholds_acceleration,
+
lower_force_thresholds_nominal, upper_force_thresholds_nominal);
+
+
double time_max = 4.0;
+
double v_max = 0.1;
+
double angle = M_PI / 4.0;
+
double time = 0.0;
+
+
auto callback_control = [=, &time](const franka::RobotState&,
+ +
time += period.toSec();
+
+
double cycle = std::floor(pow(-1.0, (time - std::fmod(time, time_max)) / time_max));
+
double v = cycle * v_max / 2.0 * (1.0 - std::cos(2.0 * M_PI / time_max * time));
+
double v_x = std::cos(angle) * v;
+
double v_z = -std::sin(angle) * v;
+
+
franka::CartesianVelocities output = {{v_x, 0.0, v_z, 0.0, 0.0, 0.0}};
+
if (time >= 2 * time_max) {
+
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
+
return franka::MotionFinished(output);
+
}
+
return output;
+
};
+
+
bool motion_finished = false;
+
auto active_control = robot.startCartesianVelocityControl(
+
research_interface::robot::Move::ControllerMode::kJointImpedance);
+
while (!motion_finished) {
+
auto read_once_return = active_control->readOnce();
+
auto robot_state = read_once_return.first;
+
auto duration = read_once_return.second;
+
auto cartesian_velocities = callback_control(robot_state, duration);
+
motion_finished = cartesian_velocities.motion_finished;
+
active_control->writeOnce(cartesian_velocities);
+
}
+
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
Implements the ActiveControlBase abstract class.
+
Contains the franka::ActiveMotionGenerator type.
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Stores values for Cartesian velocity motion generation.
Definition: control_types.h:211
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
virtual std::unique_ptr< ActiveControlBase > startCartesianVelocityControl(const research_interface::robot::Move::ControllerMode &control_type)
Starts a new cartesian velocity motion generator.
+
void setJointImpedance(const std::array< double, 7 > &K_theta)
Sets the impedance for each joint in the internal controller.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/generate_consecutive_motions_8cpp-example.html b/generate_consecutive_motions_8cpp-example.html new file mode 100644 index 00000000..ebd8bda4 --- /dev/null +++ b/generate_consecutive_motions_8cpp-example.html @@ -0,0 +1,173 @@ + + + + + + + +libfranka: generate_consecutive_motions.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_consecutive_motions.cpp
+
+
+

An example showing how to execute consecutive motions with error recovery.

Warning
Before executing this example, make sure there is enough space in front and to the side of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+ +
{{10.0, 10.0, 9.0, 9.0, 8.0, 7.0, 6.0}}, {{10.0, 10.0, 9.0, 9.0, 8.0, 7.0, 6.0}},
+
{{10.0, 10.0, 9.0, 9.0, 8.0, 7.0, 6.0}}, {{10.0, 10.0, 9.0, 9.0, 8.0, 7.0, 6.0}},
+
{{10.0, 10.0, 10.0, 12.5, 12.5, 12.5}}, {{10.0, 10.0, 10.0, 12.5, 12.5, 12.5}},
+
{{10.0, 10.0, 10.0, 12.5, 12.5, 12.5}}, {{10.0, 10.0, 10.0, 12.5, 12.5, 12.5}});
+
+
for (size_t i = 0; i < 5; i++) {
+
std::cout << "Executing motion." << std::endl;
+
try {
+
double time_max = 4.0;
+
double omega_max = 0.2;
+
double time = 0.0;
+
robot.control([=, &time](const franka::RobotState&,
+ +
time += period.toSec();
+
+
double cycle = std::floor(std::pow(-1.0, (time - std::fmod(time, time_max)) / time_max));
+
double omega = cycle * omega_max / 2.0 * (1.0 - std::cos(2.0 * M_PI / time_max * time));
+
+
franka::JointVelocities velocities = {{0.0, 0.0, omega, 0.0, 0.0, 0.0, 0.0}};
+
if (time >= 2 * time_max) {
+
std::cout << std::endl << "Finished motion." << std::endl;
+
return franka::MotionFinished(velocities);
+
}
+
return velocities;
+
});
+
} catch (const franka::ControlException& e) {
+
std::cout << e.what() << std::endl;
+
std::cout << "Running error recovery..." << std::endl;
+ +
}
+
}
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
std::cout << "Finished." << std::endl;
+
+
return 0;
+
}
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
double toSec() const noexcept
Returns the stored duration in .
+
Stores values for joint velocity motion generation.
Definition: control_types.h:99
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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 automaticErrorRecovery()
Runs automatic error recovery on the robot.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
ControlException is thrown if an error occurs during motion generation or torque control.
Definition: exception.h:73
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/generate_elbow_motion_8cpp-example.html b/generate_elbow_motion_8cpp-example.html new file mode 100644 index 00000000..bbf74be4 --- /dev/null +++ b/generate_elbow_motion_8cpp-example.html @@ -0,0 +1,170 @@ + + + + + + + +libfranka: generate_elbow_motion.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_elbow_motion.cpp
+
+
+

An example showing how to move the robot's elbow.

Warning
Before executing this example, make sure that the elbow has enough space to move.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+ +
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
+
+
std::array<double, 16> initial_pose;
+
std::array<double, 2> initial_elbow;
+
double time = 0.0;
+
robot.control(
+
[&time, &initial_pose, &initial_elbow](const franka::RobotState& robot_state,
+ +
time += period.toSec();
+
+
if (time == 0.0) {
+
initial_pose = robot_state.O_T_EE;
+
initial_elbow = robot_state.elbow;
+
}
+
+
double angle = M_PI / 10.0 * (1.0 - std::cos(M_PI / 5.0 * time));
+
+
auto elbow = initial_elbow;
+
elbow[0] += angle;
+
+
if (time >= 10.0) {
+
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
+
return franka::MotionFinished({initial_pose, elbow});
+
}
+
+
return {initial_pose, elbow};
+
});
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Stores values for Cartesian pose motion generation.
Definition: control_types.h:127
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
double toSec() const noexcept
Returns the stored duration in .
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
std::array< double, 16 > O_T_EE
Measured end effector pose in base frame.
Definition: robot_state.h:40
+
std::array< double, 2 > elbow
Elbow configuration.
Definition: robot_state.h:161
+
+ + + + diff --git a/generate_joint_position_motion_8cpp-example.html b/generate_joint_position_motion_8cpp-example.html new file mode 100644 index 00000000..94ef5680 --- /dev/null +++ b/generate_joint_position_motion_8cpp-example.html @@ -0,0 +1,167 @@ + + + + + + + +libfranka: generate_joint_position_motion.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_joint_position_motion.cpp
+
+
+

An example showing how to generate a joint position motion.

Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+ +
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
+
+
std::array<double, 7> initial_position;
+
double time = 0.0;
+
robot.control([&initial_position, &time](const franka::RobotState& robot_state,
+ +
time += period.toSec();
+
+
if (time == 0.0) {
+
initial_position = robot_state.q;
+
}
+
+
double delta_angle = M_PI / 8.0 * (1 - std::cos(M_PI / 2.5 * time));
+
+
franka::JointPositions output = {{initial_position[0], initial_position[1],
+
initial_position[2], initial_position[3] + delta_angle,
+
initial_position[4] + delta_angle, initial_position[5],
+
initial_position[6] + delta_angle}};
+
+
if (time >= 5.0) {
+
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
+
return franka::MotionFinished(output);
+
}
+
return output;
+
});
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
double toSec() const noexcept
Returns the stored duration in .
+
Stores values for joint position motion generation.
Definition: control_types.h:72
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
std::array< double, 7 > q
Measured joint position.
Definition: robot_state.h:233
+
+ + + + diff --git a/generate_joint_position_motion_external_control_loop_8cpp-example.html b/generate_joint_position_motion_external_control_loop_8cpp-example.html new file mode 100644 index 00000000..8f7fc83f --- /dev/null +++ b/generate_joint_position_motion_external_control_loop_8cpp-example.html @@ -0,0 +1,185 @@ + + + + + + + +libfranka: generate_joint_position_motion_external_control_loop.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_joint_position_motion_external_control_loop.cpp
+
+
+

An example showing how to generate a joint position motion with an external control loop..

+
Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ + + +
#include <franka/robot.h>
+ +
int main(int argc, char** argv) {
+
// Check whether the required arguments were passed
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+ +
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
+
+
std::array<double, 7> initial_position{{0, 0, 0, 0, 0, 0, 0}};
+
double time = 0.0;
+
auto control_callback = [&initial_position, &time](
+
const franka::RobotState& robot_state,
+ +
time += period.toSec();
+
+
if (time == 0.0) {
+
initial_position = robot_state.q_d;
+
}
+
+
double delta_angle = M_PI / 8.0 * (1 - std::cos(M_PI / 2.5 * time));
+
+
franka::JointPositions output = {{initial_position[0], initial_position[1],
+
initial_position[2], initial_position[3] + delta_angle,
+
initial_position[4] + delta_angle, initial_position[5],
+
initial_position[6] + delta_angle}};
+
+
if (time >= 5.0) {
+
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
+
return franka::MotionFinished(output);
+
}
+
return output;
+
};
+
+
bool motion_finished = false;
+
auto active_control = robot.startJointPositionControl(
+
research_interface::robot::Move::ControllerMode::kJointImpedance);
+
while (!motion_finished) {
+
auto read_once_return = active_control->readOnce();
+
auto robot_state = read_once_return.first;
+
auto duration = read_once_return.second;
+
auto joint_positions = control_callback(robot_state, duration);
+
motion_finished = joint_positions.motion_finished;
+
active_control->writeOnce(joint_positions);
+
}
+
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
Implements the ActiveControlBase abstract class.
+
Contains the franka::ActiveMotionGenerator type.
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Stores values for joint position motion generation.
Definition: control_types.h:72
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
virtual std::unique_ptr< ActiveControlBase > startJointPositionControl(const research_interface::robot::Move::ControllerMode &control_type)
Starts a new joint position motion generator.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/generate_joint_velocity_motion_8cpp-example.html b/generate_joint_velocity_motion_8cpp-example.html new file mode 100644 index 00000000..fc865e93 --- /dev/null +++ b/generate_joint_velocity_motion_8cpp-example.html @@ -0,0 +1,161 @@ + + + + + + + +libfranka: generate_joint_velocity_motion.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_joint_velocity_motion.cpp
+
+
+

An example showing how to generate a joint velocity motion.

Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+ +
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
+
+
double time_max = 1.0;
+
double omega_max = 1.0;
+
double time = 0.0;
+
robot.control(
+ +
time += period.toSec();
+
+
double cycle = std::floor(std::pow(-1.0, (time - std::fmod(time, time_max)) / time_max));
+
double omega = cycle * omega_max / 2.0 * (1.0 - std::cos(2.0 * M_PI / time_max * time));
+
+
franka::JointVelocities velocities = {{0.0, 0.0, 0.0, omega, omega, omega, omega}};
+
+
if (time >= 2 * time_max) {
+
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
+
return franka::MotionFinished(velocities);
+
}
+
return velocities;
+
});
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
double toSec() const noexcept
Returns the stored duration in .
+
Stores values for joint velocity motion generation.
Definition: control_types.h:99
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/generate_joint_velocity_motion_external_control_loop_8cpp-example.html b/generate_joint_velocity_motion_external_control_loop_8cpp-example.html new file mode 100644 index 00000000..85d595b5 --- /dev/null +++ b/generate_joint_velocity_motion_external_control_loop_8cpp-example.html @@ -0,0 +1,181 @@ + + + + + + + +libfranka: generate_joint_velocity_motion_external_control_loop.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
generate_joint_velocity_motion_external_control_loop.cpp
+
+
+

An example showing how to generate a joint velocity motion with an external control loop.

Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ + + +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
// Check whether the required arguments were passed
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+ +
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
+
+
double time_max = 1.0;
+
double omega_max = 1.0;
+
double time = 0.0;
+
+
auto callback_control = [=, &time](const franka::RobotState&,
+ +
time += period.toSec();
+
+
double cycle = std::floor(std::pow(-1.0, (time - std::fmod(time, time_max)) / time_max));
+
double omega = cycle * omega_max / 2.0 * (1.0 - std::cos(2.0 * M_PI / time_max * time));
+
+
franka::JointVelocities velocities = {{0.0, 0.0, 0.0, omega, omega, omega, omega}};
+
+
if (time >= 2 * time_max) {
+
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
+
return franka::MotionFinished(velocities);
+
}
+
return velocities;
+
};
+
+
bool motion_finished = false;
+
auto active_control = robot.startJointVelocityControl(
+
research_interface::robot::Move::ControllerMode::kJointImpedance);
+
while (!motion_finished) {
+
auto read_once_return = active_control->readOnce();
+
auto robot_state = read_once_return.first;
+
auto duration = read_once_return.second;
+
auto joint_velocities = callback_control(robot_state, duration);
+
motion_finished = joint_velocities.motion_finished;
+
active_control->writeOnce(joint_velocities);
+
}
+
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
Implements the ActiveControlBase abstract class.
+
Contains the franka::ActiveMotionGenerator type.
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Stores values for joint velocity motion generation.
Definition: control_types.h:99
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
virtual std::unique_ptr< ActiveControlBase > startJointVelocityControl(const research_interface::robot::Move::ControllerMode &control_type)
Starts a new joint velocity motion generator.
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/globals.html b/globals.html new file mode 100644 index 00000000..d7cad680 --- /dev/null +++ b/globals.html @@ -0,0 +1,85 @@ + + + + + + + +libfranka: File Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
Here is a list of all documented file members with links to the documentation:
+
+ + + + diff --git a/globals_func.html b/globals_func.html new file mode 100644 index 00000000..381a55ae --- /dev/null +++ b/globals_func.html @@ -0,0 +1,85 @@ + + + + + + + +libfranka: File Members + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+ + + + diff --git a/graph_legend.html b/graph_legend.html new file mode 100644 index 00000000..97959a38 --- /dev/null +++ b/graph_legend.html @@ -0,0 +1,144 @@ + + + + + + + +libfranka: Graph Legend + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
Graph Legend
+
+
+

This page explains how to interpret the graphs that are generated by doxygen.

+

Consider the following example:

/*! Invisible class because of truncation */
+
class Invisible { };
+
+
/*! Truncated class, inheritance relation is hidden */
+
class Truncated : public Invisible { };
+
+
/* Class not documented with doxygen comments */
+
class Undocumented { };
+
+
/*! Class that is inherited using public inheritance */
+
class PublicBase : public Truncated { };
+
+
/*! A template class */
+
template<class T> class Templ { };
+
+
/*! Class that is inherited using protected inheritance */
+
class ProtectedBase { };
+
+
/*! Class that is inherited using private inheritance */
+
class PrivateBase { };
+
+
/*! Class that is used by the Inherited class */
+
class Used { };
+
+
/*! Super class that inherits a number of other classes */
+
class Inherited : public PublicBase,
+
protected ProtectedBase,
+
private PrivateBase,
+
public Undocumented,
+
public Templ<int>
+
{
+
private:
+
Used *m_usedClass;
+
};
+

This will result in the following graph:

+

The boxes in the above graph have the following meaning:

+ +

The arrows have the following meaning:

+ +
+ + + + diff --git a/graph_legend.md5 b/graph_legend.md5 new file mode 100644 index 00000000..8fcdccd1 --- /dev/null +++ b/graph_legend.md5 @@ -0,0 +1 @@ +f51bf6e9a10430aafef59831b08dcbfe \ No newline at end of file diff --git a/graph_legend.png b/graph_legend.png new file mode 100644 index 00000000..7e2cbcfb Binary files /dev/null and b/graph_legend.png differ diff --git a/grasp_object_8cpp-example.html b/grasp_object_8cpp-example.html new file mode 100644 index 00000000..58b27bc7 --- /dev/null +++ b/grasp_object_8cpp-example.html @@ -0,0 +1,159 @@ + + + + + + + +libfranka: grasp_object.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
grasp_object.cpp
+
+
+

An example showing how to control FRANKA's gripper.

+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <iostream>
+
#include <sstream>
+
#include <string>
+
#include <thread>
+
+ +
#include <franka/gripper.h>
+
+
int main(int argc, char** argv) {
+
if (argc != 4) {
+
std::cerr << "Usage: ./grasp_object <gripper-hostname> <homing> <object-width>" << std::endl;
+
return -1;
+
}
+
+
try {
+
franka::Gripper gripper(argv[1]);
+
double grasping_width = std::stod(argv[3]);
+
+
std::stringstream ss(argv[2]);
+
bool homing;
+
if (!(ss >> homing)) {
+
std::cerr << "<homing> can be 0 or 1." << std::endl;
+
return -1;
+
}
+
+
if (homing) {
+
// Do a homing in order to estimate the maximum grasping width with the current fingers.
+
gripper.homing();
+
}
+
+
// Check for the maximum grasping width.
+
franka::GripperState gripper_state = gripper.readOnce();
+
if (gripper_state.max_width < grasping_width) {
+
std::cout << "Object is too large for the current fingers on the gripper." << std::endl;
+
return -1;
+
}
+
+
// Grasp the object.
+
if (!gripper.grasp(grasping_width, 0.1, 60)) {
+
std::cout << "Failed to grasp object." << std::endl;
+
return -1;
+
}
+
+
// Wait 3s and check afterwards, if the object is still grasped.
+
std::this_thread::sleep_for(std::chrono::duration<double, std::milli>(3000));
+
+
gripper_state = gripper.readOnce();
+
if (!gripper_state.is_grasped) {
+
std::cout << "Object lost." << std::endl;
+
return -1;
+
}
+
+
std::cout << "Grasped object, will release it now." << std::endl;
+
gripper.stop();
+
} catch (franka::Exception const& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
Maintains a network connection to the gripper, provides the current gripper state,...
Definition: gripper.h:27
+
GripperState readOnce() const
Waits for a gripper state update and returns it.
+
bool grasp(double width, double speed, double force, double epsilon_inner=0.005, double epsilon_outer=0.005) const
Grasps an object.
+
bool stop() const
Stops a currently running gripper move or grasp.
+
bool homing() const
Performs homing of the gripper.
+
Contains exception definitions.
+
Contains the franka::Gripper type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the gripper state.
Definition: gripper_state.h:20
+
bool is_grasped
Indicates whether an object is currently grasped.
Definition: gripper_state.h:38
+
double max_width
Maximum gripper opening width.
Definition: gripper_state.h:33
+
+ + + + diff --git a/gripper_8h.html b/gripper_8h.html new file mode 100644 index 00000000..5ba4c6fe --- /dev/null +++ b/gripper_8h.html @@ -0,0 +1,124 @@ + + + + + + + +libfranka: include/franka/gripper.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+ +
+
gripper.h File Reference
+
+
+ +

Contains the franka::Gripper type. +More...

+
#include <cstdint>
+#include <memory>
+#include <string>
+#include <franka/gripper_state.h>
+
+Include dependency graph for gripper.h:
+
+
+ + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  franka::Gripper
 Maintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands. More...
 
+

Detailed Description

+

Contains the franka::Gripper type.

+
+ + + + diff --git a/gripper_8h__incl.map b/gripper_8h__incl.map new file mode 100644 index 00000000..ab2f3ac5 --- /dev/null +++ b/gripper_8h__incl.map @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/gripper_8h__incl.md5 b/gripper_8h__incl.md5 new file mode 100644 index 00000000..3dadb7a6 --- /dev/null +++ b/gripper_8h__incl.md5 @@ -0,0 +1 @@ +901bc6e28dd18b0229ad7be1abed0856 \ No newline at end of file diff --git a/gripper_8h__incl.png b/gripper_8h__incl.png new file mode 100644 index 00000000..1b163fa9 Binary files /dev/null and b/gripper_8h__incl.png differ diff --git a/gripper_8h_source.html b/gripper_8h_source.html new file mode 100644 index 00000000..b22b8db0 --- /dev/null +++ b/gripper_8h_source.html @@ -0,0 +1,154 @@ + + + + + + + +libfranka: include/franka/gripper.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
gripper.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <cstdint>
+
6 #include <memory>
+
7 #include <string>
+
8 
+
9 #include <franka/gripper_state.h>
+
10 
+
16 namespace franka {
+
17 
+
18 class Network;
+
19 
+
27 class Gripper {
+
28  public:
+
32  using ServerVersion = uint16_t;
+
33 
+
42  explicit Gripper(const std::string& franka_address);
+
43 
+
49  Gripper(Gripper&& gripper) noexcept;
+
50 
+
58  Gripper& operator=(Gripper&& gripper) noexcept;
+
59 
+
63  ~Gripper() noexcept;
+
64 
+
78  bool homing() const;
+
79 
+
99  bool grasp(double width,
+
100  double speed,
+
101  double force,
+
102  double epsilon_inner = 0.005,
+
103  double epsilon_outer = 0.005) const;
+
104 
+
116  bool move(double width, double speed) const;
+
117 
+
126  bool stop() const;
+
127 
+ +
137 
+
143  ServerVersion serverVersion() const noexcept;
+
144 
+
146  Gripper(const Gripper&) = delete;
+
147  Gripper& operator=(const Gripper&) = delete;
+
149 
+
150  private:
+
151  std::unique_ptr<Network> network_;
+
152 
+
153  uint16_t ri_version_;
+
154 };
+
155 
+
156 } // namespace franka
+
Maintains a network connection to the gripper, provides the current gripper state,...
Definition: gripper.h:27
+
Gripper(const std::string &franka_address)
Establishes a connection with a gripper connected to a robot.
+
bool move(double width, double speed) const
Moves the gripper fingers to a specified width.
+
Gripper & operator=(Gripper &&gripper) noexcept
Move-assigns this Gripper from another Gripper instance.
+
uint16_t ServerVersion
Version of the gripper server.
Definition: gripper.h:32
+
ServerVersion serverVersion() const noexcept
Returns the software version reported by the connected server.
+
Gripper(Gripper &&gripper) noexcept
Move-constructs a new Gripper instance.
+
GripperState readOnce() const
Waits for a gripper state update and returns it.
+
bool grasp(double width, double speed, double force, double epsilon_inner=0.005, double epsilon_outer=0.005) const
Grasps an object.
+
bool stop() const
Stops a currently running gripper move or grasp.
+
~Gripper() noexcept
Closes the connection.
+
bool homing() const
Performs homing of the gripper.
+
Contains the franka::GripperState type.
+
Describes the gripper state.
Definition: gripper_state.h:20
+
+ + + + diff --git a/gripper__state_8h.html b/gripper__state_8h.html new file mode 100644 index 00000000..35f213c1 --- /dev/null +++ b/gripper__state_8h.html @@ -0,0 +1,175 @@ + + + + + + + +libfranka: include/franka/gripper_state.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+ +
+
gripper_state.h File Reference
+
+
+ +

Contains the franka::GripperState type. +More...

+
#include <cstdint>
+#include <ostream>
+#include <franka/duration.h>
+
+Include dependency graph for gripper_state.h:
+
+
+ + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

struct  franka::GripperState
 Describes the gripper state. More...
 
+ + + + +

+Functions

std::ostream & franka::operator<< (std::ostream &ostream, const franka::GripperState &gripper_state)
 Streams the gripper state as JSON object: {"field_name_1": value, "field_name_2": value, ...}. More...
 
+

Detailed Description

+

Contains the franka::GripperState type.

+

Function Documentation

+ +

◆ operator<<()

+ +
+
+ + + + + + + + + + + + + + + + + + +
std::ostream& franka::operator<< (std::ostream & ostream,
const franka::GripperStategripper_state 
)
+
+ +

Streams the gripper state as JSON object: {"field_name_1": value, "field_name_2": value, ...}.

+
Parameters
+ + + +
[in]ostreamOstream instance
[in]gripper_stateGripperState struct instance to stream
+
+
+
Returns
Ostream instance
+ +
+
+
+ + + + diff --git a/gripper__state_8h__dep__incl.map b/gripper__state_8h__dep__incl.map new file mode 100644 index 00000000..a901b8b1 --- /dev/null +++ b/gripper__state_8h__dep__incl.map @@ -0,0 +1,4 @@ + + + + diff --git a/gripper__state_8h__dep__incl.md5 b/gripper__state_8h__dep__incl.md5 new file mode 100644 index 00000000..288bf031 --- /dev/null +++ b/gripper__state_8h__dep__incl.md5 @@ -0,0 +1 @@ +d32d8979af59cc2c6a9ca0ac1fb83187 \ No newline at end of file diff --git a/gripper__state_8h__dep__incl.png b/gripper__state_8h__dep__incl.png new file mode 100644 index 00000000..cc011854 Binary files /dev/null and b/gripper__state_8h__dep__incl.png differ diff --git a/gripper__state_8h__incl.map b/gripper__state_8h__incl.map new file mode 100644 index 00000000..357bc039 --- /dev/null +++ b/gripper__state_8h__incl.map @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/gripper__state_8h__incl.md5 b/gripper__state_8h__incl.md5 new file mode 100644 index 00000000..ad91ebad --- /dev/null +++ b/gripper__state_8h__incl.md5 @@ -0,0 +1 @@ +48bcfa77f3ca458b32475714d0daa0c4 \ No newline at end of file diff --git a/gripper__state_8h__incl.png b/gripper__state_8h__incl.png new file mode 100644 index 00000000..3311da16 Binary files /dev/null and b/gripper__state_8h__incl.png differ diff --git a/gripper__state_8h_source.html b/gripper__state_8h_source.html new file mode 100644 index 00000000..049c300b --- /dev/null +++ b/gripper__state_8h_source.html @@ -0,0 +1,123 @@ + + + + + + + +libfranka: include/franka/gripper_state.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
gripper_state.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <cstdint>
+
6 #include <ostream>
+
7 
+
8 #include <franka/duration.h>
+
9 
+
15 namespace franka {
+
16 
+
20 struct GripperState {
+
24  double width{};
+
25 
+
33  double max_width{};
+
34 
+
38  bool is_grasped{};
+
39 
+
43  uint16_t temperature{};
+
44 
+ +
49 };
+
50 
+
59 std::ostream& operator<<(std::ostream& ostream, const franka::GripperState& gripper_state);
+
60 
+
61 } // namespace franka
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Contains the franka::Duration type.
+
std::ostream & operator<<(std::ostream &ostream, const Errors &errors)
Streams the errors as JSON array.
+
Describes the gripper state.
Definition: gripper_state.h:20
+
Duration time
Strictly monotonically increasing timestamp since robot start.
Definition: gripper_state.h:48
+
bool is_grasped
Indicates whether an object is currently grasped.
Definition: gripper_state.h:38
+
uint16_t temperature
Current gripper temperature.
Definition: gripper_state.h:43
+
double max_width
Maximum gripper opening width.
Definition: gripper_state.h:33
+
double width
Current gripper opening width.
Definition: gripper_state.h:24
+
+ + + + diff --git a/hierarchy.html b/hierarchy.html new file mode 100644 index 00000000..16b3e3c5 --- /dev/null +++ b/hierarchy.html @@ -0,0 +1,124 @@ + + + + + + + +libfranka: Class Hierarchy + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
Class Hierarchy
+
+
+
+

Go to the graphical class hierarchy

+This inheritance list is sorted roughly, but not completely, alphabetically:
+
[detail level 123]
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
 Cfranka::ActiveControlBaseAllows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot
 Cfranka::ActiveControlDocumented in ActiveControlBase
 Cfranka::ActiveMotionGenerator< MotionGeneratorType >Allows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot
 Cfranka::ActiveTorqueControlAllows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot
 Cfranka::DurationRepresents a duration with millisecond resolution
 Cfranka::ErrorsEnumerates errors that can occur while controlling a franka::Robot
 Cfranka::FinishableHelper type for control and motion generation loops
 Cfranka::CartesianPoseStores values for Cartesian pose motion generation
 Cfranka::CartesianVelocitiesStores values for Cartesian velocity motion generation
 Cfranka::JointPositionsStores values for joint position motion generation
 Cfranka::JointVelocitiesStores values for joint velocity motion generation
 Cfranka::TorquesStores joint-level torque commands without gravity and friction
 Cfranka::GripperMaintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands
 Cfranka::GripperStateDescribes the gripper state
 Cfranka::ModelCalculates poses of joints and dynamic properties of the robot
 CMotionGeneratorAn example showing how to generate a joint pose motion to a goal position
 Cfranka::RecordOne row of the log contains a robot command of timestamp n and a corresponding robot state of timestamp n+1
 Cfranka::RobotMaintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot
 Cfranka::RobotCommandCommand sent to the robot
 CRobotModelBaseRobot dynamic parameters computed from the URDF model with Pinocchio
 Cfranka::RobotModelImplements RobotModelBase using Pinocchio
 Cfranka::RobotStateDescribes the robot state
 Cstd::runtime_error
 Cfranka::ExceptionBase class for all exceptions used by libfranka
 Cfranka::CommandExceptionCommandException is thrown if an error occurs during command execution
 Cfranka::ControlExceptionControlException is thrown if an error occurs during motion generation or torque control
 Cfranka::IncompatibleVersionExceptionIncompatibleVersionException is thrown if the robot does not support this version of libfranka
 Cfranka::InvalidOperationExceptionInvalidOperationException is thrown if an operation cannot be performed
 Cfranka::ModelExceptionModelException is thrown if an error occurs when loading the model library
 Cfranka::NetworkExceptionNetworkException is thrown if a connection to the robot cannot be established, or when a timeout occurs
 Cfranka::ProtocolExceptionProtocolException is thrown if the robot returns an incorrect message
 Cfranka::RealtimeExceptionRealtimeException is thrown if realtime priority cannot be set
 Cfranka::VacuumGripperMaintains a network connection to the vacuum gripper, provides the current vacuum gripper state, and allows the execution of commands
 Cfranka::VacuumGripperStateDescribes the vacuum gripper state
+
+
+ + + + diff --git a/index.html b/index.html new file mode 100644 index 00000000..58724c73 --- /dev/null +++ b/index.html @@ -0,0 +1,89 @@ + + + + + + + +libfranka: libfranka: C++ library for Franka Robotics research robots + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
libfranka: C++ library for Franka Robotics research robots
+
+
+

With this library, you can control research versions of Franka Robotics robots. See the Franka Control Interface (FCI) documentation for more information about what libfranka can do and how to set it up.

+

+License

+

libfranka is licensed under the Apache 2.0 license.

+
+
+ + + + diff --git a/inherit_graph_0.map b/inherit_graph_0.map new file mode 100644 index 00000000..7c1970ae --- /dev/null +++ b/inherit_graph_0.map @@ -0,0 +1,6 @@ + + + + + + diff --git a/inherit_graph_0.md5 b/inherit_graph_0.md5 new file mode 100644 index 00000000..cc90e884 --- /dev/null +++ b/inherit_graph_0.md5 @@ -0,0 +1 @@ +6581ec3ae7612b70562e6c6835abba71 \ No newline at end of file diff --git a/inherit_graph_0.png b/inherit_graph_0.png new file mode 100644 index 00000000..65930020 Binary files /dev/null and b/inherit_graph_0.png differ diff --git a/inherit_graph_1.map b/inherit_graph_1.map new file mode 100644 index 00000000..7ad0c002 --- /dev/null +++ b/inherit_graph_1.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_1.md5 b/inherit_graph_1.md5 new file mode 100644 index 00000000..51b7c9df --- /dev/null +++ b/inherit_graph_1.md5 @@ -0,0 +1 @@ +13cd79676d479a68b01d396da7372c91 \ No newline at end of file diff --git a/inherit_graph_1.png b/inherit_graph_1.png new file mode 100644 index 00000000..399c8e21 Binary files /dev/null and b/inherit_graph_1.png differ diff --git a/inherit_graph_10.map b/inherit_graph_10.map new file mode 100644 index 00000000..7abc423c --- /dev/null +++ b/inherit_graph_10.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_10.md5 b/inherit_graph_10.md5 new file mode 100644 index 00000000..525b258c --- /dev/null +++ b/inherit_graph_10.md5 @@ -0,0 +1 @@ +6976fec6e715fef5e88f59e9708c1db5 \ No newline at end of file diff --git a/inherit_graph_10.png b/inherit_graph_10.png new file mode 100644 index 00000000..4a048321 Binary files /dev/null and b/inherit_graph_10.png differ diff --git a/inherit_graph_11.map b/inherit_graph_11.map new file mode 100644 index 00000000..0a07dafc --- /dev/null +++ b/inherit_graph_11.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_11.md5 b/inherit_graph_11.md5 new file mode 100644 index 00000000..bd79b037 --- /dev/null +++ b/inherit_graph_11.md5 @@ -0,0 +1 @@ +c469eaaebbcf130bac248ac66f90522e \ No newline at end of file diff --git a/inherit_graph_11.png b/inherit_graph_11.png new file mode 100644 index 00000000..f708a3b2 Binary files /dev/null and b/inherit_graph_11.png differ diff --git a/inherit_graph_12.map b/inherit_graph_12.map new file mode 100644 index 00000000..e7b8a6c9 --- /dev/null +++ b/inherit_graph_12.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_12.md5 b/inherit_graph_12.md5 new file mode 100644 index 00000000..41719a0c --- /dev/null +++ b/inherit_graph_12.md5 @@ -0,0 +1 @@ +4a8c8ceec44157340d6aee9d76453557 \ No newline at end of file diff --git a/inherit_graph_12.png b/inherit_graph_12.png new file mode 100644 index 00000000..b0c72a85 Binary files /dev/null and b/inherit_graph_12.png differ diff --git a/inherit_graph_13.map b/inherit_graph_13.map new file mode 100644 index 00000000..e8cd44ec --- /dev/null +++ b/inherit_graph_13.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_13.md5 b/inherit_graph_13.md5 new file mode 100644 index 00000000..1f9de2e7 --- /dev/null +++ b/inherit_graph_13.md5 @@ -0,0 +1 @@ +4b95ee7a157a38077df907b190381db3 \ No newline at end of file diff --git a/inherit_graph_13.png b/inherit_graph_13.png new file mode 100644 index 00000000..f745ae08 Binary files /dev/null and b/inherit_graph_13.png differ diff --git a/inherit_graph_14.map b/inherit_graph_14.map new file mode 100644 index 00000000..b115b839 --- /dev/null +++ b/inherit_graph_14.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_14.md5 b/inherit_graph_14.md5 new file mode 100644 index 00000000..bad5aa85 --- /dev/null +++ b/inherit_graph_14.md5 @@ -0,0 +1 @@ +13beb2915ca39665fff8777a1a8d19d8 \ No newline at end of file diff --git a/inherit_graph_14.png b/inherit_graph_14.png new file mode 100644 index 00000000..1a377db7 Binary files /dev/null and b/inherit_graph_14.png differ diff --git a/inherit_graph_15.map b/inherit_graph_15.map new file mode 100644 index 00000000..b0602769 --- /dev/null +++ b/inherit_graph_15.map @@ -0,0 +1,4 @@ + + + + diff --git a/inherit_graph_15.md5 b/inherit_graph_15.md5 new file mode 100644 index 00000000..c2195cc7 --- /dev/null +++ b/inherit_graph_15.md5 @@ -0,0 +1 @@ +a2de1ef219d46378a0e42a83777fd91d \ No newline at end of file diff --git a/inherit_graph_15.png b/inherit_graph_15.png new file mode 100644 index 00000000..2b35dddd Binary files /dev/null and b/inherit_graph_15.png differ diff --git a/inherit_graph_2.map b/inherit_graph_2.map new file mode 100644 index 00000000..b41e75d4 --- /dev/null +++ b/inherit_graph_2.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_2.md5 b/inherit_graph_2.md5 new file mode 100644 index 00000000..5f0af392 --- /dev/null +++ b/inherit_graph_2.md5 @@ -0,0 +1 @@ +1b9c9ae28948ac70e25d962ab5665326 \ No newline at end of file diff --git a/inherit_graph_2.png b/inherit_graph_2.png new file mode 100644 index 00000000..63f01b97 Binary files /dev/null and b/inherit_graph_2.png differ diff --git a/inherit_graph_3.map b/inherit_graph_3.map new file mode 100644 index 00000000..8629045b --- /dev/null +++ b/inherit_graph_3.map @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/inherit_graph_3.md5 b/inherit_graph_3.md5 new file mode 100644 index 00000000..99861f52 --- /dev/null +++ b/inherit_graph_3.md5 @@ -0,0 +1 @@ +04cfceeb66575b4432938134a54baa55 \ No newline at end of file diff --git a/inherit_graph_3.png b/inherit_graph_3.png new file mode 100644 index 00000000..5092dc28 Binary files /dev/null and b/inherit_graph_3.png differ diff --git a/inherit_graph_4.map b/inherit_graph_4.map new file mode 100644 index 00000000..defb40c0 --- /dev/null +++ b/inherit_graph_4.map @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/inherit_graph_4.md5 b/inherit_graph_4.md5 new file mode 100644 index 00000000..d366728b --- /dev/null +++ b/inherit_graph_4.md5 @@ -0,0 +1 @@ +0cff89dce9d9ee11fbbc3746cd23348a \ No newline at end of file diff --git a/inherit_graph_4.png b/inherit_graph_4.png new file mode 100644 index 00000000..90e141e8 Binary files /dev/null and b/inherit_graph_4.png differ diff --git a/inherit_graph_5.map b/inherit_graph_5.map new file mode 100644 index 00000000..09162f22 --- /dev/null +++ b/inherit_graph_5.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_5.md5 b/inherit_graph_5.md5 new file mode 100644 index 00000000..8e97df25 --- /dev/null +++ b/inherit_graph_5.md5 @@ -0,0 +1 @@ +1fde7f606647fe5a1ef6f08c18fc38cf \ No newline at end of file diff --git a/inherit_graph_5.png b/inherit_graph_5.png new file mode 100644 index 00000000..ecbc971a Binary files /dev/null and b/inherit_graph_5.png differ diff --git a/inherit_graph_6.map b/inherit_graph_6.map new file mode 100644 index 00000000..98deff48 --- /dev/null +++ b/inherit_graph_6.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_6.md5 b/inherit_graph_6.md5 new file mode 100644 index 00000000..81eeb149 --- /dev/null +++ b/inherit_graph_6.md5 @@ -0,0 +1 @@ +6d7150c2026fa6a894ac6d82fb24e9c3 \ No newline at end of file diff --git a/inherit_graph_6.png b/inherit_graph_6.png new file mode 100644 index 00000000..518a3aee Binary files /dev/null and b/inherit_graph_6.png differ diff --git a/inherit_graph_7.map b/inherit_graph_7.map new file mode 100644 index 00000000..00eda5f9 --- /dev/null +++ b/inherit_graph_7.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_7.md5 b/inherit_graph_7.md5 new file mode 100644 index 00000000..305c69e2 --- /dev/null +++ b/inherit_graph_7.md5 @@ -0,0 +1 @@ +e5261aacf97f3320b4345b58f597b103 \ No newline at end of file diff --git a/inherit_graph_7.png b/inherit_graph_7.png new file mode 100644 index 00000000..a76fe759 Binary files /dev/null and b/inherit_graph_7.png differ diff --git a/inherit_graph_8.map b/inherit_graph_8.map new file mode 100644 index 00000000..401322fd --- /dev/null +++ b/inherit_graph_8.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_8.md5 b/inherit_graph_8.md5 new file mode 100644 index 00000000..64c8fac2 --- /dev/null +++ b/inherit_graph_8.md5 @@ -0,0 +1 @@ +0fd9e3718636c19d25379f06c5ea984a \ No newline at end of file diff --git a/inherit_graph_8.png b/inherit_graph_8.png new file mode 100644 index 00000000..9fe4f3c1 Binary files /dev/null and b/inherit_graph_8.png differ diff --git a/inherit_graph_9.map b/inherit_graph_9.map new file mode 100644 index 00000000..0a55956c --- /dev/null +++ b/inherit_graph_9.map @@ -0,0 +1,3 @@ + + + diff --git a/inherit_graph_9.md5 b/inherit_graph_9.md5 new file mode 100644 index 00000000..1e1c32c2 --- /dev/null +++ b/inherit_graph_9.md5 @@ -0,0 +1 @@ +ff3a4760b2d575b55047de9c87fc6141 \ No newline at end of file diff --git a/inherit_graph_9.png b/inherit_graph_9.png new file mode 100644 index 00000000..a79cda29 Binary files /dev/null and b/inherit_graph_9.png differ diff --git a/inherits.html b/inherits.html new file mode 100644 index 00000000..0de68be1 --- /dev/null +++ b/inherits.html @@ -0,0 +1,186 @@ + + + + + + + +libfranka: Class Hierarchy + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
Class Hierarchy
+
+
+ + + + + + + + + + + + + + + + + +
+ + + + + + +
+ + + +
+ + + +
+ + + + + + + + + + + + +
+ + + + + + + + +
+ + + +
+ + + +
+ + + +
+ + + +
+ + + +
+ + + +
+ + + +
+ + + +
+ + + +
+ + + +
+ + + + +
+
+ + + + diff --git a/joint_impedance_control_8cpp-example.html b/joint_impedance_control_8cpp-example.html new file mode 100644 index 00000000..755a5d0f --- /dev/null +++ b/joint_impedance_control_8cpp-example.html @@ -0,0 +1,322 @@ + + + + + + + +libfranka: joint_impedance_control.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
joint_impedance_control.cpp
+
+
+

An example showing a joint impedance type control that executes a Cartesian motion in the shape of a circle. The example illustrates how to use the internal inverse kinematics to map a Cartesian trajectory to joint space. The joint space target is tracked by an impedance control that additionally compensates coriolis terms using the libfranka model library. This example also serves to compare commanded vs. measured torques. The results are printed from a separate thread to avoid blocking print functions in the real-time loop.

+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <array>
+
#include <atomic>
+
#include <cmath>
+
#include <functional>
+
#include <iostream>
+
#include <iterator>
+
#include <mutex>
+
#include <thread>
+
+ + +
#include <franka/model.h>
+ +
#include <franka/robot.h>
+
+ +
+
namespace {
+
template <class T, size_t N>
+
std::ostream& operator<<(std::ostream& ostream, const std::array<T, N>& array) {
+
ostream << "[";
+
std::copy(array.cbegin(), array.cend() - 1, std::ostream_iterator<T>(ostream, ","));
+
std::copy(array.cend() - 1, array.cend(), std::ostream_iterator<T>(ostream));
+
ostream << "]";
+
return ostream;
+
}
+
} // anonymous namespace
+
+
int main(int argc, char** argv) {
+
// Check whether the required arguments were passed.
+
if (argc != 2) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
+
return -1;
+
}
+
// Set and initialize trajectory parameters.
+
const double radius = 0.05;
+
const double vel_max = 0.25;
+
const double acceleration_time = 2.0;
+
const double run_time = 20.0;
+
// Set print rate for comparing commanded vs. measured torques.
+
const double print_rate = 10.0;
+
+
double vel_current = 0.0;
+
double angle = 0.0;
+
double time = 0.0;
+
+
// Initialize data fields for the print thread.
+
struct {
+
std::mutex mutex;
+
bool has_data;
+
std::array<double, 7> tau_d_last;
+
franka::RobotState robot_state;
+
std::array<double, 7> gravity;
+
} print_data{};
+
std::atomic_bool running{true};
+
+
// Start print thread.
+
std::thread print_thread([print_rate, &print_data, &running]() {
+
while (running) {
+
// Sleep to achieve the desired print rate.
+
std::this_thread::sleep_for(
+
std::chrono::milliseconds(static_cast<int>((1.0 / print_rate * 1000.0))));
+
+
// Try to lock data to avoid read write collisions.
+
if (print_data.mutex.try_lock()) {
+
if (print_data.has_data) {
+
std::array<double, 7> tau_error{};
+
double error_rms(0.0);
+
std::array<double, 7> tau_d_actual{};
+
for (size_t i = 0; i < 7; ++i) {
+
tau_d_actual[i] = print_data.tau_d_last[i] + print_data.gravity[i];
+
tau_error[i] = tau_d_actual[i] - print_data.robot_state.tau_J[i];
+
error_rms += std::pow(tau_error[i], 2.0) / tau_error.size();
+
}
+
error_rms = std::sqrt(error_rms);
+
+
// Print data to console
+
std::cout << "tau_error [Nm]: " << tau_error << std::endl
+
<< "tau_commanded [Nm]: " << tau_d_actual << std::endl
+
<< "tau_measured [Nm]: " << print_data.robot_state.tau_J << std::endl
+
<< "root mean square of tau_error [Nm]: " << error_rms << std::endl
+
<< "-----------------------" << std::endl;
+
print_data.has_data = false;
+
}
+
print_data.mutex.unlock();
+
}
+
}
+
});
+
+
try {
+
// Connect to robot.
+
franka::Robot robot(argv[1]);
+ +
+
// First move the robot to a suitable joint configuration
+
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
+
MotionGenerator motion_generator(0.5, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Finished moving to initial joint configuration." << std::endl;
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+
robot.setCollisionBehavior(
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
+
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
+
+
// Load the kinematics and dynamics model.
+
franka::Model model = robot.loadModel();
+
+
std::array<double, 16> initial_pose;
+
+
// Define callback function to send Cartesian pose goals to get inverse kinematics solved.
+
auto cartesian_pose_callback = [=, &time, &vel_current, &running, &angle, &initial_pose](
+
const franka::RobotState& robot_state,
+ +
// Update time.
+
time += period.toSec();
+
+
if (time == 0.0) {
+
// Read the initial pose to start the motion from in the first time step.
+
initial_pose = robot_state.O_T_EE_c;
+
}
+
+
// Compute Cartesian velocity.
+
if (vel_current < vel_max && time < run_time) {
+
vel_current += period.toSec() * std::fabs(vel_max / acceleration_time);
+
}
+
if (vel_current > 0.0 && time > run_time) {
+
vel_current -= period.toSec() * std::fabs(vel_max / acceleration_time);
+
}
+
vel_current = std::fmax(vel_current, 0.0);
+
vel_current = std::fmin(vel_current, vel_max);
+
+
// Compute new angle for our circular trajectory.
+
angle += period.toSec() * vel_current / std::fabs(radius);
+
if (angle > 2 * M_PI) {
+
angle -= 2 * M_PI;
+
}
+
+
// Compute relative y and z positions of desired pose.
+
double delta_y = radius * (1 - std::cos(angle));
+
double delta_z = radius * std::sin(angle);
+
franka::CartesianPose pose_desired = initial_pose;
+
pose_desired.O_T_EE[13] += delta_y;
+
pose_desired.O_T_EE[14] += delta_z;
+
+
// Send desired pose.
+
if (time >= run_time + acceleration_time) {
+
running = false;
+
return franka::MotionFinished(pose_desired);
+
}
+
+
return pose_desired;
+
};
+
+
// Set gains for the joint impedance control.
+
// Stiffness
+
const std::array<double, 7> k_gains = {{600.0, 600.0, 600.0, 600.0, 250.0, 150.0, 50.0}};
+
// Damping
+
const std::array<double, 7> d_gains = {{50.0, 50.0, 50.0, 50.0, 30.0, 25.0, 15.0}};
+
+
// Define callback for the joint torque control loop.
+ +
impedance_control_callback =
+
[&print_data, &model, k_gains, d_gains](
+
const franka::RobotState& state, franka::Duration /*period*/) -> franka::Torques {
+
// Read current coriolis terms from model.
+
std::array<double, 7> coriolis = model.coriolis(state);
+
+
// Compute torque command from joint impedance control law.
+
// Note: The answer to our Cartesian pose inverse kinematics is always in state.q_d with one
+
// time step delay.
+
std::array<double, 7> tau_d_calculated;
+
for (size_t i = 0; i < 7; i++) {
+
tau_d_calculated[i] =
+
k_gains[i] * (state.q_d[i] - state.q[i]) - d_gains[i] * state.dq[i] + coriolis[i];
+
}
+
+
// The following line is only necessary for printing the rate limited torque. As we activated
+
// rate limiting for the control loop (activated by default), the torque would anyway be
+
// adjusted!
+
std::array<double, 7> tau_d_rate_limited =
+
franka::limitRate(franka::kMaxTorqueRate, tau_d_calculated, state.tau_J_d);
+
+
// Update data to print.
+
if (print_data.mutex.try_lock()) {
+
print_data.has_data = true;
+
print_data.robot_state = state;
+
print_data.tau_d_last = tau_d_rate_limited;
+
print_data.gravity = model.gravity(state);
+
print_data.mutex.unlock();
+
}
+
+
// Send torque command.
+
return tau_d_rate_limited;
+
};
+
+
// Start real-time control loop.
+
robot.control(impedance_control_callback, cartesian_pose_callback);
+
+
} catch (const franka::Exception& ex) {
+
running = false;
+
std::cerr << ex.what() << std::endl;
+
}
+
+
if (print_thread.joinable()) {
+
print_thread.join();
+
}
+
return 0;
+
}
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Stores values for Cartesian pose motion generation.
Definition: control_types.h:127
+
std::array< double, 16 > O_T_EE
Homogeneous transformation , column major, that transforms from the end effector frame to base frame...
Definition: control_types.h:178
+
Represents a duration with millisecond resolution.
Definition: duration.h:19
+
Calculates poses of joints and dynamic properties of the robot.
Definition: model.h:52
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
+
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
+
Contains the franka::Duration type.
+
std::ostream & operator<<(std::ostream &ostream, const Errors &errors)
Streams the errors as JSON array.
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains model library types.
+
Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity,...
+
std::array< double, 7 > limitRate(const std::array< double, 7 > &max_derivatives, const std::array< double, 7 > &commanded_values, const std::array< double, 7 > &last_commanded_values)
Limits the rate of an input vector of per-joint commands considering the maximum allowed time derivat...
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/joint_point_to_point_motion_8cpp-example.html b/joint_point_to_point_motion_8cpp-example.html new file mode 100644 index 00000000..11b7afd8 --- /dev/null +++ b/joint_point_to_point_motion_8cpp-example.html @@ -0,0 +1,145 @@ + + + + + + + +libfranka: joint_point_to_point_motion.cpp + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + +
+ +
+
+ + +
+ +
+ +
+
+
joint_point_to_point_motion.cpp
+
+
+

An example that moves the robot to a target position by commanding joint positions.

Warning
Before executing this example, make sure there is enough space in front of the robot.
+
// Copyright (c) 2023 Franka Robotics GmbH
+
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
#include <cmath>
+
#include <iostream>
+
+ +
#include <franka/robot.h>
+
+ +
+
int main(int argc, char** argv) {
+
if (argc != 10) {
+
std::cerr << "Usage: " << argv[0] << " <robot-hostname> "
+
<< "<joint0> <joint1> <joint2> <joint3> <joint4> <joint5> <joint6> "
+
<< "<speed-factor>" << std::endl
+
<< "joint0 to joint6 are joint angles in [rad]." << std::endl
+
<< "speed-factor must be between zero and one." << std::endl;
+
return -1;
+
}
+
try {
+
franka::Robot robot(argv[1]);
+ +
+
std::array<double, 7> q_goal;
+
for (size_t i = 0; i < 7; i++) {
+
q_goal[i] = std::stod(argv[i + 2]);
+
}
+
double speed_factor = std::stod(argv[9]);
+
+
// Set additional parameters always before the control loop, NEVER in the control loop!
+
// Set collision behavior.
+ +
{{20.0, 20.0, 20.0, 20.0, 20.0, 20.0, 20.0}}, {{20.0, 20.0, 20.0, 20.0, 20.0, 20.0, 20.0}},
+
{{10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0}}, {{10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0}},
+
{{20.0, 20.0, 20.0, 20.0, 20.0, 20.0}}, {{20.0, 20.0, 20.0, 20.0, 20.0, 20.0}},
+
{{10.0, 10.0, 10.0, 10.0, 10.0, 10.0}}, {{10.0, 10.0, 10.0, 10.0, 10.0, 10.0}});
+
+
MotionGenerator motion_generator(speed_factor, q_goal);
+
std::cout << "WARNING: This example will move the robot! "
+
<< "Please make sure to have the user stop button at hand!" << std::endl
+
<< "Press Enter to continue..." << std::endl;
+
std::cin.ignore();
+
robot.control(motion_generator);
+
std::cout << "Motion finished" << std::endl;
+
} catch (const franka::Exception& e) {
+
std::cout << e.what() << std::endl;
+
return -1;
+
}
+
+
return 0;
+
}
+
An example showing how to generate a joint pose motion to a goal position.
Definition: examples_common.h:31
+
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition: robot.h:68
+
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
+
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.
+
Contains common types and functions for the examples.
+
void setDefaultBehavior(franka::Robot &robot)
Sets a default collision behavior, joint impedance and Cartesian impedance.
Definition: examples_common.cpp:12
+
Contains exception definitions.
+
Contains the franka::Robot type.
+
Base class for all exceptions used by libfranka.
Definition: exception.h:20
+
+ + + + diff --git a/jquery.js b/jquery.js new file mode 100644 index 00000000..103c32d7 --- /dev/null +++ b/jquery.js @@ -0,0 +1,35 @@ +/*! jQuery v3.4.1 | (c) JS Foundation and other contributors | jquery.org/license */ +!function(e,t){"use strict";"object"==typeof module&&"object"==typeof module.exports?module.exports=e.document?t(e,!0):function(e){if(!e.document)throw new Error("jQuery requires a window with a document");return t(e)}:t(e)}("undefined"!=typeof window?window:this,function(C,e){"use strict";var t=[],E=C.document,r=Object.getPrototypeOf,s=t.slice,g=t.concat,u=t.push,i=t.indexOf,n={},o=n.toString,v=n.hasOwnProperty,a=v.toString,l=a.call(Object),y={},m=function(e){return"function"==typeof e&&"number"!=typeof e.nodeType},x=function(e){return null!=e&&e===e.window},c={type:!0,src:!0,nonce:!0,noModule:!0};function b(e,t,n){var r,i,o=(n=n||E).createElement("script");if(o.text=e,t)for(r in c)(i=t[r]||t.getAttribute&&t.getAttribute(r))&&o.setAttribute(r,i);n.head.appendChild(o).parentNode.removeChild(o)}function w(e){return null==e?e+"":"object"==typeof e||"function"==typeof e?n[o.call(e)]||"object":typeof e}var f="3.4.1",k=function(e,t){return new k.fn.init(e,t)},p=/^[\s\uFEFF\xA0]+|[\s\uFEFF\xA0]+$/g;function d(e){var t=!!e&&"length"in e&&e.length,n=w(e);return!m(e)&&!x(e)&&("array"===n||0===t||"number"==typeof t&&0+~]|"+M+")"+M+"*"),U=new RegExp(M+"|>"),X=new RegExp($),V=new RegExp("^"+I+"$"),G={ID:new RegExp("^#("+I+")"),CLASS:new RegExp("^\\.("+I+")"),TAG:new RegExp("^("+I+"|[*])"),ATTR:new RegExp("^"+W),PSEUDO:new RegExp("^"+$),CHILD:new RegExp("^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\("+M+"*(even|odd|(([+-]|)(\\d*)n|)"+M+"*(?:([+-]|)"+M+"*(\\d+)|))"+M+"*\\)|)","i"),bool:new RegExp("^(?:"+R+")$","i"),needsContext:new RegExp("^"+M+"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\("+M+"*((?:-\\d)?\\d*)"+M+"*\\)|)(?=[^-]|$)","i")},Y=/HTML$/i,Q=/^(?:input|select|textarea|button)$/i,J=/^h\d$/i,K=/^[^{]+\{\s*\[native \w/,Z=/^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/,ee=/[+~]/,te=new RegExp("\\\\([\\da-f]{1,6}"+M+"?|("+M+")|.)","ig"),ne=function(e,t,n){var r="0x"+t-65536;return r!=r||n?t:r<0?String.fromCharCode(r+65536):String.fromCharCode(r>>10|55296,1023&r|56320)},re=/([\0-\x1f\x7f]|^-?\d)|^-$|[^\0-\x1f\x7f-\uFFFF\w-]/g,ie=function(e,t){return t?"\0"===e?"\ufffd":e.slice(0,-1)+"\\"+e.charCodeAt(e.length-1).toString(16)+" ":"\\"+e},oe=function(){T()},ae=be(function(e){return!0===e.disabled&&"fieldset"===e.nodeName.toLowerCase()},{dir:"parentNode",next:"legend"});try{H.apply(t=O.call(m.childNodes),m.childNodes),t[m.childNodes.length].nodeType}catch(e){H={apply:t.length?function(e,t){L.apply(e,O.call(t))}:function(e,t){var n=e.length,r=0;while(e[n++]=t[r++]);e.length=n-1}}}function se(t,e,n,r){var i,o,a,s,u,l,c,f=e&&e.ownerDocument,p=e?e.nodeType:9;if(n=n||[],"string"!=typeof t||!t||1!==p&&9!==p&&11!==p)return n;if(!r&&((e?e.ownerDocument||e:m)!==C&&T(e),e=e||C,E)){if(11!==p&&(u=Z.exec(t)))if(i=u[1]){if(9===p){if(!(a=e.getElementById(i)))return n;if(a.id===i)return n.push(a),n}else if(f&&(a=f.getElementById(i))&&y(e,a)&&a.id===i)return n.push(a),n}else{if(u[2])return H.apply(n,e.getElementsByTagName(t)),n;if((i=u[3])&&d.getElementsByClassName&&e.getElementsByClassName)return H.apply(n,e.getElementsByClassName(i)),n}if(d.qsa&&!A[t+" "]&&(!v||!v.test(t))&&(1!==p||"object"!==e.nodeName.toLowerCase())){if(c=t,f=e,1===p&&U.test(t)){(s=e.getAttribute("id"))?s=s.replace(re,ie):e.setAttribute("id",s=k),o=(l=h(t)).length;while(o--)l[o]="#"+s+" "+xe(l[o]);c=l.join(","),f=ee.test(t)&&ye(e.parentNode)||e}try{return H.apply(n,f.querySelectorAll(c)),n}catch(e){A(t,!0)}finally{s===k&&e.removeAttribute("id")}}}return g(t.replace(B,"$1"),e,n,r)}function ue(){var r=[];return function e(t,n){return r.push(t+" ")>b.cacheLength&&delete e[r.shift()],e[t+" "]=n}}function le(e){return e[k]=!0,e}function ce(e){var t=C.createElement("fieldset");try{return!!e(t)}catch(e){return!1}finally{t.parentNode&&t.parentNode.removeChild(t),t=null}}function fe(e,t){var n=e.split("|"),r=n.length;while(r--)b.attrHandle[n[r]]=t}function pe(e,t){var n=t&&e,r=n&&1===e.nodeType&&1===t.nodeType&&e.sourceIndex-t.sourceIndex;if(r)return r;if(n)while(n=n.nextSibling)if(n===t)return-1;return e?1:-1}function de(t){return function(e){return"input"===e.nodeName.toLowerCase()&&e.type===t}}function he(n){return function(e){var t=e.nodeName.toLowerCase();return("input"===t||"button"===t)&&e.type===n}}function ge(t){return function(e){return"form"in e?e.parentNode&&!1===e.disabled?"label"in e?"label"in e.parentNode?e.parentNode.disabled===t:e.disabled===t:e.isDisabled===t||e.isDisabled!==!t&&ae(e)===t:e.disabled===t:"label"in e&&e.disabled===t}}function ve(a){return le(function(o){return o=+o,le(function(e,t){var n,r=a([],e.length,o),i=r.length;while(i--)e[n=r[i]]&&(e[n]=!(t[n]=e[n]))})})}function ye(e){return e&&"undefined"!=typeof e.getElementsByTagName&&e}for(e in d=se.support={},i=se.isXML=function(e){var t=e.namespaceURI,n=(e.ownerDocument||e).documentElement;return!Y.test(t||n&&n.nodeName||"HTML")},T=se.setDocument=function(e){var t,n,r=e?e.ownerDocument||e:m;return r!==C&&9===r.nodeType&&r.documentElement&&(a=(C=r).documentElement,E=!i(C),m!==C&&(n=C.defaultView)&&n.top!==n&&(n.addEventListener?n.addEventListener("unload",oe,!1):n.attachEvent&&n.attachEvent("onunload",oe)),d.attributes=ce(function(e){return e.className="i",!e.getAttribute("className")}),d.getElementsByTagName=ce(function(e){return e.appendChild(C.createComment("")),!e.getElementsByTagName("*").length}),d.getElementsByClassName=K.test(C.getElementsByClassName),d.getById=ce(function(e){return a.appendChild(e).id=k,!C.getElementsByName||!C.getElementsByName(k).length}),d.getById?(b.filter.ID=function(e){var t=e.replace(te,ne);return function(e){return e.getAttribute("id")===t}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n=t.getElementById(e);return n?[n]:[]}}):(b.filter.ID=function(e){var n=e.replace(te,ne);return function(e){var t="undefined"!=typeof e.getAttributeNode&&e.getAttributeNode("id");return t&&t.value===n}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n,r,i,o=t.getElementById(e);if(o){if((n=o.getAttributeNode("id"))&&n.value===e)return[o];i=t.getElementsByName(e),r=0;while(o=i[r++])if((n=o.getAttributeNode("id"))&&n.value===e)return[o]}return[]}}),b.find.TAG=d.getElementsByTagName?function(e,t){return"undefined"!=typeof t.getElementsByTagName?t.getElementsByTagName(e):d.qsa?t.querySelectorAll(e):void 0}:function(e,t){var n,r=[],i=0,o=t.getElementsByTagName(e);if("*"===e){while(n=o[i++])1===n.nodeType&&r.push(n);return r}return o},b.find.CLASS=d.getElementsByClassName&&function(e,t){if("undefined"!=typeof t.getElementsByClassName&&E)return t.getElementsByClassName(e)},s=[],v=[],(d.qsa=K.test(C.querySelectorAll))&&(ce(function(e){a.appendChild(e).innerHTML="",e.querySelectorAll("[msallowcapture^='']").length&&v.push("[*^$]="+M+"*(?:''|\"\")"),e.querySelectorAll("[selected]").length||v.push("\\["+M+"*(?:value|"+R+")"),e.querySelectorAll("[id~="+k+"-]").length||v.push("~="),e.querySelectorAll(":checked").length||v.push(":checked"),e.querySelectorAll("a#"+k+"+*").length||v.push(".#.+[+~]")}),ce(function(e){e.innerHTML="";var t=C.createElement("input");t.setAttribute("type","hidden"),e.appendChild(t).setAttribute("name","D"),e.querySelectorAll("[name=d]").length&&v.push("name"+M+"*[*^$|!~]?="),2!==e.querySelectorAll(":enabled").length&&v.push(":enabled",":disabled"),a.appendChild(e).disabled=!0,2!==e.querySelectorAll(":disabled").length&&v.push(":enabled",":disabled"),e.querySelectorAll("*,:x"),v.push(",.*:")})),(d.matchesSelector=K.test(c=a.matches||a.webkitMatchesSelector||a.mozMatchesSelector||a.oMatchesSelector||a.msMatchesSelector))&&ce(function(e){d.disconnectedMatch=c.call(e,"*"),c.call(e,"[s!='']:x"),s.push("!=",$)}),v=v.length&&new RegExp(v.join("|")),s=s.length&&new RegExp(s.join("|")),t=K.test(a.compareDocumentPosition),y=t||K.test(a.contains)?function(e,t){var n=9===e.nodeType?e.documentElement:e,r=t&&t.parentNode;return e===r||!(!r||1!==r.nodeType||!(n.contains?n.contains(r):e.compareDocumentPosition&&16&e.compareDocumentPosition(r)))}:function(e,t){if(t)while(t=t.parentNode)if(t===e)return!0;return!1},D=t?function(e,t){if(e===t)return l=!0,0;var n=!e.compareDocumentPosition-!t.compareDocumentPosition;return n||(1&(n=(e.ownerDocument||e)===(t.ownerDocument||t)?e.compareDocumentPosition(t):1)||!d.sortDetached&&t.compareDocumentPosition(e)===n?e===C||e.ownerDocument===m&&y(m,e)?-1:t===C||t.ownerDocument===m&&y(m,t)?1:u?P(u,e)-P(u,t):0:4&n?-1:1)}:function(e,t){if(e===t)return l=!0,0;var n,r=0,i=e.parentNode,o=t.parentNode,a=[e],s=[t];if(!i||!o)return e===C?-1:t===C?1:i?-1:o?1:u?P(u,e)-P(u,t):0;if(i===o)return pe(e,t);n=e;while(n=n.parentNode)a.unshift(n);n=t;while(n=n.parentNode)s.unshift(n);while(a[r]===s[r])r++;return r?pe(a[r],s[r]):a[r]===m?-1:s[r]===m?1:0}),C},se.matches=function(e,t){return se(e,null,null,t)},se.matchesSelector=function(e,t){if((e.ownerDocument||e)!==C&&T(e),d.matchesSelector&&E&&!A[t+" "]&&(!s||!s.test(t))&&(!v||!v.test(t)))try{var n=c.call(e,t);if(n||d.disconnectedMatch||e.document&&11!==e.document.nodeType)return n}catch(e){A(t,!0)}return 0":{dir:"parentNode",first:!0}," ":{dir:"parentNode"},"+":{dir:"previousSibling",first:!0},"~":{dir:"previousSibling"}},preFilter:{ATTR:function(e){return e[1]=e[1].replace(te,ne),e[3]=(e[3]||e[4]||e[5]||"").replace(te,ne),"~="===e[2]&&(e[3]=" "+e[3]+" "),e.slice(0,4)},CHILD:function(e){return e[1]=e[1].toLowerCase(),"nth"===e[1].slice(0,3)?(e[3]||se.error(e[0]),e[4]=+(e[4]?e[5]+(e[6]||1):2*("even"===e[3]||"odd"===e[3])),e[5]=+(e[7]+e[8]||"odd"===e[3])):e[3]&&se.error(e[0]),e},PSEUDO:function(e){var t,n=!e[6]&&e[2];return G.CHILD.test(e[0])?null:(e[3]?e[2]=e[4]||e[5]||"":n&&X.test(n)&&(t=h(n,!0))&&(t=n.indexOf(")",n.length-t)-n.length)&&(e[0]=e[0].slice(0,t),e[2]=n.slice(0,t)),e.slice(0,3))}},filter:{TAG:function(e){var t=e.replace(te,ne).toLowerCase();return"*"===e?function(){return!0}:function(e){return e.nodeName&&e.nodeName.toLowerCase()===t}},CLASS:function(e){var t=p[e+" "];return t||(t=new RegExp("(^|"+M+")"+e+"("+M+"|$)"))&&p(e,function(e){return t.test("string"==typeof e.className&&e.className||"undefined"!=typeof e.getAttribute&&e.getAttribute("class")||"")})},ATTR:function(n,r,i){return function(e){var t=se.attr(e,n);return null==t?"!="===r:!r||(t+="","="===r?t===i:"!="===r?t!==i:"^="===r?i&&0===t.indexOf(i):"*="===r?i&&-1:\x20\t\r\n\f]*)[\x20\t\r\n\f]*\/?>(?:<\/\1>|)$/i;function j(e,n,r){return m(n)?k.grep(e,function(e,t){return!!n.call(e,t,e)!==r}):n.nodeType?k.grep(e,function(e){return e===n!==r}):"string"!=typeof n?k.grep(e,function(e){return-1)[^>]*|#([\w-]+))$/;(k.fn.init=function(e,t,n){var r,i;if(!e)return this;if(n=n||q,"string"==typeof e){if(!(r="<"===e[0]&&">"===e[e.length-1]&&3<=e.length?[null,e,null]:L.exec(e))||!r[1]&&t)return!t||t.jquery?(t||n).find(e):this.constructor(t).find(e);if(r[1]){if(t=t instanceof k?t[0]:t,k.merge(this,k.parseHTML(r[1],t&&t.nodeType?t.ownerDocument||t:E,!0)),D.test(r[1])&&k.isPlainObject(t))for(r in t)m(this[r])?this[r](t[r]):this.attr(r,t[r]);return this}return(i=E.getElementById(r[2]))&&(this[0]=i,this.length=1),this}return e.nodeType?(this[0]=e,this.length=1,this):m(e)?void 0!==n.ready?n.ready(e):e(k):k.makeArray(e,this)}).prototype=k.fn,q=k(E);var H=/^(?:parents|prev(?:Until|All))/,O={children:!0,contents:!0,next:!0,prev:!0};function P(e,t){while((e=e[t])&&1!==e.nodeType);return e}k.fn.extend({has:function(e){var t=k(e,this),n=t.length;return this.filter(function(){for(var e=0;e\x20\t\r\n\f]*)/i,he=/^$|^module$|\/(?:java|ecma)script/i,ge={option:[1,""],thead:[1,"","
"],col:[2,"","
"],tr:[2,"","
"],td:[3,"","
"],_default:[0,"",""]};function ve(e,t){var n;return n="undefined"!=typeof e.getElementsByTagName?e.getElementsByTagName(t||"*"):"undefined"!=typeof e.querySelectorAll?e.querySelectorAll(t||"*"):[],void 0===t||t&&A(e,t)?k.merge([e],n):n}function ye(e,t){for(var n=0,r=e.length;nx",y.noCloneChecked=!!me.cloneNode(!0).lastChild.defaultValue;var Te=/^key/,Ce=/^(?:mouse|pointer|contextmenu|drag|drop)|click/,Ee=/^([^.]*)(?:\.(.+)|)/;function ke(){return!0}function Se(){return!1}function Ne(e,t){return e===function(){try{return E.activeElement}catch(e){}}()==("focus"===t)}function Ae(e,t,n,r,i,o){var a,s;if("object"==typeof t){for(s in"string"!=typeof n&&(r=r||n,n=void 0),t)Ae(e,s,n,r,t[s],o);return e}if(null==r&&null==i?(i=n,r=n=void 0):null==i&&("string"==typeof n?(i=r,r=void 0):(i=r,r=n,n=void 0)),!1===i)i=Se;else if(!i)return e;return 1===o&&(a=i,(i=function(e){return k().off(e),a.apply(this,arguments)}).guid=a.guid||(a.guid=k.guid++)),e.each(function(){k.event.add(this,t,i,r,n)})}function De(e,i,o){o?(Q.set(e,i,!1),k.event.add(e,i,{namespace:!1,handler:function(e){var t,n,r=Q.get(this,i);if(1&e.isTrigger&&this[i]){if(r.length)(k.event.special[i]||{}).delegateType&&e.stopPropagation();else if(r=s.call(arguments),Q.set(this,i,r),t=o(this,i),this[i](),r!==(n=Q.get(this,i))||t?Q.set(this,i,!1):n={},r!==n)return e.stopImmediatePropagation(),e.preventDefault(),n.value}else r.length&&(Q.set(this,i,{value:k.event.trigger(k.extend(r[0],k.Event.prototype),r.slice(1),this)}),e.stopImmediatePropagation())}})):void 0===Q.get(e,i)&&k.event.add(e,i,ke)}k.event={global:{},add:function(t,e,n,r,i){var o,a,s,u,l,c,f,p,d,h,g,v=Q.get(t);if(v){n.handler&&(n=(o=n).handler,i=o.selector),i&&k.find.matchesSelector(ie,i),n.guid||(n.guid=k.guid++),(u=v.events)||(u=v.events={}),(a=v.handle)||(a=v.handle=function(e){return"undefined"!=typeof k&&k.event.triggered!==e.type?k.event.dispatch.apply(t,arguments):void 0}),l=(e=(e||"").match(R)||[""]).length;while(l--)d=g=(s=Ee.exec(e[l])||[])[1],h=(s[2]||"").split(".").sort(),d&&(f=k.event.special[d]||{},d=(i?f.delegateType:f.bindType)||d,f=k.event.special[d]||{},c=k.extend({type:d,origType:g,data:r,handler:n,guid:n.guid,selector:i,needsContext:i&&k.expr.match.needsContext.test(i),namespace:h.join(".")},o),(p=u[d])||((p=u[d]=[]).delegateCount=0,f.setup&&!1!==f.setup.call(t,r,h,a)||t.addEventListener&&t.addEventListener(d,a)),f.add&&(f.add.call(t,c),c.handler.guid||(c.handler.guid=n.guid)),i?p.splice(p.delegateCount++,0,c):p.push(c),k.event.global[d]=!0)}},remove:function(e,t,n,r,i){var o,a,s,u,l,c,f,p,d,h,g,v=Q.hasData(e)&&Q.get(e);if(v&&(u=v.events)){l=(t=(t||"").match(R)||[""]).length;while(l--)if(d=g=(s=Ee.exec(t[l])||[])[1],h=(s[2]||"").split(".").sort(),d){f=k.event.special[d]||{},p=u[d=(r?f.delegateType:f.bindType)||d]||[],s=s[2]&&new RegExp("(^|\\.)"+h.join("\\.(?:.*\\.|)")+"(\\.|$)"),a=o=p.length;while(o--)c=p[o],!i&&g!==c.origType||n&&n.guid!==c.guid||s&&!s.test(c.namespace)||r&&r!==c.selector&&("**"!==r||!c.selector)||(p.splice(o,1),c.selector&&p.delegateCount--,f.remove&&f.remove.call(e,c));a&&!p.length&&(f.teardown&&!1!==f.teardown.call(e,h,v.handle)||k.removeEvent(e,d,v.handle),delete u[d])}else for(d in u)k.event.remove(e,d+t[l],n,r,!0);k.isEmptyObject(u)&&Q.remove(e,"handle events")}},dispatch:function(e){var t,n,r,i,o,a,s=k.event.fix(e),u=new Array(arguments.length),l=(Q.get(this,"events")||{})[s.type]||[],c=k.event.special[s.type]||{};for(u[0]=s,t=1;t\x20\t\r\n\f]*)[^>]*)\/>/gi,qe=/\s*$/g;function Oe(e,t){return A(e,"table")&&A(11!==t.nodeType?t:t.firstChild,"tr")&&k(e).children("tbody")[0]||e}function Pe(e){return e.type=(null!==e.getAttribute("type"))+"/"+e.type,e}function Re(e){return"true/"===(e.type||"").slice(0,5)?e.type=e.type.slice(5):e.removeAttribute("type"),e}function Me(e,t){var n,r,i,o,a,s,u,l;if(1===t.nodeType){if(Q.hasData(e)&&(o=Q.access(e),a=Q.set(t,o),l=o.events))for(i in delete a.handle,a.events={},l)for(n=0,r=l[i].length;n")},clone:function(e,t,n){var r,i,o,a,s,u,l,c=e.cloneNode(!0),f=oe(e);if(!(y.noCloneChecked||1!==e.nodeType&&11!==e.nodeType||k.isXMLDoc(e)))for(a=ve(c),r=0,i=(o=ve(e)).length;r").attr(n.scriptAttrs||{}).prop({charset:n.scriptCharset,src:n.url}).on("load error",i=function(e){r.remove(),i=null,e&&t("error"===e.type?404:200,e.type)}),E.head.appendChild(r[0])},abort:function(){i&&i()}}});var Vt,Gt=[],Yt=/(=)\?(?=&|$)|\?\?/;k.ajaxSetup({jsonp:"callback",jsonpCallback:function(){var e=Gt.pop()||k.expando+"_"+kt++;return this[e]=!0,e}}),k.ajaxPrefilter("json jsonp",function(e,t,n){var r,i,o,a=!1!==e.jsonp&&(Yt.test(e.url)?"url":"string"==typeof e.data&&0===(e.contentType||"").indexOf("application/x-www-form-urlencoded")&&Yt.test(e.data)&&"data");if(a||"jsonp"===e.dataTypes[0])return r=e.jsonpCallback=m(e.jsonpCallback)?e.jsonpCallback():e.jsonpCallback,a?e[a]=e[a].replace(Yt,"$1"+r):!1!==e.jsonp&&(e.url+=(St.test(e.url)?"&":"?")+e.jsonp+"="+r),e.converters["script json"]=function(){return o||k.error(r+" was not called"),o[0]},e.dataTypes[0]="json",i=C[r],C[r]=function(){o=arguments},n.always(function(){void 0===i?k(C).removeProp(r):C[r]=i,e[r]&&(e.jsonpCallback=t.jsonpCallback,Gt.push(r)),o&&m(i)&&i(o[0]),o=i=void 0}),"script"}),y.createHTMLDocument=((Vt=E.implementation.createHTMLDocument("").body).innerHTML="
",2===Vt.childNodes.length),k.parseHTML=function(e,t,n){return"string"!=typeof e?[]:("boolean"==typeof t&&(n=t,t=!1),t||(y.createHTMLDocument?((r=(t=E.implementation.createHTMLDocument("")).createElement("base")).href=E.location.href,t.head.appendChild(r)):t=E),o=!n&&[],(i=D.exec(e))?[t.createElement(i[1])]:(i=we([e],t,o),o&&o.length&&k(o).remove(),k.merge([],i.childNodes)));var r,i,o},k.fn.load=function(e,t,n){var r,i,o,a=this,s=e.indexOf(" ");return-1").append(k.parseHTML(e)).find(r):e)}).always(n&&function(e,t){a.each(function(){n.apply(this,o||[e.responseText,t,e])})}),this},k.each(["ajaxStart","ajaxStop","ajaxComplete","ajaxError","ajaxSuccess","ajaxSend"],function(e,t){k.fn[t]=function(e){return this.on(t,e)}}),k.expr.pseudos.animated=function(t){return k.grep(k.timers,function(e){return t===e.elem}).length},k.offset={setOffset:function(e,t,n){var r,i,o,a,s,u,l=k.css(e,"position"),c=k(e),f={};"static"===l&&(e.style.position="relative"),s=c.offset(),o=k.css(e,"top"),u=k.css(e,"left"),("absolute"===l||"fixed"===l)&&-1<(o+u).indexOf("auto")?(a=(r=c.position()).top,i=r.left):(a=parseFloat(o)||0,i=parseFloat(u)||0),m(t)&&(t=t.call(e,n,k.extend({},s))),null!=t.top&&(f.top=t.top-s.top+a),null!=t.left&&(f.left=t.left-s.left+i),"using"in t?t.using.call(e,f):c.css(f)}},k.fn.extend({offset:function(t){if(arguments.length)return void 0===t?this:this.each(function(e){k.offset.setOffset(this,t,e)});var e,n,r=this[0];return r?r.getClientRects().length?(e=r.getBoundingClientRect(),n=r.ownerDocument.defaultView,{top:e.top+n.pageYOffset,left:e.left+n.pageXOffset}):{top:0,left:0}:void 0},position:function(){if(this[0]){var e,t,n,r=this[0],i={top:0,left:0};if("fixed"===k.css(r,"position"))t=r.getBoundingClientRect();else{t=this.offset(),n=r.ownerDocument,e=r.offsetParent||n.documentElement;while(e&&(e===n.body||e===n.documentElement)&&"static"===k.css(e,"position"))e=e.parentNode;e&&e!==r&&1===e.nodeType&&((i=k(e).offset()).top+=k.css(e,"borderTopWidth",!0),i.left+=k.css(e,"borderLeftWidth",!0))}return{top:t.top-i.top-k.css(r,"marginTop",!0),left:t.left-i.left-k.css(r,"marginLeft",!0)}}},offsetParent:function(){return this.map(function(){var e=this.offsetParent;while(e&&"static"===k.css(e,"position"))e=e.offsetParent;return e||ie})}}),k.each({scrollLeft:"pageXOffset",scrollTop:"pageYOffset"},function(t,i){var o="pageYOffset"===i;k.fn[t]=function(e){return _(this,function(e,t,n){var r;if(x(e)?r=e:9===e.nodeType&&(r=e.defaultView),void 0===n)return r?r[i]:e[t];r?r.scrollTo(o?r.pageXOffset:n,o?n:r.pageYOffset):e[t]=n},t,e,arguments.length)}}),k.each(["top","left"],function(e,n){k.cssHooks[n]=ze(y.pixelPosition,function(e,t){if(t)return t=_e(e,n),$e.test(t)?k(e).position()[n]+"px":t})}),k.each({Height:"height",Width:"width"},function(a,s){k.each({padding:"inner"+a,content:s,"":"outer"+a},function(r,o){k.fn[o]=function(e,t){var n=arguments.length&&(r||"boolean"!=typeof e),i=r||(!0===e||!0===t?"margin":"border");return _(this,function(e,t,n){var r;return x(e)?0===o.indexOf("outer")?e["inner"+a]:e.document.documentElement["client"+a]:9===e.nodeType?(r=e.documentElement,Math.max(e.body["scroll"+a],r["scroll"+a],e.body["offset"+a],r["offset"+a],r["client"+a])):void 0===n?k.css(e,t,i):k.style(e,t,n,i)},s,n?e:void 0,n)}})}),k.each("blur focus focusin focusout resize scroll click dblclick mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave change select submit keydown keypress keyup contextmenu".split(" "),function(e,n){k.fn[n]=function(e,t){return 0a;a++)for(i in o[a])n=o[a][i],o[a].hasOwnProperty(i)&&void 0!==n&&(e[i]=t.isPlainObject(n)?t.isPlainObject(e[i])?t.widget.extend({},e[i],n):t.widget.extend({},n):n);return e},t.widget.bridge=function(e,i){var n=i.prototype.widgetFullName||e;t.fn[e]=function(o){var a="string"==typeof o,r=s.call(arguments,1),h=this;return a?this.length||"instance"!==o?this.each(function(){var i,s=t.data(this,n);return"instance"===o?(h=s,!1):s?t.isFunction(s[o])&&"_"!==o.charAt(0)?(i=s[o].apply(s,r),i!==s&&void 0!==i?(h=i&&i.jquery?h.pushStack(i.get()):i,!1):void 0):t.error("no such method '"+o+"' for "+e+" widget instance"):t.error("cannot call methods on "+e+" prior to initialization; "+"attempted to call method '"+o+"'")}):h=void 0:(r.length&&(o=t.widget.extend.apply(null,[o].concat(r))),this.each(function(){var e=t.data(this,n);e?(e.option(o||{}),e._init&&e._init()):t.data(this,n,new i(o,this))})),h}},t.Widget=function(){},t.Widget._childConstructors=[],t.Widget.prototype={widgetName:"widget",widgetEventPrefix:"",defaultElement:"
",options:{classes:{},disabled:!1,create:null},_createWidget:function(e,s){s=t(s||this.defaultElement||this)[0],this.element=t(s),this.uuid=i++,this.eventNamespace="."+this.widgetName+this.uuid,this.bindings=t(),this.hoverable=t(),this.focusable=t(),this.classesElementLookup={},s!==this&&(t.data(s,this.widgetFullName,this),this._on(!0,this.element,{remove:function(t){t.target===s&&this.destroy()}}),this.document=t(s.style?s.ownerDocument:s.document||s),this.window=t(this.document[0].defaultView||this.document[0].parentWindow)),this.options=t.widget.extend({},this.options,this._getCreateOptions(),e),this._create(),this.options.disabled&&this._setOptionDisabled(this.options.disabled),this._trigger("create",null,this._getCreateEventData()),this._init()},_getCreateOptions:function(){return{}},_getCreateEventData:t.noop,_create:t.noop,_init:t.noop,destroy:function(){var e=this;this._destroy(),t.each(this.classesElementLookup,function(t,i){e._removeClass(i,t)}),this.element.off(this.eventNamespace).removeData(this.widgetFullName),this.widget().off(this.eventNamespace).removeAttr("aria-disabled"),this.bindings.off(this.eventNamespace)},_destroy:t.noop,widget:function(){return this.element},option:function(e,i){var s,n,o,a=e;if(0===arguments.length)return t.widget.extend({},this.options);if("string"==typeof e)if(a={},s=e.split("."),e=s.shift(),s.length){for(n=a[e]=t.widget.extend({},this.options[e]),o=0;s.length-1>o;o++)n[s[o]]=n[s[o]]||{},n=n[s[o]];if(e=s.pop(),1===arguments.length)return void 0===n[e]?null:n[e];n[e]=i}else{if(1===arguments.length)return void 0===this.options[e]?null:this.options[e];a[e]=i}return this._setOptions(a),this},_setOptions:function(t){var e;for(e in t)this._setOption(e,t[e]);return this},_setOption:function(t,e){return"classes"===t&&this._setOptionClasses(e),this.options[t]=e,"disabled"===t&&this._setOptionDisabled(e),this},_setOptionClasses:function(e){var i,s,n;for(i in e)n=this.classesElementLookup[i],e[i]!==this.options.classes[i]&&n&&n.length&&(s=t(n.get()),this._removeClass(n,i),s.addClass(this._classes({element:s,keys:i,classes:e,add:!0})))},_setOptionDisabled:function(t){this._toggleClass(this.widget(),this.widgetFullName+"-disabled",null,!!t),t&&(this._removeClass(this.hoverable,null,"ui-state-hover"),this._removeClass(this.focusable,null,"ui-state-focus"))},enable:function(){return this._setOptions({disabled:!1})},disable:function(){return this._setOptions({disabled:!0})},_classes:function(e){function i(i,o){var a,r;for(r=0;i.length>r;r++)a=n.classesElementLookup[i[r]]||t(),a=e.add?t(t.unique(a.get().concat(e.element.get()))):t(a.not(e.element).get()),n.classesElementLookup[i[r]]=a,s.push(i[r]),o&&e.classes[i[r]]&&s.push(e.classes[i[r]])}var s=[],n=this;return e=t.extend({element:this.element,classes:this.options.classes||{}},e),this._on(e.element,{remove:"_untrackClassesElement"}),e.keys&&i(e.keys.match(/\S+/g)||[],!0),e.extra&&i(e.extra.match(/\S+/g)||[]),s.join(" ")},_untrackClassesElement:function(e){var i=this;t.each(i.classesElementLookup,function(s,n){-1!==t.inArray(e.target,n)&&(i.classesElementLookup[s]=t(n.not(e.target).get()))})},_removeClass:function(t,e,i){return this._toggleClass(t,e,i,!1)},_addClass:function(t,e,i){return this._toggleClass(t,e,i,!0)},_toggleClass:function(t,e,i,s){s="boolean"==typeof s?s:i;var n="string"==typeof t||null===t,o={extra:n?e:i,keys:n?t:e,element:n?this.element:t,add:s};return o.element.toggleClass(this._classes(o),s),this},_on:function(e,i,s){var n,o=this;"boolean"!=typeof e&&(s=i,i=e,e=!1),s?(i=n=t(i),this.bindings=this.bindings.add(i)):(s=i,i=this.element,n=this.widget()),t.each(s,function(s,a){function r(){return e||o.options.disabled!==!0&&!t(this).hasClass("ui-state-disabled")?("string"==typeof a?o[a]:a).apply(o,arguments):void 0}"string"!=typeof a&&(r.guid=a.guid=a.guid||r.guid||t.guid++);var h=s.match(/^([\w:-]*)\s*(.*)$/),l=h[1]+o.eventNamespace,c=h[2];c?n.on(l,c,r):i.on(l,r)})},_off:function(e,i){i=(i||"").split(" ").join(this.eventNamespace+" ")+this.eventNamespace,e.off(i).off(i),this.bindings=t(this.bindings.not(e).get()),this.focusable=t(this.focusable.not(e).get()),this.hoverable=t(this.hoverable.not(e).get())},_delay:function(t,e){function i(){return("string"==typeof t?s[t]:t).apply(s,arguments)}var s=this;return setTimeout(i,e||0)},_hoverable:function(e){this.hoverable=this.hoverable.add(e),this._on(e,{mouseenter:function(e){this._addClass(t(e.currentTarget),null,"ui-state-hover")},mouseleave:function(e){this._removeClass(t(e.currentTarget),null,"ui-state-hover")}})},_focusable:function(e){this.focusable=this.focusable.add(e),this._on(e,{focusin:function(e){this._addClass(t(e.currentTarget),null,"ui-state-focus")},focusout:function(e){this._removeClass(t(e.currentTarget),null,"ui-state-focus")}})},_trigger:function(e,i,s){var n,o,a=this.options[e];if(s=s||{},i=t.Event(i),i.type=(e===this.widgetEventPrefix?e:this.widgetEventPrefix+e).toLowerCase(),i.target=this.element[0],o=i.originalEvent)for(n in o)n in i||(i[n]=o[n]);return this.element.trigger(i,s),!(t.isFunction(a)&&a.apply(this.element[0],[i].concat(s))===!1||i.isDefaultPrevented())}},t.each({show:"fadeIn",hide:"fadeOut"},function(e,i){t.Widget.prototype["_"+e]=function(s,n,o){"string"==typeof n&&(n={effect:n});var a,r=n?n===!0||"number"==typeof n?i:n.effect||i:e;n=n||{},"number"==typeof n&&(n={duration:n}),a=!t.isEmptyObject(n),n.complete=o,n.delay&&s.delay(n.delay),a&&t.effects&&t.effects.effect[r]?s[e](n):r!==e&&s[r]?s[r](n.duration,n.easing,o):s.queue(function(i){t(this)[e](),o&&o.call(s[0]),i()})}}),t.widget,function(){function e(t,e,i){return[parseFloat(t[0])*(u.test(t[0])?e/100:1),parseFloat(t[1])*(u.test(t[1])?i/100:1)]}function i(e,i){return parseInt(t.css(e,i),10)||0}function s(e){var i=e[0];return 9===i.nodeType?{width:e.width(),height:e.height(),offset:{top:0,left:0}}:t.isWindow(i)?{width:e.width(),height:e.height(),offset:{top:e.scrollTop(),left:e.scrollLeft()}}:i.preventDefault?{width:0,height:0,offset:{top:i.pageY,left:i.pageX}}:{width:e.outerWidth(),height:e.outerHeight(),offset:e.offset()}}var n,o=Math.max,a=Math.abs,r=/left|center|right/,h=/top|center|bottom/,l=/[\+\-]\d+(\.[\d]+)?%?/,c=/^\w+/,u=/%$/,d=t.fn.position;t.position={scrollbarWidth:function(){if(void 0!==n)return n;var e,i,s=t("
"),o=s.children()[0];return t("body").append(s),e=o.offsetWidth,s.css("overflow","scroll"),i=o.offsetWidth,e===i&&(i=s[0].clientWidth),s.remove(),n=e-i},getScrollInfo:function(e){var i=e.isWindow||e.isDocument?"":e.element.css("overflow-x"),s=e.isWindow||e.isDocument?"":e.element.css("overflow-y"),n="scroll"===i||"auto"===i&&e.widthi?"left":e>0?"right":"center",vertical:0>r?"top":s>0?"bottom":"middle"};l>p&&p>a(e+i)&&(u.horizontal="center"),c>f&&f>a(s+r)&&(u.vertical="middle"),u.important=o(a(e),a(i))>o(a(s),a(r))?"horizontal":"vertical",n.using.call(this,t,u)}),h.offset(t.extend(D,{using:r}))})},t.ui.position={fit:{left:function(t,e){var i,s=e.within,n=s.isWindow?s.scrollLeft:s.offset.left,a=s.width,r=t.left-e.collisionPosition.marginLeft,h=n-r,l=r+e.collisionWidth-a-n;e.collisionWidth>a?h>0&&0>=l?(i=t.left+h+e.collisionWidth-a-n,t.left+=h-i):t.left=l>0&&0>=h?n:h>l?n+a-e.collisionWidth:n:h>0?t.left+=h:l>0?t.left-=l:t.left=o(t.left-r,t.left)},top:function(t,e){var i,s=e.within,n=s.isWindow?s.scrollTop:s.offset.top,a=e.within.height,r=t.top-e.collisionPosition.marginTop,h=n-r,l=r+e.collisionHeight-a-n;e.collisionHeight>a?h>0&&0>=l?(i=t.top+h+e.collisionHeight-a-n,t.top+=h-i):t.top=l>0&&0>=h?n:h>l?n+a-e.collisionHeight:n:h>0?t.top+=h:l>0?t.top-=l:t.top=o(t.top-r,t.top)}},flip:{left:function(t,e){var i,s,n=e.within,o=n.offset.left+n.scrollLeft,r=n.width,h=n.isWindow?n.scrollLeft:n.offset.left,l=t.left-e.collisionPosition.marginLeft,c=l-h,u=l+e.collisionWidth-r-h,d="left"===e.my[0]?-e.elemWidth:"right"===e.my[0]?e.elemWidth:0,p="left"===e.at[0]?e.targetWidth:"right"===e.at[0]?-e.targetWidth:0,f=-2*e.offset[0];0>c?(i=t.left+d+p+f+e.collisionWidth-r-o,(0>i||a(c)>i)&&(t.left+=d+p+f)):u>0&&(s=t.left-e.collisionPosition.marginLeft+d+p+f-h,(s>0||u>a(s))&&(t.left+=d+p+f))},top:function(t,e){var i,s,n=e.within,o=n.offset.top+n.scrollTop,r=n.height,h=n.isWindow?n.scrollTop:n.offset.top,l=t.top-e.collisionPosition.marginTop,c=l-h,u=l+e.collisionHeight-r-h,d="top"===e.my[1],p=d?-e.elemHeight:"bottom"===e.my[1]?e.elemHeight:0,f="top"===e.at[1]?e.targetHeight:"bottom"===e.at[1]?-e.targetHeight:0,m=-2*e.offset[1];0>c?(s=t.top+p+f+m+e.collisionHeight-r-o,(0>s||a(c)>s)&&(t.top+=p+f+m)):u>0&&(i=t.top-e.collisionPosition.marginTop+p+f+m-h,(i>0||u>a(i))&&(t.top+=p+f+m))}},flipfit:{left:function(){t.ui.position.flip.left.apply(this,arguments),t.ui.position.fit.left.apply(this,arguments)},top:function(){t.ui.position.flip.top.apply(this,arguments),t.ui.position.fit.top.apply(this,arguments)}}}}(),t.ui.position,t.extend(t.expr[":"],{data:t.expr.createPseudo?t.expr.createPseudo(function(e){return function(i){return!!t.data(i,e)}}):function(e,i,s){return!!t.data(e,s[3])}}),t.fn.extend({disableSelection:function(){var t="onselectstart"in document.createElement("div")?"selectstart":"mousedown";return function(){return this.on(t+".ui-disableSelection",function(t){t.preventDefault()})}}(),enableSelection:function(){return this.off(".ui-disableSelection")}}),t.ui.focusable=function(i,s){var n,o,a,r,h,l=i.nodeName.toLowerCase();return"area"===l?(n=i.parentNode,o=n.name,i.href&&o&&"map"===n.nodeName.toLowerCase()?(a=t("img[usemap='#"+o+"']"),a.length>0&&a.is(":visible")):!1):(/^(input|select|textarea|button|object)$/.test(l)?(r=!i.disabled,r&&(h=t(i).closest("fieldset")[0],h&&(r=!h.disabled))):r="a"===l?i.href||s:s,r&&t(i).is(":visible")&&e(t(i)))},t.extend(t.expr[":"],{focusable:function(e){return t.ui.focusable(e,null!=t.attr(e,"tabindex"))}}),t.ui.focusable,t.fn.form=function(){return"string"==typeof this[0].form?this.closest("form"):t(this[0].form)},t.ui.formResetMixin={_formResetHandler:function(){var e=t(this);setTimeout(function(){var i=e.data("ui-form-reset-instances");t.each(i,function(){this.refresh()})})},_bindFormResetHandler:function(){if(this.form=this.element.form(),this.form.length){var t=this.form.data("ui-form-reset-instances")||[];t.length||this.form.on("reset.ui-form-reset",this._formResetHandler),t.push(this),this.form.data("ui-form-reset-instances",t)}},_unbindFormResetHandler:function(){if(this.form.length){var e=this.form.data("ui-form-reset-instances");e.splice(t.inArray(this,e),1),e.length?this.form.data("ui-form-reset-instances",e):this.form.removeData("ui-form-reset-instances").off("reset.ui-form-reset")}}},"1.7"===t.fn.jquery.substring(0,3)&&(t.each(["Width","Height"],function(e,i){function s(e,i,s,o){return t.each(n,function(){i-=parseFloat(t.css(e,"padding"+this))||0,s&&(i-=parseFloat(t.css(e,"border"+this+"Width"))||0),o&&(i-=parseFloat(t.css(e,"margin"+this))||0)}),i}var n="Width"===i?["Left","Right"]:["Top","Bottom"],o=i.toLowerCase(),a={innerWidth:t.fn.innerWidth,innerHeight:t.fn.innerHeight,outerWidth:t.fn.outerWidth,outerHeight:t.fn.outerHeight};t.fn["inner"+i]=function(e){return void 0===e?a["inner"+i].call(this):this.each(function(){t(this).css(o,s(this,e)+"px")})},t.fn["outer"+i]=function(e,n){return"number"!=typeof e?a["outer"+i].call(this,e):this.each(function(){t(this).css(o,s(this,e,!0,n)+"px")})}}),t.fn.addBack=function(t){return this.add(null==t?this.prevObject:this.prevObject.filter(t))}),t.ui.keyCode={BACKSPACE:8,COMMA:188,DELETE:46,DOWN:40,END:35,ENTER:13,ESCAPE:27,HOME:36,LEFT:37,PAGE_DOWN:34,PAGE_UP:33,PERIOD:190,RIGHT:39,SPACE:32,TAB:9,UP:38},t.ui.escapeSelector=function(){var t=/([!"#$%&'()*+,./:;<=>?@[\]^`{|}~])/g;return function(e){return e.replace(t,"\\$1")}}(),t.fn.labels=function(){var e,i,s,n,o;return this[0].labels&&this[0].labels.length?this.pushStack(this[0].labels):(n=this.eq(0).parents("label"),s=this.attr("id"),s&&(e=this.eq(0).parents().last(),o=e.add(e.length?e.siblings():this.siblings()),i="label[for='"+t.ui.escapeSelector(s)+"']",n=n.add(o.find(i).addBack(i))),this.pushStack(n))},t.fn.scrollParent=function(e){var i=this.css("position"),s="absolute"===i,n=e?/(auto|scroll|hidden)/:/(auto|scroll)/,o=this.parents().filter(function(){var e=t(this);return s&&"static"===e.css("position")?!1:n.test(e.css("overflow")+e.css("overflow-y")+e.css("overflow-x"))}).eq(0);return"fixed"!==i&&o.length?o:t(this[0].ownerDocument||document)},t.extend(t.expr[":"],{tabbable:function(e){var i=t.attr(e,"tabindex"),s=null!=i;return(!s||i>=0)&&t.ui.focusable(e,s)}}),t.fn.extend({uniqueId:function(){var t=0;return function(){return this.each(function(){this.id||(this.id="ui-id-"+ ++t)})}}(),removeUniqueId:function(){return this.each(function(){/^ui-id-\d+$/.test(this.id)&&t(this).removeAttr("id")})}}),t.ui.ie=!!/msie [\w.]+/.exec(navigator.userAgent.toLowerCase());var n=!1;t(document).on("mouseup",function(){n=!1}),t.widget("ui.mouse",{version:"1.12.1",options:{cancel:"input, textarea, button, select, option",distance:1,delay:0},_mouseInit:function(){var e=this;this.element.on("mousedown."+this.widgetName,function(t){return e._mouseDown(t)}).on("click."+this.widgetName,function(i){return!0===t.data(i.target,e.widgetName+".preventClickEvent")?(t.removeData(i.target,e.widgetName+".preventClickEvent"),i.stopImmediatePropagation(),!1):void 0}),this.started=!1},_mouseDestroy:function(){this.element.off("."+this.widgetName),this._mouseMoveDelegate&&this.document.off("mousemove."+this.widgetName,this._mouseMoveDelegate).off("mouseup."+this.widgetName,this._mouseUpDelegate)},_mouseDown:function(e){if(!n){this._mouseMoved=!1,this._mouseStarted&&this._mouseUp(e),this._mouseDownEvent=e;var i=this,s=1===e.which,o="string"==typeof this.options.cancel&&e.target.nodeName?t(e.target).closest(this.options.cancel).length:!1;return s&&!o&&this._mouseCapture(e)?(this.mouseDelayMet=!this.options.delay,this.mouseDelayMet||(this._mouseDelayTimer=setTimeout(function(){i.mouseDelayMet=!0},this.options.delay)),this._mouseDistanceMet(e)&&this._mouseDelayMet(e)&&(this._mouseStarted=this._mouseStart(e)!==!1,!this._mouseStarted)?(e.preventDefault(),!0):(!0===t.data(e.target,this.widgetName+".preventClickEvent")&&t.removeData(e.target,this.widgetName+".preventClickEvent"),this._mouseMoveDelegate=function(t){return i._mouseMove(t)},this._mouseUpDelegate=function(t){return i._mouseUp(t)},this.document.on("mousemove."+this.widgetName,this._mouseMoveDelegate).on("mouseup."+this.widgetName,this._mouseUpDelegate),e.preventDefault(),n=!0,!0)):!0}},_mouseMove:function(e){if(this._mouseMoved){if(t.ui.ie&&(!document.documentMode||9>document.documentMode)&&!e.button)return this._mouseUp(e);if(!e.which)if(e.originalEvent.altKey||e.originalEvent.ctrlKey||e.originalEvent.metaKey||e.originalEvent.shiftKey)this.ignoreMissingWhich=!0;else if(!this.ignoreMissingWhich)return this._mouseUp(e)}return(e.which||e.button)&&(this._mouseMoved=!0),this._mouseStarted?(this._mouseDrag(e),e.preventDefault()):(this._mouseDistanceMet(e)&&this._mouseDelayMet(e)&&(this._mouseStarted=this._mouseStart(this._mouseDownEvent,e)!==!1,this._mouseStarted?this._mouseDrag(e):this._mouseUp(e)),!this._mouseStarted)},_mouseUp:function(e){this.document.off("mousemove."+this.widgetName,this._mouseMoveDelegate).off("mouseup."+this.widgetName,this._mouseUpDelegate),this._mouseStarted&&(this._mouseStarted=!1,e.target===this._mouseDownEvent.target&&t.data(e.target,this.widgetName+".preventClickEvent",!0),this._mouseStop(e)),this._mouseDelayTimer&&(clearTimeout(this._mouseDelayTimer),delete this._mouseDelayTimer),this.ignoreMissingWhich=!1,n=!1,e.preventDefault()},_mouseDistanceMet:function(t){return Math.max(Math.abs(this._mouseDownEvent.pageX-t.pageX),Math.abs(this._mouseDownEvent.pageY-t.pageY))>=this.options.distance},_mouseDelayMet:function(){return this.mouseDelayMet},_mouseStart:function(){},_mouseDrag:function(){},_mouseStop:function(){},_mouseCapture:function(){return!0}}),t.ui.plugin={add:function(e,i,s){var n,o=t.ui[e].prototype;for(n in s)o.plugins[n]=o.plugins[n]||[],o.plugins[n].push([i,s[n]])},call:function(t,e,i,s){var n,o=t.plugins[e];if(o&&(s||t.element[0].parentNode&&11!==t.element[0].parentNode.nodeType))for(n=0;o.length>n;n++)t.options[o[n][0]]&&o[n][1].apply(t.element,i)}},t.widget("ui.resizable",t.ui.mouse,{version:"1.12.1",widgetEventPrefix:"resize",options:{alsoResize:!1,animate:!1,animateDuration:"slow",animateEasing:"swing",aspectRatio:!1,autoHide:!1,classes:{"ui-resizable-se":"ui-icon ui-icon-gripsmall-diagonal-se"},containment:!1,ghost:!1,grid:!1,handles:"e,s,se",helper:!1,maxHeight:null,maxWidth:null,minHeight:10,minWidth:10,zIndex:90,resize:null,start:null,stop:null},_num:function(t){return parseFloat(t)||0},_isNumber:function(t){return!isNaN(parseFloat(t))},_hasScroll:function(e,i){if("hidden"===t(e).css("overflow"))return!1;var s=i&&"left"===i?"scrollLeft":"scrollTop",n=!1;return e[s]>0?!0:(e[s]=1,n=e[s]>0,e[s]=0,n)},_create:function(){var e,i=this.options,s=this;this._addClass("ui-resizable"),t.extend(this,{_aspectRatio:!!i.aspectRatio,aspectRatio:i.aspectRatio,originalElement:this.element,_proportionallyResizeElements:[],_helper:i.helper||i.ghost||i.animate?i.helper||"ui-resizable-helper":null}),this.element[0].nodeName.match(/^(canvas|textarea|input|select|button|img)$/i)&&(this.element.wrap(t("
").css({position:this.element.css("position"),width:this.element.outerWidth(),height:this.element.outerHeight(),top:this.element.css("top"),left:this.element.css("left")})),this.element=this.element.parent().data("ui-resizable",this.element.resizable("instance")),this.elementIsWrapper=!0,e={marginTop:this.originalElement.css("marginTop"),marginRight:this.originalElement.css("marginRight"),marginBottom:this.originalElement.css("marginBottom"),marginLeft:this.originalElement.css("marginLeft")},this.element.css(e),this.originalElement.css("margin",0),this.originalResizeStyle=this.originalElement.css("resize"),this.originalElement.css("resize","none"),this._proportionallyResizeElements.push(this.originalElement.css({position:"static",zoom:1,display:"block"})),this.originalElement.css(e),this._proportionallyResize()),this._setupHandles(),i.autoHide&&t(this.element).on("mouseenter",function(){i.disabled||(s._removeClass("ui-resizable-autohide"),s._handles.show())}).on("mouseleave",function(){i.disabled||s.resizing||(s._addClass("ui-resizable-autohide"),s._handles.hide())}),this._mouseInit()},_destroy:function(){this._mouseDestroy();var e,i=function(e){t(e).removeData("resizable").removeData("ui-resizable").off(".resizable").find(".ui-resizable-handle").remove()};return this.elementIsWrapper&&(i(this.element),e=this.element,this.originalElement.css({position:e.css("position"),width:e.outerWidth(),height:e.outerHeight(),top:e.css("top"),left:e.css("left")}).insertAfter(e),e.remove()),this.originalElement.css("resize",this.originalResizeStyle),i(this.originalElement),this},_setOption:function(t,e){switch(this._super(t,e),t){case"handles":this._removeHandles(),this._setupHandles();break;default:}},_setupHandles:function(){var e,i,s,n,o,a=this.options,r=this;if(this.handles=a.handles||(t(".ui-resizable-handle",this.element).length?{n:".ui-resizable-n",e:".ui-resizable-e",s:".ui-resizable-s",w:".ui-resizable-w",se:".ui-resizable-se",sw:".ui-resizable-sw",ne:".ui-resizable-ne",nw:".ui-resizable-nw"}:"e,s,se"),this._handles=t(),this.handles.constructor===String)for("all"===this.handles&&(this.handles="n,e,s,w,se,sw,ne,nw"),s=this.handles.split(","),this.handles={},i=0;s.length>i;i++)e=t.trim(s[i]),n="ui-resizable-"+e,o=t("
"),this._addClass(o,"ui-resizable-handle "+n),o.css({zIndex:a.zIndex}),this.handles[e]=".ui-resizable-"+e,this.element.append(o);this._renderAxis=function(e){var i,s,n,o;e=e||this.element;for(i in this.handles)this.handles[i].constructor===String?this.handles[i]=this.element.children(this.handles[i]).first().show():(this.handles[i].jquery||this.handles[i].nodeType)&&(this.handles[i]=t(this.handles[i]),this._on(this.handles[i],{mousedown:r._mouseDown})),this.elementIsWrapper&&this.originalElement[0].nodeName.match(/^(textarea|input|select|button)$/i)&&(s=t(this.handles[i],this.element),o=/sw|ne|nw|se|n|s/.test(i)?s.outerHeight():s.outerWidth(),n=["padding",/ne|nw|n/.test(i)?"Top":/se|sw|s/.test(i)?"Bottom":/^e$/.test(i)?"Right":"Left"].join(""),e.css(n,o),this._proportionallyResize()),this._handles=this._handles.add(this.handles[i])},this._renderAxis(this.element),this._handles=this._handles.add(this.element.find(".ui-resizable-handle")),this._handles.disableSelection(),this._handles.on("mouseover",function(){r.resizing||(this.className&&(o=this.className.match(/ui-resizable-(se|sw|ne|nw|n|e|s|w)/i)),r.axis=o&&o[1]?o[1]:"se")}),a.autoHide&&(this._handles.hide(),this._addClass("ui-resizable-autohide"))},_removeHandles:function(){this._handles.remove()},_mouseCapture:function(e){var i,s,n=!1;for(i in this.handles)s=t(this.handles[i])[0],(s===e.target||t.contains(s,e.target))&&(n=!0);return!this.options.disabled&&n},_mouseStart:function(e){var i,s,n,o=this.options,a=this.element;return this.resizing=!0,this._renderProxy(),i=this._num(this.helper.css("left")),s=this._num(this.helper.css("top")),o.containment&&(i+=t(o.containment).scrollLeft()||0,s+=t(o.containment).scrollTop()||0),this.offset=this.helper.offset(),this.position={left:i,top:s},this.size=this._helper?{width:this.helper.width(),height:this.helper.height()}:{width:a.width(),height:a.height()},this.originalSize=this._helper?{width:a.outerWidth(),height:a.outerHeight()}:{width:a.width(),height:a.height()},this.sizeDiff={width:a.outerWidth()-a.width(),height:a.outerHeight()-a.height()},this.originalPosition={left:i,top:s},this.originalMousePosition={left:e.pageX,top:e.pageY},this.aspectRatio="number"==typeof o.aspectRatio?o.aspectRatio:this.originalSize.width/this.originalSize.height||1,n=t(".ui-resizable-"+this.axis).css("cursor"),t("body").css("cursor","auto"===n?this.axis+"-resize":n),this._addClass("ui-resizable-resizing"),this._propagate("start",e),!0},_mouseDrag:function(e){var i,s,n=this.originalMousePosition,o=this.axis,a=e.pageX-n.left||0,r=e.pageY-n.top||0,h=this._change[o];return this._updatePrevProperties(),h?(i=h.apply(this,[e,a,r]),this._updateVirtualBoundaries(e.shiftKey),(this._aspectRatio||e.shiftKey)&&(i=this._updateRatio(i,e)),i=this._respectSize(i,e),this._updateCache(i),this._propagate("resize",e),s=this._applyChanges(),!this._helper&&this._proportionallyResizeElements.length&&this._proportionallyResize(),t.isEmptyObject(s)||(this._updatePrevProperties(),this._trigger("resize",e,this.ui()),this._applyChanges()),!1):!1},_mouseStop:function(e){this.resizing=!1;var i,s,n,o,a,r,h,l=this.options,c=this;return this._helper&&(i=this._proportionallyResizeElements,s=i.length&&/textarea/i.test(i[0].nodeName),n=s&&this._hasScroll(i[0],"left")?0:c.sizeDiff.height,o=s?0:c.sizeDiff.width,a={width:c.helper.width()-o,height:c.helper.height()-n},r=parseFloat(c.element.css("left"))+(c.position.left-c.originalPosition.left)||null,h=parseFloat(c.element.css("top"))+(c.position.top-c.originalPosition.top)||null,l.animate||this.element.css(t.extend(a,{top:h,left:r})),c.helper.height(c.size.height),c.helper.width(c.size.width),this._helper&&!l.animate&&this._proportionallyResize()),t("body").css("cursor","auto"),this._removeClass("ui-resizable-resizing"),this._propagate("stop",e),this._helper&&this.helper.remove(),!1},_updatePrevProperties:function(){this.prevPosition={top:this.position.top,left:this.position.left},this.prevSize={width:this.size.width,height:this.size.height}},_applyChanges:function(){var t={};return this.position.top!==this.prevPosition.top&&(t.top=this.position.top+"px"),this.position.left!==this.prevPosition.left&&(t.left=this.position.left+"px"),this.size.width!==this.prevSize.width&&(t.width=this.size.width+"px"),this.size.height!==this.prevSize.height&&(t.height=this.size.height+"px"),this.helper.css(t),t},_updateVirtualBoundaries:function(t){var e,i,s,n,o,a=this.options;o={minWidth:this._isNumber(a.minWidth)?a.minWidth:0,maxWidth:this._isNumber(a.maxWidth)?a.maxWidth:1/0,minHeight:this._isNumber(a.minHeight)?a.minHeight:0,maxHeight:this._isNumber(a.maxHeight)?a.maxHeight:1/0},(this._aspectRatio||t)&&(e=o.minHeight*this.aspectRatio,s=o.minWidth/this.aspectRatio,i=o.maxHeight*this.aspectRatio,n=o.maxWidth/this.aspectRatio,e>o.minWidth&&(o.minWidth=e),s>o.minHeight&&(o.minHeight=s),o.maxWidth>i&&(o.maxWidth=i),o.maxHeight>n&&(o.maxHeight=n)),this._vBoundaries=o},_updateCache:function(t){this.offset=this.helper.offset(),this._isNumber(t.left)&&(this.position.left=t.left),this._isNumber(t.top)&&(this.position.top=t.top),this._isNumber(t.height)&&(this.size.height=t.height),this._isNumber(t.width)&&(this.size.width=t.width)},_updateRatio:function(t){var e=this.position,i=this.size,s=this.axis;return this._isNumber(t.height)?t.width=t.height*this.aspectRatio:this._isNumber(t.width)&&(t.height=t.width/this.aspectRatio),"sw"===s&&(t.left=e.left+(i.width-t.width),t.top=null),"nw"===s&&(t.top=e.top+(i.height-t.height),t.left=e.left+(i.width-t.width)),t},_respectSize:function(t){var e=this._vBoundaries,i=this.axis,s=this._isNumber(t.width)&&e.maxWidth&&e.maxWidtht.width,a=this._isNumber(t.height)&&e.minHeight&&e.minHeight>t.height,r=this.originalPosition.left+this.originalSize.width,h=this.originalPosition.top+this.originalSize.height,l=/sw|nw|w/.test(i),c=/nw|ne|n/.test(i);return o&&(t.width=e.minWidth),a&&(t.height=e.minHeight),s&&(t.width=e.maxWidth),n&&(t.height=e.maxHeight),o&&l&&(t.left=r-e.minWidth),s&&l&&(t.left=r-e.maxWidth),a&&c&&(t.top=h-e.minHeight),n&&c&&(t.top=h-e.maxHeight),t.width||t.height||t.left||!t.top?t.width||t.height||t.top||!t.left||(t.left=null):t.top=null,t},_getPaddingPlusBorderDimensions:function(t){for(var e=0,i=[],s=[t.css("borderTopWidth"),t.css("borderRightWidth"),t.css("borderBottomWidth"),t.css("borderLeftWidth")],n=[t.css("paddingTop"),t.css("paddingRight"),t.css("paddingBottom"),t.css("paddingLeft")];4>e;e++)i[e]=parseFloat(s[e])||0,i[e]+=parseFloat(n[e])||0;return{height:i[0]+i[2],width:i[1]+i[3]}},_proportionallyResize:function(){if(this._proportionallyResizeElements.length)for(var t,e=0,i=this.helper||this.element;this._proportionallyResizeElements.length>e;e++)t=this._proportionallyResizeElements[e],this.outerDimensions||(this.outerDimensions=this._getPaddingPlusBorderDimensions(t)),t.css({height:i.height()-this.outerDimensions.height||0,width:i.width()-this.outerDimensions.width||0})},_renderProxy:function(){var e=this.element,i=this.options;this.elementOffset=e.offset(),this._helper?(this.helper=this.helper||t("
"),this._addClass(this.helper,this._helper),this.helper.css({width:this.element.outerWidth(),height:this.element.outerHeight(),position:"absolute",left:this.elementOffset.left+"px",top:this.elementOffset.top+"px",zIndex:++i.zIndex}),this.helper.appendTo("body").disableSelection()):this.helper=this.element +},_change:{e:function(t,e){return{width:this.originalSize.width+e}},w:function(t,e){var i=this.originalSize,s=this.originalPosition;return{left:s.left+e,width:i.width-e}},n:function(t,e,i){var s=this.originalSize,n=this.originalPosition;return{top:n.top+i,height:s.height-i}},s:function(t,e,i){return{height:this.originalSize.height+i}},se:function(e,i,s){return t.extend(this._change.s.apply(this,arguments),this._change.e.apply(this,[e,i,s]))},sw:function(e,i,s){return t.extend(this._change.s.apply(this,arguments),this._change.w.apply(this,[e,i,s]))},ne:function(e,i,s){return t.extend(this._change.n.apply(this,arguments),this._change.e.apply(this,[e,i,s]))},nw:function(e,i,s){return t.extend(this._change.n.apply(this,arguments),this._change.w.apply(this,[e,i,s]))}},_propagate:function(e,i){t.ui.plugin.call(this,e,[i,this.ui()]),"resize"!==e&&this._trigger(e,i,this.ui())},plugins:{},ui:function(){return{originalElement:this.originalElement,element:this.element,helper:this.helper,position:this.position,size:this.size,originalSize:this.originalSize,originalPosition:this.originalPosition}}}),t.ui.plugin.add("resizable","animate",{stop:function(e){var i=t(this).resizable("instance"),s=i.options,n=i._proportionallyResizeElements,o=n.length&&/textarea/i.test(n[0].nodeName),a=o&&i._hasScroll(n[0],"left")?0:i.sizeDiff.height,r=o?0:i.sizeDiff.width,h={width:i.size.width-r,height:i.size.height-a},l=parseFloat(i.element.css("left"))+(i.position.left-i.originalPosition.left)||null,c=parseFloat(i.element.css("top"))+(i.position.top-i.originalPosition.top)||null;i.element.animate(t.extend(h,c&&l?{top:c,left:l}:{}),{duration:s.animateDuration,easing:s.animateEasing,step:function(){var s={width:parseFloat(i.element.css("width")),height:parseFloat(i.element.css("height")),top:parseFloat(i.element.css("top")),left:parseFloat(i.element.css("left"))};n&&n.length&&t(n[0]).css({width:s.width,height:s.height}),i._updateCache(s),i._propagate("resize",e)}})}}),t.ui.plugin.add("resizable","containment",{start:function(){var e,i,s,n,o,a,r,h=t(this).resizable("instance"),l=h.options,c=h.element,u=l.containment,d=u instanceof t?u.get(0):/parent/.test(u)?c.parent().get(0):u;d&&(h.containerElement=t(d),/document/.test(u)||u===document?(h.containerOffset={left:0,top:0},h.containerPosition={left:0,top:0},h.parentData={element:t(document),left:0,top:0,width:t(document).width(),height:t(document).height()||document.body.parentNode.scrollHeight}):(e=t(d),i=[],t(["Top","Right","Left","Bottom"]).each(function(t,s){i[t]=h._num(e.css("padding"+s))}),h.containerOffset=e.offset(),h.containerPosition=e.position(),h.containerSize={height:e.innerHeight()-i[3],width:e.innerWidth()-i[1]},s=h.containerOffset,n=h.containerSize.height,o=h.containerSize.width,a=h._hasScroll(d,"left")?d.scrollWidth:o,r=h._hasScroll(d)?d.scrollHeight:n,h.parentData={element:d,left:s.left,top:s.top,width:a,height:r}))},resize:function(e){var i,s,n,o,a=t(this).resizable("instance"),r=a.options,h=a.containerOffset,l=a.position,c=a._aspectRatio||e.shiftKey,u={top:0,left:0},d=a.containerElement,p=!0;d[0]!==document&&/static/.test(d.css("position"))&&(u=h),l.left<(a._helper?h.left:0)&&(a.size.width=a.size.width+(a._helper?a.position.left-h.left:a.position.left-u.left),c&&(a.size.height=a.size.width/a.aspectRatio,p=!1),a.position.left=r.helper?h.left:0),l.top<(a._helper?h.top:0)&&(a.size.height=a.size.height+(a._helper?a.position.top-h.top:a.position.top),c&&(a.size.width=a.size.height*a.aspectRatio,p=!1),a.position.top=a._helper?h.top:0),n=a.containerElement.get(0)===a.element.parent().get(0),o=/relative|absolute/.test(a.containerElement.css("position")),n&&o?(a.offset.left=a.parentData.left+a.position.left,a.offset.top=a.parentData.top+a.position.top):(a.offset.left=a.element.offset().left,a.offset.top=a.element.offset().top),i=Math.abs(a.sizeDiff.width+(a._helper?a.offset.left-u.left:a.offset.left-h.left)),s=Math.abs(a.sizeDiff.height+(a._helper?a.offset.top-u.top:a.offset.top-h.top)),i+a.size.width>=a.parentData.width&&(a.size.width=a.parentData.width-i,c&&(a.size.height=a.size.width/a.aspectRatio,p=!1)),s+a.size.height>=a.parentData.height&&(a.size.height=a.parentData.height-s,c&&(a.size.width=a.size.height*a.aspectRatio,p=!1)),p||(a.position.left=a.prevPosition.left,a.position.top=a.prevPosition.top,a.size.width=a.prevSize.width,a.size.height=a.prevSize.height)},stop:function(){var e=t(this).resizable("instance"),i=e.options,s=e.containerOffset,n=e.containerPosition,o=e.containerElement,a=t(e.helper),r=a.offset(),h=a.outerWidth()-e.sizeDiff.width,l=a.outerHeight()-e.sizeDiff.height;e._helper&&!i.animate&&/relative/.test(o.css("position"))&&t(this).css({left:r.left-n.left-s.left,width:h,height:l}),e._helper&&!i.animate&&/static/.test(o.css("position"))&&t(this).css({left:r.left-n.left-s.left,width:h,height:l})}}),t.ui.plugin.add("resizable","alsoResize",{start:function(){var e=t(this).resizable("instance"),i=e.options;t(i.alsoResize).each(function(){var e=t(this);e.data("ui-resizable-alsoresize",{width:parseFloat(e.width()),height:parseFloat(e.height()),left:parseFloat(e.css("left")),top:parseFloat(e.css("top"))})})},resize:function(e,i){var s=t(this).resizable("instance"),n=s.options,o=s.originalSize,a=s.originalPosition,r={height:s.size.height-o.height||0,width:s.size.width-o.width||0,top:s.position.top-a.top||0,left:s.position.left-a.left||0};t(n.alsoResize).each(function(){var e=t(this),s=t(this).data("ui-resizable-alsoresize"),n={},o=e.parents(i.originalElement[0]).length?["width","height"]:["width","height","top","left"];t.each(o,function(t,e){var i=(s[e]||0)+(r[e]||0);i&&i>=0&&(n[e]=i||null)}),e.css(n)})},stop:function(){t(this).removeData("ui-resizable-alsoresize")}}),t.ui.plugin.add("resizable","ghost",{start:function(){var e=t(this).resizable("instance"),i=e.size;e.ghost=e.originalElement.clone(),e.ghost.css({opacity:.25,display:"block",position:"relative",height:i.height,width:i.width,margin:0,left:0,top:0}),e._addClass(e.ghost,"ui-resizable-ghost"),t.uiBackCompat!==!1&&"string"==typeof e.options.ghost&&e.ghost.addClass(this.options.ghost),e.ghost.appendTo(e.helper)},resize:function(){var e=t(this).resizable("instance");e.ghost&&e.ghost.css({position:"relative",height:e.size.height,width:e.size.width})},stop:function(){var e=t(this).resizable("instance");e.ghost&&e.helper&&e.helper.get(0).removeChild(e.ghost.get(0))}}),t.ui.plugin.add("resizable","grid",{resize:function(){var e,i=t(this).resizable("instance"),s=i.options,n=i.size,o=i.originalSize,a=i.originalPosition,r=i.axis,h="number"==typeof s.grid?[s.grid,s.grid]:s.grid,l=h[0]||1,c=h[1]||1,u=Math.round((n.width-o.width)/l)*l,d=Math.round((n.height-o.height)/c)*c,p=o.width+u,f=o.height+d,m=s.maxWidth&&p>s.maxWidth,g=s.maxHeight&&f>s.maxHeight,_=s.minWidth&&s.minWidth>p,v=s.minHeight&&s.minHeight>f;s.grid=h,_&&(p+=l),v&&(f+=c),m&&(p-=l),g&&(f-=c),/^(se|s|e)$/.test(r)?(i.size.width=p,i.size.height=f):/^(ne)$/.test(r)?(i.size.width=p,i.size.height=f,i.position.top=a.top-d):/^(sw)$/.test(r)?(i.size.width=p,i.size.height=f,i.position.left=a.left-u):((0>=f-c||0>=p-l)&&(e=i._getPaddingPlusBorderDimensions(this)),f-c>0?(i.size.height=f,i.position.top=a.top-d):(f=c-e.height,i.size.height=f,i.position.top=a.top+o.height-f),p-l>0?(i.size.width=p,i.position.left=a.left-u):(p=l-e.width,i.size.width=p,i.position.left=a.left+o.width-p))}}),t.ui.resizable});/** + * Copyright (c) 2007 Ariel Flesler - aflesler ○ gmail • com | https://github.com/flesler + * Licensed under MIT + * @author Ariel Flesler + * @version 2.1.2 + */ +;(function(f){"use strict";"function"===typeof define&&define.amd?define(["jquery"],f):"undefined"!==typeof module&&module.exports?module.exports=f(require("jquery")):f(jQuery)})(function($){"use strict";function n(a){return!a.nodeName||-1!==$.inArray(a.nodeName.toLowerCase(),["iframe","#document","html","body"])}function h(a){return $.isFunction(a)||$.isPlainObject(a)?a:{top:a,left:a}}var p=$.scrollTo=function(a,d,b){return $(window).scrollTo(a,d,b)};p.defaults={axis:"xy",duration:0,limit:!0};$.fn.scrollTo=function(a,d,b){"object"=== typeof d&&(b=d,d=0);"function"===typeof b&&(b={onAfter:b});"max"===a&&(a=9E9);b=$.extend({},p.defaults,b);d=d||b.duration;var u=b.queue&&1=f[g]?0:Math.min(f[g],n));!a&&1-1){targetElements.on(evt+EVENT_NAMESPACE,function elementToggle(event){$.powerTip.toggle(this,event)})}else{targetElements.on(evt+EVENT_NAMESPACE,function elementOpen(event){$.powerTip.show(this,event)})}});$.each(options.closeEvents,function(idx,evt){if($.inArray(evt,options.openEvents)<0){targetElements.on(evt+EVENT_NAMESPACE,function elementClose(event){$.powerTip.hide(this,!isMouseEvent(event))})}});targetElements.on("keydown"+EVENT_NAMESPACE,function elementKeyDown(event){if(event.keyCode===27){$.powerTip.hide(this,true)}})}return targetElements};$.fn.powerTip.defaults={fadeInTime:200,fadeOutTime:100,followMouse:false,popupId:"powerTip",popupClass:null,intentSensitivity:7,intentPollInterval:100,closeDelay:100,placement:"n",smartPlacement:false,offset:10,mouseOnToPopup:false,manual:false,openEvents:["mouseenter","focus"],closeEvents:["mouseleave","blur"]};$.fn.powerTip.smartPlacementLists={n:["n","ne","nw","s"],e:["e","ne","se","w","nw","sw","n","s","e"],s:["s","se","sw","n"],w:["w","nw","sw","e","ne","se","n","s","w"],nw:["nw","w","sw","n","s","se","nw"],ne:["ne","e","se","n","s","sw","ne"],sw:["sw","w","nw","s","n","ne","sw"],se:["se","e","ne","s","n","nw","se"],"nw-alt":["nw-alt","n","ne-alt","sw-alt","s","se-alt","w","e"],"ne-alt":["ne-alt","n","nw-alt","se-alt","s","sw-alt","e","w"],"sw-alt":["sw-alt","s","se-alt","nw-alt","n","ne-alt","w","e"],"se-alt":["se-alt","s","sw-alt","ne-alt","n","nw-alt","e","w"]};$.powerTip={show:function apiShowTip(element,event){if(isMouseEvent(event)){trackMouse(event);session.previousX=event.pageX;session.previousY=event.pageY;$(element).data(DATA_DISPLAYCONTROLLER).show()}else{$(element).first().data(DATA_DISPLAYCONTROLLER).show(true,true)}return element},reposition:function apiResetPosition(element){$(element).first().data(DATA_DISPLAYCONTROLLER).resetPosition();return element},hide:function apiCloseTip(element,immediate){var displayController;immediate=element?immediate:true;if(element){displayController=$(element).first().data(DATA_DISPLAYCONTROLLER)}else if(session.activeHover){displayController=session.activeHover.data(DATA_DISPLAYCONTROLLER)}if(displayController){displayController.hide(immediate)}return element},toggle:function apiToggle(element,event){if(session.activeHover&&session.activeHover.is(element)){$.powerTip.hide(element,!isMouseEvent(event))}else{$.powerTip.show(element,event)}return element}};$.powerTip.showTip=$.powerTip.show;$.powerTip.closeTip=$.powerTip.hide;function CSSCoordinates(){var me=this;me.top="auto";me.left="auto";me.right="auto";me.bottom="auto";me.set=function(property,value){if($.isNumeric(value)){me[property]=Math.round(value)}}}function DisplayController(element,options,tipController){var hoverTimer=null,myCloseDelay=null;function openTooltip(immediate,forceOpen){cancelTimer();if(!element.data(DATA_HASACTIVEHOVER)){if(!immediate){session.tipOpenImminent=true;hoverTimer=setTimeout(function intentDelay(){hoverTimer=null;checkForIntent()},options.intentPollInterval)}else{if(forceOpen){element.data(DATA_FORCEDOPEN,true)}closeAnyDelayed();tipController.showTip(element)}}else{cancelClose()}}function closeTooltip(disableDelay){if(myCloseDelay){myCloseDelay=session.closeDelayTimeout=clearTimeout(myCloseDelay);session.delayInProgress=false}cancelTimer();session.tipOpenImminent=false;if(element.data(DATA_HASACTIVEHOVER)){element.data(DATA_FORCEDOPEN,false);if(!disableDelay){session.delayInProgress=true;session.closeDelayTimeout=setTimeout(function closeDelay(){session.closeDelayTimeout=null;tipController.hideTip(element);session.delayInProgress=false;myCloseDelay=null},options.closeDelay);myCloseDelay=session.closeDelayTimeout}else{tipController.hideTip(element)}}}function checkForIntent(){var xDifference=Math.abs(session.previousX-session.currentX),yDifference=Math.abs(session.previousY-session.currentY),totalDifference=xDifference+yDifference;if(totalDifference",{id:options.popupId});if($body.length===0){$body=$("body")}$body.append(tipElement);session.tooltips=session.tooltips?session.tooltips.add(tipElement):tipElement}if(options.followMouse){if(!tipElement.data(DATA_HASMOUSEMOVE)){$document.on("mousemove"+EVENT_NAMESPACE,positionTipOnCursor);$window.on("scroll"+EVENT_NAMESPACE,positionTipOnCursor);tipElement.data(DATA_HASMOUSEMOVE,true)}}function beginShowTip(element){element.data(DATA_HASACTIVEHOVER,true);tipElement.queue(function queueTipInit(next){showTip(element);next()})}function showTip(element){var tipContent;if(!element.data(DATA_HASACTIVEHOVER)){return}if(session.isTipOpen){if(!session.isClosing){hideTip(session.activeHover)}tipElement.delay(100).queue(function queueTipAgain(next){showTip(element);next()});return}element.trigger("powerTipPreRender");tipContent=getTooltipContent(element);if(tipContent){tipElement.empty().append(tipContent)}else{return}element.trigger("powerTipRender");session.activeHover=element;session.isTipOpen=true;tipElement.data(DATA_MOUSEONTOTIP,options.mouseOnToPopup);tipElement.addClass(options.popupClass);if(!options.followMouse||element.data(DATA_FORCEDOPEN)){positionTipOnElement(element);session.isFixedTipOpen=true}else{positionTipOnCursor()}if(!element.data(DATA_FORCEDOPEN)&&!options.followMouse){$document.on("click"+EVENT_NAMESPACE,function documentClick(event){var target=event.target;if(target!==element[0]){if(options.mouseOnToPopup){if(target!==tipElement[0]&&!$.contains(tipElement[0],target)){$.powerTip.hide()}}else{$.powerTip.hide()}}})}if(options.mouseOnToPopup&&!options.manual){tipElement.on("mouseenter"+EVENT_NAMESPACE,function tipMouseEnter(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).cancel()}});tipElement.on("mouseleave"+EVENT_NAMESPACE,function tipMouseLeave(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).hide()}})}tipElement.fadeIn(options.fadeInTime,function fadeInCallback(){if(!session.desyncTimeout){session.desyncTimeout=setInterval(closeDesyncedTip,500)}element.trigger("powerTipOpen")})}function hideTip(element){session.isClosing=true;session.isTipOpen=false;session.desyncTimeout=clearInterval(session.desyncTimeout);element.data(DATA_HASACTIVEHOVER,false);element.data(DATA_FORCEDOPEN,false);$document.off("click"+EVENT_NAMESPACE);tipElement.off(EVENT_NAMESPACE);tipElement.fadeOut(options.fadeOutTime,function fadeOutCallback(){var coords=new CSSCoordinates;session.activeHover=null;session.isClosing=false;session.isFixedTipOpen=false;tipElement.removeClass();coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);tipElement.css(coords);element.trigger("powerTipClose")})}function positionTipOnCursor(){var tipWidth,tipHeight,coords,collisions,collisionCount;if(!session.isFixedTipOpen&&(session.isTipOpen||session.tipOpenImminent&&tipElement.data(DATA_HASMOUSEMOVE))){tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=new CSSCoordinates;coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);collisions=getViewportCollisions(coords,tipWidth,tipHeight);if(collisions!==Collision.none){collisionCount=countFlags(collisions);if(collisionCount===1){if(collisions===Collision.right){coords.set("left",session.scrollLeft+session.windowWidth-tipWidth)}else if(collisions===Collision.bottom){coords.set("top",session.scrollTop+session.windowHeight-tipHeight)}}else{coords.set("left",session.currentX-tipWidth-options.offset);coords.set("top",session.currentY-tipHeight-options.offset)}}tipElement.css(coords)}}function positionTipOnElement(element){var priorityList,finalPlacement;if(options.smartPlacement||options.followMouse&&element.data(DATA_FORCEDOPEN)){priorityList=$.fn.powerTip.smartPlacementLists[options.placement];$.each(priorityList,function(idx,pos){var collisions=getViewportCollisions(placeTooltip(element,pos),tipElement.outerWidth(),tipElement.outerHeight());finalPlacement=pos;return collisions!==Collision.none})}else{placeTooltip(element,options.placement);finalPlacement=options.placement}tipElement.removeClass("w nw sw e ne se n s w se-alt sw-alt ne-alt nw-alt");tipElement.addClass(finalPlacement)}function placeTooltip(element,placement){var iterationCount=0,tipWidth,tipHeight,coords=new CSSCoordinates;coords.set("top",0);coords.set("left",0);tipElement.css(coords);do{tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=placementCalculator.compute(element,placement,tipWidth,tipHeight,options.offset);tipElement.css(coords)}while(++iterationCount<=5&&(tipWidth!==tipElement.outerWidth()||tipHeight!==tipElement.outerHeight()));return coords}function closeDesyncedTip(){var isDesynced=false,hasDesyncableCloseEvent=$.grep(["mouseleave","mouseout","blur","focusout"],function(eventType){return $.inArray(eventType,options.closeEvents)!==-1}).length>0;if(session.isTipOpen&&!session.isClosing&&!session.delayInProgress&&hasDesyncableCloseEvent){if(session.activeHover.data(DATA_HASACTIVEHOVER)===false||session.activeHover.is(":disabled")){isDesynced=true}else if(!isMouseOver(session.activeHover)&&!session.activeHover.is(":focus")&&!session.activeHover.data(DATA_FORCEDOPEN)){if(tipElement.data(DATA_MOUSEONTOTIP)){if(!isMouseOver(tipElement)){isDesynced=true}}else{isDesynced=true}}if(isDesynced){hideTip(session.activeHover)}}}this.showTip=beginShowTip;this.hideTip=hideTip;this.resetPosition=positionTipOnElement}function isSvgElement(element){return Boolean(window.SVGElement&&element[0]instanceof SVGElement)}function isMouseEvent(event){return Boolean(event&&$.inArray(event.type,MOUSE_EVENTS)>-1&&typeof event.pageX==="number")}function initTracking(){if(!session.mouseTrackingActive){session.mouseTrackingActive=true;getViewportDimensions();$(getViewportDimensions);$document.on("mousemove"+EVENT_NAMESPACE,trackMouse);$window.on("resize"+EVENT_NAMESPACE,trackResize);$window.on("scroll"+EVENT_NAMESPACE,trackScroll)}}function getViewportDimensions(){session.scrollLeft=$window.scrollLeft();session.scrollTop=$window.scrollTop();session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackResize(){session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackScroll(){var x=$window.scrollLeft(),y=$window.scrollTop();if(x!==session.scrollLeft){session.currentX+=x-session.scrollLeft;session.scrollLeft=x}if(y!==session.scrollTop){session.currentY+=y-session.scrollTop;session.scrollTop=y}}function trackMouse(event){session.currentX=event.pageX;session.currentY=event.pageY}function isMouseOver(element){var elementPosition=element.offset(),elementBox=element[0].getBoundingClientRect(),elementWidth=elementBox.right-elementBox.left,elementHeight=elementBox.bottom-elementBox.top;return session.currentX>=elementPosition.left&&session.currentX<=elementPosition.left+elementWidth&&session.currentY>=elementPosition.top&&session.currentY<=elementPosition.top+elementHeight}function getTooltipContent(element){var tipText=element.data(DATA_POWERTIP),tipObject=element.data(DATA_POWERTIPJQ),tipTarget=element.data(DATA_POWERTIPTARGET),targetElement,content;if(tipText){if($.isFunction(tipText)){tipText=tipText.call(element[0])}content=tipText}else if(tipObject){if($.isFunction(tipObject)){tipObject=tipObject.call(element[0])}if(tipObject.length>0){content=tipObject.clone(true,true)}}else if(tipTarget){targetElement=$("#"+tipTarget);if(targetElement.length>0){content=targetElement.html()}}return content}function getViewportCollisions(coords,elementWidth,elementHeight){var viewportTop=session.scrollTop,viewportLeft=session.scrollLeft,viewportBottom=viewportTop+session.windowHeight,viewportRight=viewportLeft+session.windowWidth,collisions=Collision.none;if(coords.topviewportBottom||Math.abs(coords.bottom-session.windowHeight)>viewportBottom){collisions|=Collision.bottom}if(coords.leftviewportRight){collisions|=Collision.left}if(coords.left+elementWidth>viewportRight||coords.right1)){a.preventDefault();var c=a.originalEvent.changedTouches[0],d=document.createEvent("MouseEvents");d.initMouseEvent(b,!0,!0,window,1,c.screenX,c.screenY,c.clientX,c.clientY,!1,!1,!1,!1,0,null),a.target.dispatchEvent(d)}}if(a.support.touch="ontouchend"in document,a.support.touch){var e,b=a.ui.mouse.prototype,c=b._mouseInit,d=b._mouseDestroy;b._touchStart=function(a){var b=this;!e&&b._mouseCapture(a.originalEvent.changedTouches[0])&&(e=!0,b._touchMoved=!1,f(a,"mouseover"),f(a,"mousemove"),f(a,"mousedown"))},b._touchMove=function(a){e&&(this._touchMoved=!0,f(a,"mousemove"))},b._touchEnd=function(a){e&&(f(a,"mouseup"),f(a,"mouseout"),this._touchMoved||f(a,"click"),e=!1)},b._mouseInit=function(){var b=this;b.element.bind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),c.call(b)},b._mouseDestroy=function(){var b=this;b.element.unbind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),d.call(b)}}}(jQuery);/*! SmartMenus jQuery Plugin - v1.1.0 - September 17, 2017 + * http://www.smartmenus.org/ + * Copyright Vasil Dinkov, Vadikom Web Ltd. http://vadikom.com; Licensed MIT */(function(t){"function"==typeof define&&define.amd?define(["jquery"],t):"object"==typeof module&&"object"==typeof module.exports?module.exports=t(require("jquery")):t(jQuery)})(function($){function initMouseDetection(t){var e=".smartmenus_mouse";if(mouseDetectionEnabled||t)mouseDetectionEnabled&&t&&($(document).off(e),mouseDetectionEnabled=!1);else{var i=!0,s=null,o={mousemove:function(t){var e={x:t.pageX,y:t.pageY,timeStamp:(new Date).getTime()};if(s){var o=Math.abs(s.x-e.x),a=Math.abs(s.y-e.y);if((o>0||a>0)&&2>=o&&2>=a&&300>=e.timeStamp-s.timeStamp&&(mouse=!0,i)){var n=$(t.target).closest("a");n.is("a")&&$.each(menuTrees,function(){return $.contains(this.$root[0],n[0])?(this.itemEnter({currentTarget:n[0]}),!1):void 0}),i=!1}}s=e}};o[touchEvents?"touchstart":"pointerover pointermove pointerout MSPointerOver MSPointerMove MSPointerOut"]=function(t){isTouchEvent(t.originalEvent)&&(mouse=!1)},$(document).on(getEventsNS(o,e)),mouseDetectionEnabled=!0}}function isTouchEvent(t){return!/^(4|mouse)$/.test(t.pointerType)}function getEventsNS(t,e){e||(e="");var i={};for(var s in t)i[s.split(" ").join(e+" ")+e]=t[s];return i}var menuTrees=[],mouse=!1,touchEvents="ontouchstart"in window,mouseDetectionEnabled=!1,requestAnimationFrame=window.requestAnimationFrame||function(t){return setTimeout(t,1e3/60)},cancelAnimationFrame=window.cancelAnimationFrame||function(t){clearTimeout(t)},canAnimate=!!$.fn.animate;return $.SmartMenus=function(t,e){this.$root=$(t),this.opts=e,this.rootId="",this.accessIdPrefix="",this.$subArrow=null,this.activatedItems=[],this.visibleSubMenus=[],this.showTimeout=0,this.hideTimeout=0,this.scrollTimeout=0,this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.idInc=0,this.$firstLink=null,this.$firstSub=null,this.disabled=!1,this.$disableOverlay=null,this.$touchScrollingSub=null,this.cssTransforms3d="perspective"in t.style||"webkitPerspective"in t.style,this.wasCollapsible=!1,this.init()},$.extend($.SmartMenus,{hideAll:function(){$.each(menuTrees,function(){this.menuHideAll()})},destroy:function(){for(;menuTrees.length;)menuTrees[0].destroy();initMouseDetection(!0)},prototype:{init:function(t){var e=this;if(!t){menuTrees.push(this),this.rootId=((new Date).getTime()+Math.random()+"").replace(/\D/g,""),this.accessIdPrefix="sm-"+this.rootId+"-",this.$root.hasClass("sm-rtl")&&(this.opts.rightToLeftSubMenus=!0);var i=".smartmenus";this.$root.data("smartmenus",this).attr("data-smartmenus-id",this.rootId).dataSM("level",1).on(getEventsNS({"mouseover focusin":$.proxy(this.rootOver,this),"mouseout focusout":$.proxy(this.rootOut,this),keydown:$.proxy(this.rootKeyDown,this)},i)).on(getEventsNS({mouseenter:$.proxy(this.itemEnter,this),mouseleave:$.proxy(this.itemLeave,this),mousedown:$.proxy(this.itemDown,this),focus:$.proxy(this.itemFocus,this),blur:$.proxy(this.itemBlur,this),click:$.proxy(this.itemClick,this)},i),"a"),i+=this.rootId,this.opts.hideOnClick&&$(document).on(getEventsNS({touchstart:$.proxy(this.docTouchStart,this),touchmove:$.proxy(this.docTouchMove,this),touchend:$.proxy(this.docTouchEnd,this),click:$.proxy(this.docClick,this)},i)),$(window).on(getEventsNS({"resize orientationchange":$.proxy(this.winResize,this)},i)),this.opts.subIndicators&&(this.$subArrow=$("").addClass("sub-arrow"),this.opts.subIndicatorsText&&this.$subArrow.html(this.opts.subIndicatorsText)),initMouseDetection()}if(this.$firstSub=this.$root.find("ul").each(function(){e.menuInit($(this))}).eq(0),this.$firstLink=this.$root.find("a").eq(0),this.opts.markCurrentItem){var s=/(index|default)\.[^#\?\/]*/i,o=/#.*/,a=window.location.href.replace(s,""),n=a.replace(o,"");this.$root.find("a").each(function(){var t=this.href.replace(s,""),i=$(this);(t==a||t==n)&&(i.addClass("current"),e.opts.markCurrentTree&&i.parentsUntil("[data-smartmenus-id]","ul").each(function(){$(this).dataSM("parent-a").addClass("current")}))})}this.wasCollapsible=this.isCollapsible()},destroy:function(t){if(!t){var e=".smartmenus";this.$root.removeData("smartmenus").removeAttr("data-smartmenus-id").removeDataSM("level").off(e),e+=this.rootId,$(document).off(e),$(window).off(e),this.opts.subIndicators&&(this.$subArrow=null)}this.menuHideAll();var i=this;this.$root.find("ul").each(function(){var t=$(this);t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.dataSM("shown-before")&&((i.opts.subMenusMinWidth||i.opts.subMenusMaxWidth)&&t.css({width:"",minWidth:"",maxWidth:""}).removeClass("sm-nowrap"),t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.css({zIndex:"",top:"",left:"",marginLeft:"",marginTop:"",display:""})),0==(t.attr("id")||"").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeDataSM("in-mega").removeDataSM("shown-before").removeDataSM("scroll-arrows").removeDataSM("parent-a").removeDataSM("level").removeDataSM("beforefirstshowfired").removeAttr("role").removeAttr("aria-hidden").removeAttr("aria-labelledby").removeAttr("aria-expanded"),this.$root.find("a.has-submenu").each(function(){var t=$(this);0==t.attr("id").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeClass("has-submenu").removeDataSM("sub").removeAttr("aria-haspopup").removeAttr("aria-controls").removeAttr("aria-expanded").closest("li").removeDataSM("sub"),this.opts.subIndicators&&this.$root.find("span.sub-arrow").remove(),this.opts.markCurrentItem&&this.$root.find("a.current").removeClass("current"),t||(this.$root=null,this.$firstLink=null,this.$firstSub=null,this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),menuTrees.splice($.inArray(this,menuTrees),1))},disable:function(t){if(!this.disabled){if(this.menuHideAll(),!t&&!this.opts.isPopup&&this.$root.is(":visible")){var e=this.$root.offset();this.$disableOverlay=$('
').css({position:"absolute",top:e.top,left:e.left,width:this.$root.outerWidth(),height:this.$root.outerHeight(),zIndex:this.getStartZIndex(!0),opacity:0}).appendTo(document.body)}this.disabled=!0}},docClick:function(t){return this.$touchScrollingSub?(this.$touchScrollingSub=null,void 0):((this.visibleSubMenus.length&&!$.contains(this.$root[0],t.target)||$(t.target).closest("a").length)&&this.menuHideAll(),void 0)},docTouchEnd:function(){if(this.lastTouch){if(!(!this.visibleSubMenus.length||void 0!==this.lastTouch.x2&&this.lastTouch.x1!=this.lastTouch.x2||void 0!==this.lastTouch.y2&&this.lastTouch.y1!=this.lastTouch.y2||this.lastTouch.target&&$.contains(this.$root[0],this.lastTouch.target))){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var t=this;this.hideTimeout=setTimeout(function(){t.menuHideAll()},350)}this.lastTouch=null}},docTouchMove:function(t){if(this.lastTouch){var e=t.originalEvent.touches[0];this.lastTouch.x2=e.pageX,this.lastTouch.y2=e.pageY}},docTouchStart:function(t){var e=t.originalEvent.touches[0];this.lastTouch={x1:e.pageX,y1:e.pageY,target:e.target}},enable:function(){this.disabled&&(this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),this.disabled=!1)},getClosestMenu:function(t){for(var e=$(t).closest("ul");e.dataSM("in-mega");)e=e.parent().closest("ul");return e[0]||null},getHeight:function(t){return this.getOffset(t,!0)},getOffset:function(t,e){var i;"none"==t.css("display")&&(i={position:t[0].style.position,visibility:t[0].style.visibility},t.css({position:"absolute",visibility:"hidden"}).show());var s=t[0].getBoundingClientRect&&t[0].getBoundingClientRect(),o=s&&(e?s.height||s.bottom-s.top:s.width||s.right-s.left);return o||0===o||(o=e?t[0].offsetHeight:t[0].offsetWidth),i&&t.hide().css(i),o},getStartZIndex:function(t){var e=parseInt(this[t?"$root":"$firstSub"].css("z-index"));return!t&&isNaN(e)&&(e=parseInt(this.$root.css("z-index"))),isNaN(e)?1:e},getTouchPoint:function(t){return t.touches&&t.touches[0]||t.changedTouches&&t.changedTouches[0]||t},getViewport:function(t){var e=t?"Height":"Width",i=document.documentElement["client"+e],s=window["inner"+e];return s&&(i=Math.min(i,s)),i},getViewportHeight:function(){return this.getViewport(!0)},getViewportWidth:function(){return this.getViewport()},getWidth:function(t){return this.getOffset(t)},handleEvents:function(){return!this.disabled&&this.isCSSOn()},handleItemEvents:function(t){return this.handleEvents()&&!this.isLinkInMegaMenu(t)},isCollapsible:function(){return"static"==this.$firstSub.css("position")},isCSSOn:function(){return"inline"!=this.$firstLink.css("display")},isFixed:function(){var t="fixed"==this.$root.css("position");return t||this.$root.parentsUntil("body").each(function(){return"fixed"==$(this).css("position")?(t=!0,!1):void 0}),t},isLinkInMegaMenu:function(t){return $(this.getClosestMenu(t[0])).hasClass("mega-menu")},isTouchMode:function(){return!mouse||this.opts.noMouseOver||this.isCollapsible()},itemActivate:function(t,e){var i=t.closest("ul"),s=i.dataSM("level");if(s>1&&(!this.activatedItems[s-2]||this.activatedItems[s-2][0]!=i.dataSM("parent-a")[0])){var o=this;$(i.parentsUntil("[data-smartmenus-id]","ul").get().reverse()).add(i).each(function(){o.itemActivate($(this).dataSM("parent-a"))})}if((!this.isCollapsible()||e)&&this.menuHideSubMenus(this.activatedItems[s-1]&&this.activatedItems[s-1][0]==t[0]?s:s-1),this.activatedItems[s-1]=t,this.$root.triggerHandler("activate.smapi",t[0])!==!1){var a=t.dataSM("sub");a&&(this.isTouchMode()||!this.opts.showOnClick||this.clickActivated)&&this.menuShow(a)}},itemBlur:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&this.$root.triggerHandler("blur.smapi",e[0])},itemClick:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(this.$touchScrollingSub&&this.$touchScrollingSub[0]==e.closest("ul")[0])return this.$touchScrollingSub=null,t.stopPropagation(),!1;if(this.$root.triggerHandler("click.smapi",e[0])===!1)return!1;var i=$(t.target).is(".sub-arrow"),s=e.dataSM("sub"),o=s?2==s.dataSM("level"):!1,a=this.isCollapsible(),n=/toggle$/.test(this.opts.collapsibleBehavior),r=/link$/.test(this.opts.collapsibleBehavior),h=/^accordion/.test(this.opts.collapsibleBehavior);if(s&&!s.is(":visible")){if((!r||!a||i)&&(this.opts.showOnClick&&o&&(this.clickActivated=!0),this.itemActivate(e,h),s.is(":visible")))return this.focusActivated=!0,!1}else if(a&&(n||i))return this.itemActivate(e,h),this.menuHide(s),n&&(this.focusActivated=!1),!1;return this.opts.showOnClick&&o||e.hasClass("disabled")||this.$root.triggerHandler("select.smapi",e[0])===!1?!1:void 0}},itemDown:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&e.dataSM("mousedown",!0)},itemEnter:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(!this.isTouchMode()){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);var i=this;this.showTimeout=setTimeout(function(){i.itemActivate(e)},this.opts.showOnClick&&1==e.closest("ul").dataSM("level")?1:this.opts.showTimeout)}this.$root.triggerHandler("mouseenter.smapi",e[0])}},itemFocus:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(!this.focusActivated||this.isTouchMode()&&e.dataSM("mousedown")||this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0]==e[0]||this.itemActivate(e,!0),this.$root.triggerHandler("focus.smapi",e[0]))},itemLeave:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(this.isTouchMode()||(e[0].blur(),this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0)),e.removeDataSM("mousedown"),this.$root.triggerHandler("mouseleave.smapi",e[0]))},menuHide:function(t){if(this.$root.triggerHandler("beforehide.smapi",t[0])!==!1&&(canAnimate&&t.stop(!0,!0),"none"!=t.css("display"))){var e=function(){t.css("z-index","")};this.isCollapsible()?canAnimate&&this.opts.collapsibleHideFunction?this.opts.collapsibleHideFunction.call(this,t,e):t.hide(this.opts.collapsibleHideDuration,e):canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,t,e):t.hide(this.opts.hideDuration,e),t.dataSM("scroll")&&(this.menuScrollStop(t),t.css({"touch-action":"","-ms-touch-action":"","-webkit-transform":"",transform:""}).off(".smartmenus_scroll").removeDataSM("scroll").dataSM("scroll-arrows").hide()),t.dataSM("parent-a").removeClass("highlighted").attr("aria-expanded","false"),t.attr({"aria-expanded":"false","aria-hidden":"true"});var i=t.dataSM("level");this.activatedItems.splice(i-1,1),this.visibleSubMenus.splice($.inArray(t,this.visibleSubMenus),1),this.$root.triggerHandler("hide.smapi",t[0])}},menuHideAll:function(){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);for(var t=this.opts.isPopup?1:0,e=this.visibleSubMenus.length-1;e>=t;e--)this.menuHide(this.visibleSubMenus[e]);this.opts.isPopup&&(canAnimate&&this.$root.stop(!0,!0),this.$root.is(":visible")&&(canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,this.$root):this.$root.hide(this.opts.hideDuration))),this.activatedItems=[],this.visibleSubMenus=[],this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.$root.triggerHandler("hideAll.smapi")},menuHideSubMenus:function(t){for(var e=this.activatedItems.length-1;e>=t;e--){var i=this.activatedItems[e].dataSM("sub");i&&this.menuHide(i)}},menuInit:function(t){if(!t.dataSM("in-mega")){t.hasClass("mega-menu")&&t.find("ul").dataSM("in-mega",!0);for(var e=2,i=t[0];(i=i.parentNode.parentNode)!=this.$root[0];)e++;var s=t.prevAll("a").eq(-1);s.length||(s=t.prevAll().find("a").eq(-1)),s.addClass("has-submenu").dataSM("sub",t),t.dataSM("parent-a",s).dataSM("level",e).parent().dataSM("sub",t);var o=s.attr("id")||this.accessIdPrefix+ ++this.idInc,a=t.attr("id")||this.accessIdPrefix+ ++this.idInc;s.attr({id:o,"aria-haspopup":"true","aria-controls":a,"aria-expanded":"false"}),t.attr({id:a,role:"group","aria-hidden":"true","aria-labelledby":o,"aria-expanded":"false"}),this.opts.subIndicators&&s[this.opts.subIndicatorsPos](this.$subArrow.clone())}},menuPosition:function(t){var e,i,s=t.dataSM("parent-a"),o=s.closest("li"),a=o.parent(),n=t.dataSM("level"),r=this.getWidth(t),h=this.getHeight(t),u=s.offset(),l=u.left,c=u.top,d=this.getWidth(s),m=this.getHeight(s),p=$(window),f=p.scrollLeft(),v=p.scrollTop(),b=this.getViewportWidth(),S=this.getViewportHeight(),g=a.parent().is("[data-sm-horizontal-sub]")||2==n&&!a.hasClass("sm-vertical"),M=this.opts.rightToLeftSubMenus&&!o.is("[data-sm-reverse]")||!this.opts.rightToLeftSubMenus&&o.is("[data-sm-reverse]"),w=2==n?this.opts.mainMenuSubOffsetX:this.opts.subMenusSubOffsetX,T=2==n?this.opts.mainMenuSubOffsetY:this.opts.subMenusSubOffsetY;if(g?(e=M?d-r-w:w,i=this.opts.bottomToTopSubMenus?-h-T:m+T):(e=M?w-r:d-w,i=this.opts.bottomToTopSubMenus?m-T-h:T),this.opts.keepInViewport){var y=l+e,I=c+i;if(M&&f>y?e=g?f-y+e:d-w:!M&&y+r>f+b&&(e=g?f+b-r-y+e:w-r),g||(S>h&&I+h>v+S?i+=v+S-h-I:(h>=S||v>I)&&(i+=v-I)),g&&(I+h>v+S+.49||v>I)||!g&&h>S+.49){var x=this;t.dataSM("scroll-arrows")||t.dataSM("scroll-arrows",$([$('')[0],$('')[0]]).on({mouseenter:function(){t.dataSM("scroll").up=$(this).hasClass("scroll-up"),x.menuScroll(t)},mouseleave:function(e){x.menuScrollStop(t),x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(t){t.preventDefault()}}).insertAfter(t));var A=".smartmenus_scroll";if(t.dataSM("scroll",{y:this.cssTransforms3d?0:i-m,step:1,itemH:m,subH:h,arrowDownH:this.getHeight(t.dataSM("scroll-arrows").eq(1))}).on(getEventsNS({mouseover:function(e){x.menuScrollOver(t,e)},mouseout:function(e){x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(e){x.menuScrollMousewheel(t,e)}},A)).dataSM("scroll-arrows").css({top:"auto",left:"0",marginLeft:e+(parseInt(t.css("border-left-width"))||0),width:r-(parseInt(t.css("border-left-width"))||0)-(parseInt(t.css("border-right-width"))||0),zIndex:t.css("z-index")}).eq(g&&this.opts.bottomToTopSubMenus?0:1).show(),this.isFixed()){var C={};C[touchEvents?"touchstart touchmove touchend":"pointerdown pointermove pointerup MSPointerDown MSPointerMove MSPointerUp"]=function(e){x.menuScrollTouch(t,e)},t.css({"touch-action":"none","-ms-touch-action":"none"}).on(getEventsNS(C,A))}}}t.css({top:"auto",left:"0",marginLeft:e,marginTop:i-m})},menuScroll:function(t,e,i){var s,o=t.dataSM("scroll"),a=t.dataSM("scroll-arrows"),n=o.up?o.upEnd:o.downEnd;if(!e&&o.momentum){if(o.momentum*=.92,s=o.momentum,.5>s)return this.menuScrollStop(t),void 0}else s=i||(e||!this.opts.scrollAccelerate?this.opts.scrollStep:Math.floor(o.step));var r=t.dataSM("level");if(this.activatedItems[r-1]&&this.activatedItems[r-1].dataSM("sub")&&this.activatedItems[r-1].dataSM("sub").is(":visible")&&this.menuHideSubMenus(r-1),o.y=o.up&&o.y>=n||!o.up&&n>=o.y?o.y:Math.abs(n-o.y)>s?o.y+(o.up?s:-s):n,t.css(this.cssTransforms3d?{"-webkit-transform":"translate3d(0, "+o.y+"px, 0)",transform:"translate3d(0, "+o.y+"px, 0)"}:{marginTop:o.y}),mouse&&(o.up&&o.y>o.downEnd||!o.up&&o.y0;t.dataSM("scroll-arrows").eq(i?0:1).is(":visible")&&(t.dataSM("scroll").up=i,this.menuScroll(t,!0))}e.preventDefault()},menuScrollOut:function(t,e){mouse&&(/^scroll-(up|down)/.test((e.relatedTarget||"").className)||(t[0]==e.relatedTarget||$.contains(t[0],e.relatedTarget))&&this.getClosestMenu(e.relatedTarget)==t[0]||t.dataSM("scroll-arrows").css("visibility","hidden"))},menuScrollOver:function(t,e){if(mouse&&!/^scroll-(up|down)/.test(e.target.className)&&this.getClosestMenu(e.target)==t[0]){this.menuScrollRefreshData(t);var i=t.dataSM("scroll"),s=$(window).scrollTop()-t.dataSM("parent-a").offset().top-i.itemH;t.dataSM("scroll-arrows").eq(0).css("margin-top",s).end().eq(1).css("margin-top",s+this.getViewportHeight()-i.arrowDownH).end().css("visibility","visible")}},menuScrollRefreshData:function(t){var e=t.dataSM("scroll"),i=$(window).scrollTop()-t.dataSM("parent-a").offset().top-e.itemH;this.cssTransforms3d&&(i=-(parseFloat(t.css("margin-top"))-i)),$.extend(e,{upEnd:i,downEnd:i+this.getViewportHeight()-e.subH})},menuScrollStop:function(t){return this.scrollTimeout?(cancelAnimationFrame(this.scrollTimeout),this.scrollTimeout=0,t.dataSM("scroll").step=1,!0):void 0},menuScrollTouch:function(t,e){if(e=e.originalEvent,isTouchEvent(e)){var i=this.getTouchPoint(e);if(this.getClosestMenu(i.target)==t[0]){var s=t.dataSM("scroll");if(/(start|down)$/i.test(e.type))this.menuScrollStop(t)?(e.preventDefault(),this.$touchScrollingSub=t):this.$touchScrollingSub=null,this.menuScrollRefreshData(t),$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp});else if(/move$/i.test(e.type)){var o=void 0!==s.touchY?s.touchY:s.touchStartY;if(void 0!==o&&o!=i.pageY){this.$touchScrollingSub=t;var a=i.pageY>o;void 0!==s.up&&s.up!=a&&$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp}),$.extend(s,{up:a,touchY:i.pageY}),this.menuScroll(t,!0,Math.abs(i.pageY-o))}e.preventDefault()}else void 0!==s.touchY&&((s.momentum=15*Math.pow(Math.abs(i.pageY-s.touchStartY)/(e.timeStamp-s.touchStartTime),2))&&(this.menuScrollStop(t),this.menuScroll(t),e.preventDefault()),delete s.touchY)}}},menuShow:function(t){if((t.dataSM("beforefirstshowfired")||(t.dataSM("beforefirstshowfired",!0),this.$root.triggerHandler("beforefirstshow.smapi",t[0])!==!1))&&this.$root.triggerHandler("beforeshow.smapi",t[0])!==!1&&(t.dataSM("shown-before",!0),canAnimate&&t.stop(!0,!0),!t.is(":visible"))){var e=t.dataSM("parent-a"),i=this.isCollapsible();if((this.opts.keepHighlighted||i)&&e.addClass("highlighted"),i)t.removeClass("sm-nowrap").css({zIndex:"",width:"auto",minWidth:"",maxWidth:"",top:"",left:"",marginLeft:"",marginTop:""});else{if(t.css("z-index",this.zIndexInc=(this.zIndexInc||this.getStartZIndex())+1),(this.opts.subMenusMinWidth||this.opts.subMenusMaxWidth)&&(t.css({width:"auto",minWidth:"",maxWidth:""}).addClass("sm-nowrap"),this.opts.subMenusMinWidth&&t.css("min-width",this.opts.subMenusMinWidth),this.opts.subMenusMaxWidth)){var s=this.getWidth(t);t.css("max-width",this.opts.subMenusMaxWidth),s>this.getWidth(t)&&t.removeClass("sm-nowrap").css("width",this.opts.subMenusMaxWidth)}this.menuPosition(t)}var o=function(){t.css("overflow","")};i?canAnimate&&this.opts.collapsibleShowFunction?this.opts.collapsibleShowFunction.call(this,t,o):t.show(this.opts.collapsibleShowDuration,o):canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,t,o):t.show(this.opts.showDuration,o),e.attr("aria-expanded","true"),t.attr({"aria-expanded":"true","aria-hidden":"false"}),this.visibleSubMenus.push(t),this.$root.triggerHandler("show.smapi",t[0])}},popupHide:function(t){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},t?1:this.opts.hideTimeout)},popupShow:function(t,e){if(!this.opts.isPopup)return alert('SmartMenus jQuery Error:\n\nIf you want to show this menu via the "popupShow" method, set the isPopup:true option.'),void 0;if(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),this.$root.dataSM("shown-before",!0),canAnimate&&this.$root.stop(!0,!0),!this.$root.is(":visible")){this.$root.css({left:t,top:e});var i=this,s=function(){i.$root.css("overflow","")};canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,this.$root,s):this.$root.show(this.opts.showDuration,s),this.visibleSubMenus[0]=this.$root}},refresh:function(){this.destroy(!0),this.init(!0)},rootKeyDown:function(t){if(this.handleEvents())switch(t.keyCode){case 27:var e=this.activatedItems[0];if(e){this.menuHideAll(),e[0].focus();var i=e.dataSM("sub");i&&this.menuHide(i)}break;case 32:var s=$(t.target);if(s.is("a")&&this.handleItemEvents(s)){var i=s.dataSM("sub");i&&!i.is(":visible")&&(this.itemClick({currentTarget:t.target}),t.preventDefault())}}},rootOut:function(t){if(this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),!this.opts.showOnClick||!this.opts.hideOnClick)){var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},this.opts.hideTimeout)}},rootOver:function(t){this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0)},winResize:function(t){if(this.handleEvents()){if(!("onorientationchange"in window)||"orientationchange"==t.type){var e=this.isCollapsible();this.wasCollapsible&&e||(this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0].blur(),this.menuHideAll()),this.wasCollapsible=e}}else if(this.$disableOverlay){var i=this.$root.offset();this.$disableOverlay.css({top:i.top,left:i.left,width:this.$root.outerWidth(),height:this.$root.outerHeight()})}}}}),$.fn.dataSM=function(t,e){return e?this.data(t+"_smartmenus",e):this.data(t+"_smartmenus")},$.fn.removeDataSM=function(t){return this.removeData(t+"_smartmenus")},$.fn.smartmenus=function(options){if("string"==typeof options){var args=arguments,method=options;return Array.prototype.shift.call(args),this.each(function(){var t=$(this).data("smartmenus");t&&t[method]&&t[method].apply(t,args)})}return this.each(function(){var dataOpts=$(this).data("sm-options")||null;if(dataOpts)try{dataOpts=eval("("+dataOpts+")")}catch(e){dataOpts=null,alert('ERROR\n\nSmartMenus jQuery init:\nInvalid "data-sm-options" attribute value syntax.')}new $.SmartMenus(this,$.extend({},$.fn.smartmenus.defaults,options,dataOpts))})},$.fn.smartmenus.defaults={isPopup:!1,mainMenuSubOffsetX:0,mainMenuSubOffsetY:0,subMenusSubOffsetX:0,subMenusSubOffsetY:0,subMenusMinWidth:"10em",subMenusMaxWidth:"20em",subIndicators:!0,subIndicatorsPos:"append",subIndicatorsText:"",scrollStep:30,scrollAccelerate:!0,showTimeout:250,hideTimeout:500,showDuration:0,showFunction:null,hideDuration:0,hideFunction:function(t,e){t.fadeOut(200,e)},collapsibleShowDuration:0,collapsibleShowFunction:function(t,e){t.slideDown(200,e)},collapsibleHideDuration:0,collapsibleHideFunction:function(t,e){t.slideUp(200,e)},showOnClick:!1,hideOnClick:!0,noMouseOver:!1,keepInViewport:!0,keepHighlighted:!0,markCurrentItem:!1,markCurrentTree:!0,rightToLeftSubMenus:!1,bottomToTopSubMenus:!1,collapsibleBehavior:"default"},$}); \ No newline at end of file diff --git a/log_8h.html b/log_8h.html new file mode 100644 index 00000000..0ad627bb --- /dev/null +++ b/log_8h.html @@ -0,0 +1,182 @@ + + + + + + + +libfranka: include/franka/log.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+ +
+
log.h File Reference
+
+
+ +

Contains helper types for logging sent commands and received robot states. +More...

+
#include <vector>
+#include <franka/control_types.h>
+#include <franka/robot_state.h>
+
+Include dependency graph for log.h:
+
+
+ + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + + + +

+Classes

struct  franka::RobotCommand
 Command sent to the robot. More...
 
struct  franka::Record
 One row of the log contains a robot command of timestamp n and a corresponding robot state of timestamp n+1. More...
 
+ + + + +

+Functions

std::string franka::logToCSV (const std::vector< Record > &log)
 Writes the log to a string in CSV format. More...
 
+

Detailed Description

+

Contains helper types for logging sent commands and received robot states.

+

Function Documentation

+ +

◆ logToCSV()

+ +
+
+ + + + + + + + +
std::string franka::logToCSV (const std::vector< Record > & log)
+
+ +

Writes the log to a string in CSV format.

+

If the string is not empty, the first row contains the header with names of columns. The following lines contain rows of values separated by commas.

+

If the log is empty, the function returns an empty string.

+
Parameters
+ + +
[in]logLog provided by the ControlException.
+
+
+
Returns
a string in CSV format, or empty string.
+
Examples
motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.
+
+ +
+
+
+ + + + diff --git a/log_8h__dep__incl.map b/log_8h__dep__incl.map new file mode 100644 index 00000000..7a70bf28 --- /dev/null +++ b/log_8h__dep__incl.map @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/log_8h__dep__incl.md5 b/log_8h__dep__incl.md5 new file mode 100644 index 00000000..a4a6f120 --- /dev/null +++ b/log_8h__dep__incl.md5 @@ -0,0 +1 @@ +125eef755c6361efeae12c631c7f666d \ No newline at end of file diff --git a/log_8h__dep__incl.png b/log_8h__dep__incl.png new file mode 100644 index 00000000..1ea0462f Binary files /dev/null and b/log_8h__dep__incl.png differ diff --git a/log_8h__incl.map b/log_8h__incl.map new file mode 100644 index 00000000..d3209548 --- /dev/null +++ b/log_8h__incl.map @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/log_8h__incl.md5 b/log_8h__incl.md5 new file mode 100644 index 00000000..81e61f17 --- /dev/null +++ b/log_8h__incl.md5 @@ -0,0 +1 @@ +2625f728cdb4360d8d279f47bbc5ed43 \ No newline at end of file diff --git a/log_8h__incl.png b/log_8h__incl.png new file mode 100644 index 00000000..6532e044 Binary files /dev/null and b/log_8h__incl.png differ diff --git a/log_8h_source.html b/log_8h_source.html new file mode 100644 index 00000000..4e4461b5 --- /dev/null +++ b/log_8h_source.html @@ -0,0 +1,132 @@ + + + + + + + +libfranka: include/franka/log.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
log.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <vector>
+
6 
+
7 #include <franka/control_types.h>
+
8 #include <franka/robot_state.h>
+
9 
+
15 namespace franka {
+
16 
+
20 struct RobotCommand {
+
24  JointPositions joint_positions{0, 0, 0, 0, 0, 0, 0};
+
28  JointVelocities joint_velocities{0, 0, 0, 0, 0, 0, 0};
+
32  CartesianPose cartesian_pose{1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1};
+ +
40  Torques torques{0, 0, 0, 0, 0, 0, 0};
+
41 };
+
42 
+
48 struct Record {
+ + +
57 };
+
58 
+
69 std::string logToCSV(const std::vector<Record>& log);
+
70 } // namespace franka
+
Stores values for Cartesian pose motion generation.
Definition: control_types.h:127
+
Stores values for Cartesian velocity motion generation.
Definition: control_types.h:211
+
Stores values for joint position motion generation.
Definition: control_types.h:72
+
Stores values for joint velocity motion generation.
Definition: control_types.h:99
+
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
+
Contains helper types for returning motion generation and joint-level torque commands.
+
std::string logToCSV(const std::vector< Record > &log)
Writes the log to a string in CSV format.
+
Contains the franka::RobotState types.
+
One row of the log contains a robot command of timestamp n and a corresponding robot state of timesta...
Definition: log.h:48
+
RobotState state
Robot state of timestamp n+1.
Definition: log.h:52
+
RobotCommand command
Robot command of timestamp n, after rate limiting (if activated).
Definition: log.h:56
+
Command sent to the robot.
Definition: log.h:20
+
JointVelocities joint_velocities
sent to the robot.
Definition: log.h:28
+
CartesianVelocities cartesian_velocities
sent to the robot.
Definition: log.h:36
+
JointPositions joint_positions
sent to the robot.
Definition: log.h:24
+
Torques torques
sent to the robot.
Definition: log.h:40
+
CartesianPose cartesian_pose
sent to the robot.
Definition: log.h:32
+
Describes the robot state.
Definition: robot_state.h:34
+
+ + + + diff --git a/lowpass__filter_8h.html b/lowpass__filter_8h.html new file mode 100644 index 00000000..877db1cb --- /dev/null +++ b/lowpass__filter_8h.html @@ -0,0 +1,268 @@ + + + + + + + +libfranka: include/franka/lowpass_filter.h File Reference + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+ +
+
lowpass_filter.h File Reference
+
+
+ +

Contains functions for filtering signals with a low-pass filter. +More...

+
#include <array>
+#include <cmath>
+
+Include dependency graph for lowpass_filter.h:
+
+
+ + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + + + +

+Functions

double franka::lowpassFilter (double sample_time, double y, double y_last, double cutoff_frequency)
 Applies a first-order low-pass filter. More...
 
std::array< double, 16 > franka::cartesianLowpassFilter (double sample_time, std::array< double, 16 > y, std::array< double, 16 > y_last, double cutoff_frequency)
 Applies a first-order low-pass filter to the translation and spherical linear interpolation to the rotation of a transformation matrix which represents a Cartesian Motion. More...
 
+ + + + + + + +

+Variables

+constexpr double franka::kMaxCutoffFrequency = 1000.0
 Maximum cutoff frequency.
 
+constexpr double franka::kDefaultCutoffFrequency = 100.0
 Default cutoff frequency.
 
+

Detailed Description

+

Contains functions for filtering signals with a low-pass filter.

+

Function Documentation

+ +

◆ cartesianLowpassFilter()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
std::array<double, 16> franka::cartesianLowpassFilter (double sample_time,
std::array< double, 16 > y,
std::array< double, 16 > y_last,
double cutoff_frequency 
)
+
+ +

Applies a first-order low-pass filter to the translation and spherical linear interpolation to the rotation of a transformation matrix which represents a Cartesian Motion.

+
Parameters
+ + + + + +
[in]sample_timeSample time constant
[in]yCurrent Cartesian transformation matrix to be filtered
[in]y_lastCartesian transformation matrix from the previous time step
[in]cutoff_frequencyCutoff frequency of the low-pass filter
+
+
+
Exceptions
+ + + + + +
std::invalid_argumentif elements of y is infinite or NaN.
std::invalid_argumentif elements of y_last is infinite or NaN.
std::invalid_argumentif cutoff_frequency is zero, negative, infinite or NaN.
std::invalid_argumentif sample_time is negative, infinite or NaN.
+
+
+
Returns
Filtered Cartesian transformation matrix.
+ +
+
+ +

◆ lowpassFilter()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
double franka::lowpassFilter (double sample_time,
double y,
double y_last,
double cutoff_frequency 
)
+
+ +

Applies a first-order low-pass filter.

+
Parameters
+ + + + + +
[in]sample_timeSample time constant
[in]yCurrent value of the signal to be filtered
[in]y_lastValue of the signal to be filtered in the previous time step
[in]cutoff_frequencyCutoff frequency of the low-pass filter
+
+
+
Exceptions
+ + + + + +
std::invalid_argumentif y is infinite or NaN.
std::invalid_argumentif y_last is infinite or NaN.
std::invalid_argumentif cutoff_frequency is zero, negative, infinite or NaN.
std::invalid_argumentif sample_time is negative, infinite or NaN.
+
+
+
Returns
Filtered value.
+ +
+
+
+ + + + diff --git a/lowpass__filter_8h__dep__incl.map b/lowpass__filter_8h__dep__incl.map new file mode 100644 index 00000000..38e577c9 --- /dev/null +++ b/lowpass__filter_8h__dep__incl.map @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/lowpass__filter_8h__dep__incl.md5 b/lowpass__filter_8h__dep__incl.md5 new file mode 100644 index 00000000..e155d1ef --- /dev/null +++ b/lowpass__filter_8h__dep__incl.md5 @@ -0,0 +1 @@ +72bfa0337d03fb215f3e592c6abfcede \ No newline at end of file diff --git a/lowpass__filter_8h__dep__incl.png b/lowpass__filter_8h__dep__incl.png new file mode 100644 index 00000000..bafe15d5 Binary files /dev/null and b/lowpass__filter_8h__dep__incl.png differ diff --git a/lowpass__filter_8h__incl.map b/lowpass__filter_8h__incl.map new file mode 100644 index 00000000..85ee43b1 --- /dev/null +++ b/lowpass__filter_8h__incl.map @@ -0,0 +1,5 @@ + + + + + diff --git a/lowpass__filter_8h__incl.md5 b/lowpass__filter_8h__incl.md5 new file mode 100644 index 00000000..c54d3d97 --- /dev/null +++ b/lowpass__filter_8h__incl.md5 @@ -0,0 +1 @@ +81234cca7188375c2e4a16790f69f10e \ No newline at end of file diff --git a/lowpass__filter_8h__incl.png b/lowpass__filter_8h__incl.png new file mode 100644 index 00000000..5df81d0d Binary files /dev/null and b/lowpass__filter_8h__incl.png differ diff --git a/lowpass__filter_8h_source.html b/lowpass__filter_8h_source.html new file mode 100644 index 00000000..2cb9355a --- /dev/null +++ b/lowpass__filter_8h_source.html @@ -0,0 +1,109 @@ + + + + + + + +libfranka: include/franka/lowpass_filter.h Source File + + + + + + + + + + + +
+
+ + + + + + + +
+
libfranka +  0.14.0 +
+
FCI C++ API
+
+
+ + + + + + + + +
+
+ + +
+ +
+ + +
+
+
+
lowpass_filter.h
+
+
+Go to the documentation of this file.
1 // Copyright (c) 2023 Franka Robotics GmbH
+
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
+
3 #pragma once
+
4 
+
5 #include <array>
+
6 #include <cmath>
+
7 
+
13 namespace franka {
+
17 constexpr double kMaxCutoffFrequency = 1000.0;
+
21 constexpr double kDefaultCutoffFrequency = 100.0;
+
37 double lowpassFilter(double sample_time, double y, double y_last, double cutoff_frequency);
+
38 
+
56 std::array<double, 16> cartesianLowpassFilter(double sample_time,
+
57  std::array<double, 16> y,
+
58  std::array<double, 16> y_last,
+
59  double cutoff_frequency);
+
60 } // namespace franka
+
double lowpassFilter(double sample_time, double y, double y_last, double cutoff_frequency)
Applies a first-order low-pass filter.
+
std::array< double, 16 > cartesianLowpassFilter(double sample_time, std::array< double, 16 > y, std::array< double, 16 > y_last, double cutoff_frequency)
Applies a first-order low-pass filter to the translation and spherical linear interpolation to the ro...
+
constexpr double kDefaultCutoffFrequency
Default cutoff frequency.
Definition: lowpass_filter.h:21
+
constexpr double kMaxCutoffFrequency
Maximum cutoff frequency.
Definition: lowpass_filter.h:17
+
+ + + + diff --git a/menu.js b/menu.js new file mode 100644 index 00000000..2fe2214f --- /dev/null +++ b/menu.js @@ -0,0 +1,51 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file + */ +function initMenu(relPath,searchEnabled,serverSide,searchPage,search) { + function makeTree(data,relPath) { + var result=''; + if ('children' in data) { + result+=''; + } + return result; + } + + $('#main-nav').append(makeTree(menudata,relPath)); + $('#main-nav').children(':first').addClass('sm sm-dox').attr('id','main-menu'); + if (searchEnabled) { + if (serverSide) { + $('#main-menu').append('
  • '); + } else { + $('#main-menu').append('
  • '); + } + } + $('#main-menu').smartmenus(); +} +/* @license-end */ diff --git a/menudata.js b/menudata.js new file mode 100644 index 00000000..8da82039 --- /dev/null +++ b/menudata.js @@ -0,0 +1,107 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file +*/ +var menudata={children:[ +{text:"Main Page",url:"index.html"}, +{text:"Classes",url:"annotated.html",children:[ +{text:"Class List",url:"annotated.html"}, +{text:"Class Index",url:"classes.html"}, +{text:"Class Hierarchy",url:"inherits.html"}, +{text:"Class Members",url:"functions.html",children:[ +{text:"All",url:"functions.html",children:[ +{text:"a",url:"functions.html#index_a"}, +{text:"b",url:"functions_b.html#index_b"}, +{text:"c",url:"functions_c.html#index_c"}, +{text:"d",url:"functions_d.html#index_d"}, +{text:"e",url:"functions_e.html#index_e"}, +{text:"f",url:"functions_f.html#index_f"}, +{text:"g",url:"functions_g.html#index_g"}, +{text:"h",url:"functions_h.html#index_h"}, +{text:"i",url:"functions_i.html#index_i"}, +{text:"j",url:"functions_j.html#index_j"}, +{text:"k",url:"functions_k.html#index_k"}, +{text:"l",url:"functions_l.html#index_l"}, +{text:"m",url:"functions_m.html#index_m"}, +{text:"n",url:"functions_n.html#index_n"}, +{text:"o",url:"functions_o.html#index_o"}, +{text:"p",url:"functions_p.html#index_p"}, +{text:"q",url:"functions_q.html#index_q"}, +{text:"r",url:"functions_r.html#index_r"}, +{text:"s",url:"functions_s.html#index_s"}, +{text:"t",url:"functions_t.html#index_t"}, +{text:"v",url:"functions_v.html#index_v"}, +{text:"w",url:"functions_w.html#index_w"}, +{text:"z",url:"functions_z.html#index_z"}, +{text:"~",url:"functions_~.html#index__7E"}]}, +{text:"Functions",url:"functions_func.html",children:[ +{text:"a",url:"functions_func.html#index_a"}, +{text:"b",url:"functions_func.html#index_b"}, +{text:"c",url:"functions_func.html#index_c"}, +{text:"d",url:"functions_func.html#index_d"}, +{text:"e",url:"functions_func.html#index_e"}, +{text:"g",url:"functions_func.html#index_g"}, +{text:"h",url:"functions_func.html#index_h"}, +{text:"i",url:"functions_func.html#index_i"}, +{text:"j",url:"functions_func.html#index_j"}, +{text:"l",url:"functions_func.html#index_l"}, +{text:"m",url:"functions_func.html#index_m"}, +{text:"o",url:"functions_func.html#index_o"}, +{text:"p",url:"functions_func.html#index_p"}, +{text:"r",url:"functions_func.html#index_r"}, +{text:"s",url:"functions_func.html#index_s"}, +{text:"t",url:"functions_func.html#index_t"}, +{text:"v",url:"functions_func.html#index_v"}, +{text:"w",url:"functions_func.html#index_w"}, +{text:"z",url:"functions_func.html#index_z"}, +{text:"~",url:"functions_func.html#index__7E"}]}, +{text:"Variables",url:"functions_vars.html",children:[ +{text:"a",url:"functions_vars.html#index_a"}, +{text:"b",url:"functions_vars.html#index_b"}, +{text:"c",url:"functions_vars.html#index_c"}, +{text:"d",url:"functions_vars.html#index_d"}, +{text:"e",url:"functions_vars.html#index_e"}, +{text:"f",url:"functions_vars.html#index_f"}, +{text:"i",url:"functions_vars.html#index_i"}, +{text:"j",url:"functions_vars.html#index_j"}, +{text:"k",url:"functions_vars.html#index_k"}, +{text:"l",url:"functions_vars.html#index_l"}, +{text:"m",url:"functions_vars.html#index_m"}, +{text:"n",url:"functions_vars.html#index_n"}, +{text:"o",url:"functions_vars.html#index_o"}, +{text:"p",url:"functions_vars.html#index_p"}, +{text:"q",url:"functions_vars.html#index_q"}, +{text:"r",url:"functions_vars.html#index_r"}, +{text:"s",url:"functions_vars.html#index_s"}, +{text:"t",url:"functions_vars.html#index_t"}, +{text:"v",url:"functions_vars.html#index_v"}, +{text:"w",url:"functions_vars.html#index_w"}]}, +{text:"Typedefs",url:"functions_type.html"}, +{text:"Enumerations",url:"functions_enum.html"}, +{text:"Related Functions",url:"functions_rela.html"}]}]}, +{text:"Files",url:"files.html",children:[ +{text:"File List",url:"files.html"}, +{text:"File Members",url:"globals.html",children:[ +{text:"All",url:"globals.html"}, +{text:"Functions",url:"globals_func.html"}]}]}, +{text:"Examples",url:"examples.html"}]} diff --git a/model_8h.html b/model_8h.html new file mode 100644 index 00000000..d7d19ed4 --- /dev/null +++ b/model_8h.html @@ -0,0 +1,212 @@ + + + + + + + +libfranka: include/franka/model.h File Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    model.h File Reference
    +
    +
    + +

    Contains model library types. +More...

    +
    #include <array>
    +#include <memory>
    +#include <franka/robot.h>
    +#include <franka/robot_model_base.h>
    +#include <franka/robot_state.h>
    +
    +Include dependency graph for model.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  franka::Model
     Calculates poses of joints and dynamic properties of the robot. More...
     
    + + + + +

    +Enumerations

    enum class  franka::Frame {
    +  kJoint1 +, kJoint2 +, kJoint3 +, kJoint4 +,
    +  kJoint5 +, kJoint6 +, kJoint7 +, kFlange +,
    +  kEndEffector +, kStiffness +
    + }
     Enumerates the seven joints, the flange, and the end effector of a robot.
     
    + + + + +

    +Functions

    Frame franka::operator++ (Frame &frame, int) noexcept
     Post-increments the given Frame by one. More...
     
    +

    Detailed Description

    +

    Contains model library types.

    +

    Function Documentation

    + +

    ◆ operator++()

    + +
    +
    + + + + + +
    + + + + + + + + + + + + + + + + + + +
    Frame franka::operator++ (Frameframe,
    int  
    )
    +
    +noexcept
    +
    + +

    Post-increments the given Frame by one.

    +

    For example, Frame::kJoint2++ results in Frame::kJoint3.

    +
    Parameters
    + + +
    [in]frameFrame to increment.
    +
    +
    +
    Returns
    Original Frame.
    + +
    +
    +
    + + + + diff --git a/model_8h__incl.map b/model_8h__incl.map new file mode 100644 index 00000000..8b86fe4b --- /dev/null +++ b/model_8h__incl.map @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/model_8h__incl.md5 b/model_8h__incl.md5 new file mode 100644 index 00000000..6882520d --- /dev/null +++ b/model_8h__incl.md5 @@ -0,0 +1 @@ +959268beaead9c169c5ca1561c6508c0 \ No newline at end of file diff --git a/model_8h__incl.png b/model_8h__incl.png new file mode 100644 index 00000000..72648751 Binary files /dev/null and b/model_8h__incl.png differ diff --git a/model_8h_source.html b/model_8h_source.html new file mode 100644 index 00000000..a870cfa6 --- /dev/null +++ b/model_8h_source.html @@ -0,0 +1,216 @@ + + + + + + + +libfranka: include/franka/model.h Source File + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    model.h
    +
    +
    +Go to the documentation of this file.
    1 // Copyright (c) 2023 Franka Robotics GmbH
    +
    2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    3 #pragma once
    +
    4 
    +
    5 #include <array>
    +
    6 #include <memory>
    +
    7 
    +
    8 #include <franka/robot.h>
    +
    9 #include <franka/robot_model_base.h>
    +
    10 #include <franka/robot_state.h>
    +
    11 
    +
    17 namespace franka {
    +
    18 
    +
    22 enum class Frame {
    +
    23  kJoint1,
    +
    24  kJoint2,
    +
    25  kJoint3,
    +
    26  kJoint4,
    +
    27  kJoint5,
    +
    28  kJoint6,
    +
    29  kJoint7,
    +
    30  kFlange,
    +
    31  kEndEffector,
    +
    32  kStiffness
    +
    33 };
    +
    34 
    +
    44 Frame operator++(Frame& frame, int /* dummy */) noexcept;
    +
    45 
    +
    46 class ModelLibrary;
    +
    47 class Network;
    +
    48 
    +
    52 class Model {
    +
    53  public:
    +
    65  explicit Model(franka::Network& network, const std::string& urdf_model);
    +
    66 
    +
    76  explicit Model(franka::Network& network, std::unique_ptr<RobotModelBase> robot_model);
    +
    77 
    +
    83  Model(Model&& model) noexcept;
    +
    84 
    +
    92  Model& operator=(Model&& model) noexcept;
    +
    93 
    +
    97  ~Model() noexcept;
    +
    98 
    +
    109  std::array<double, 16> pose(Frame frame, const franka::RobotState& robot_state) const;
    +
    110 
    +
    123  std::array<double, 16> pose(
    +
    124  Frame frame,
    +
    125  const std::array<double, 7>& q,
    +
    126  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
    +
    127  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
    +
    128  const;
    +
    129 
    +
    140  std::array<double, 42> bodyJacobian(Frame frame, const franka::RobotState& robot_state) const;
    +
    141 
    +
    154  std::array<double, 42> bodyJacobian(
    +
    155  Frame frame,
    +
    156  const std::array<double, 7>& q,
    +
    157  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
    +
    158  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
    +
    159  const;
    +
    160 
    +
    171  std::array<double, 42> zeroJacobian(Frame frame, const franka::RobotState& robot_state) const;
    +
    172 
    +
    185  std::array<double, 42> zeroJacobian(
    +
    186  Frame frame,
    +
    187  const std::array<double, 7>& q,
    +
    188  const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
    +
    189  const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
    +
    190  const;
    +
    191 
    +
    199  std::array<double, 49> mass(const franka::RobotState& robot_state) const noexcept;
    +
    200 
    +
    214  std::array<double, 49> mass(
    +
    215  const std::array<double, 7>& q,
    +
    216  const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
    +
    217  double m_total,
    +
    218  const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
    +
    219  const noexcept;
    +
    220 
    +
    229  std::array<double, 7> coriolis(const franka::RobotState& robot_state) const noexcept;
    +
    230 
    +
    246  std::array<double, 7> coriolis(
    +
    247  const std::array<double, 7>& q,
    +
    248  const std::array<double, 7>& dq,
    +
    249  const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
    +
    250  double m_total,
    +
    251  const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
    +
    252  const noexcept;
    +
    253 
    +
    267  std::array<double, 7> gravity(
    +
    268  const std::array<double, 7>& q,
    +
    269  double m_total,
    +
    270  const std::array<double, 3>& F_x_Ctotal, // NOLINT(readability-identifier-naming)
    +
    271  const std::array<double, 3>& gravity_earth = {{0., 0., -9.81}}) const noexcept;
    +
    272 
    +
    281  std::array<double, 7> gravity(const franka::RobotState& robot_state,
    +
    282  const std::array<double, 3>& gravity_earth) const noexcept;
    +
    283 
    +
    291  std::array<double, 7> gravity(const franka::RobotState& robot_state) const noexcept;
    +
    292 
    +
    294  Model(const Model&) = delete;
    +
    295  Model& operator=(const Model&) = delete;
    +
    297 
    +
    298  private:
    +
    299  std::unique_ptr<ModelLibrary> library_;
    +
    300  std::unique_ptr<RobotModelBase> robot_model_;
    +
    301 };
    +
    302 
    +
    303 } // namespace franka
    +
    Calculates poses of joints and dynamic properties of the robot.
    Definition: model.h:52
    +
    ~Model() noexcept
    Unloads the model library.
    +
    std::array< double, 16 > pose(Frame frame, const franka::RobotState &robot_state) const
    Gets the 4x4 pose matrix for the given frame in base frame.
    +
    Model & operator=(Model &&model) noexcept
    Move-assigns this Model from another Model instance.
    +
    std::array< double, 42 > zeroJacobian(Frame frame, const franka::RobotState &robot_state) const
    Gets the 6x7 Jacobian for the given joint relative to the base frame.
    +
    std::array< double, 7 > gravity(const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const noexcept
    Calculates the gravity vector.
    +
    Model(franka::Network &network, std::unique_ptr< RobotModelBase > robot_model)
    Creates a new Model instance only for the tests.
    +
    Model(Model &&model) noexcept
    Move-constructs a new Model instance.
    +
    Model(franka::Network &network, const std::string &urdf_model)
    Creates a new Model instance.
    +
    std::array< double, 7 > coriolis(const franka::RobotState &robot_state) const noexcept
    Calculates the Coriolis force vector (state-space equation): , in .
    +
    std::array< double, 42 > bodyJacobian(Frame frame, const franka::RobotState &robot_state) const
    Gets the 6x7 Jacobian for the given frame, relative to that frame.
    +
    std::array< double, 7 > gravity(const franka::RobotState &robot_state) const noexcept
    Calculates the gravity vector using the robot state.
    +
    std::array< double, 7 > gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexcept
    Calculates the gravity vector.
    +
    std::array< double, 49 > mass(const franka::RobotState &robot_state) const noexcept
    Calculates the 7x7 mass matrix.
    +
    Frame
    Enumerates the seven joints, the flange, and the end effector of a robot.
    Definition: model.h:22
    +
    Frame operator++(Frame &frame, int) noexcept
    Post-increments the given Frame by one.
    +
    Contains the franka::Robot type.
    +
    Contains the franka::RobotState types.
    +
    Describes the robot state.
    Definition: robot_state.h:34
    +
    + + + + diff --git a/motion_with_control_8cpp-example.html b/motion_with_control_8cpp-example.html new file mode 100644 index 00000000..6e31b0f7 --- /dev/null +++ b/motion_with_control_8cpp-example.html @@ -0,0 +1,305 @@ + + + + + + + +libfranka: motion_with_control.cpp + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + +
    + +
    +
    + + +
    + +
    + +
    +
    +
    motion_with_control.cpp
    +
    +
    +

    An example showing how to use a joint velocity motion generator and torque control.Additionally, this example shows how to capture and write logs in case an exception is thrown during a motion.

    +
    Warning
    Before executing this example, make sure there is enough space in front of the robot.
    +
    // Copyright (c) 2023 Franka Robotics GmbH
    +
    // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    #include <cmath>
    +
    #include <fstream>
    +
    #include <iomanip>
    +
    #include <iostream>
    +
    #include <vector>
    +
    +
    #include <Poco/DateTimeFormatter.h>
    +
    #include <Poco/File.h>
    +
    #include <Poco/Path.h>
    +
    + +
    #include <franka/robot.h>
    +
    + +
    +
    namespace {
    +
    +
    class Controller {
    +
    public:
    +
    Controller(size_t dq_filter_size,
    +
    const std::array<double, 7>& K_P, // NOLINT(readability-identifier-naming)
    +
    const std::array<double, 7>& K_D) // NOLINT(readability-identifier-naming)
    +
    : dq_current_filter_position_(0), dq_filter_size_(dq_filter_size), K_P_(K_P), K_D_(K_D) {
    +
    std::fill(dq_d_.begin(), dq_d_.end(), 0);
    +
    dq_buffer_ = std::make_unique<double[]>(dq_filter_size_ * 7);
    +
    std::fill(&dq_buffer_.get()[0], &dq_buffer_.get()[dq_filter_size_ * 7], 0);
    +
    }
    +
    +
    inline franka::Torques step(const franka::RobotState& state) {
    +
    updateDQFilter(state);
    +
    +
    std::array<double, 7> tau_J_d; // NOLINT(readability-identifier-naming)
    +
    for (size_t i = 0; i < 7; i++) {
    +
    tau_J_d[i] = K_P_[i] * (state.q_d[i] - state.q[i]) + K_D_[i] * (dq_d_[i] - getDQFiltered(i));
    +
    }
    +
    return tau_J_d;
    +
    }
    +
    +
    void updateDQFilter(const franka::RobotState& state) {
    +
    for (size_t i = 0; i < 7; i++) {
    +
    dq_buffer_.get()[dq_current_filter_position_ * 7 + i] = state.dq[i];
    +
    }
    +
    dq_current_filter_position_ = (dq_current_filter_position_ + 1) % dq_filter_size_;
    +
    }
    +
    +
    double getDQFiltered(size_t index) const {
    +
    double value = 0;
    +
    for (size_t i = index; i < 7 * dq_filter_size_; i += 7) {
    +
    value += dq_buffer_.get()[i];
    +
    }
    +
    return value / dq_filter_size_;
    +
    }
    +
    +
    private:
    +
    size_t dq_current_filter_position_;
    +
    size_t dq_filter_size_;
    +
    +
    const std::array<double, 7> K_P_; // NOLINT(readability-identifier-naming)
    +
    const std::array<double, 7> K_D_; // NOLINT(readability-identifier-naming)
    +
    +
    std::array<double, 7> dq_d_;
    +
    std::unique_ptr<double[]> dq_buffer_;
    +
    };
    +
    +
    std::vector<double> generateTrajectory(double a_max) {
    +
    // Generating a motion with smooth velocity and acceleration.
    +
    // Squared sine is used for the acceleration/deceleration phase.
    +
    std::vector<double> trajectory;
    +
    constexpr double kTimeStep = 0.001; // [s]
    +
    constexpr double kAccelerationTime = 1; // time spend accelerating and decelerating [s]
    +
    constexpr double kConstantVelocityTime = 1; // time spend with constant speed [s]
    +
    // obtained during the speed up
    +
    // and slow down [rad/s^2]
    +
    double a = 0; // [rad/s^2]
    +
    double v = 0; // [rad/s]
    +
    double t = 0; // [s]
    +
    while (t < (2 * kAccelerationTime + kConstantVelocityTime)) {
    +
    if (t <= kAccelerationTime) {
    +
    a = pow(sin(t * M_PI / kAccelerationTime), 2) * a_max;
    +
    } else if (t <= (kAccelerationTime + kConstantVelocityTime)) {
    +
    a = 0;
    +
    } else {
    +
    const double deceleration_time =
    +
    (kAccelerationTime + kConstantVelocityTime) - t; // time spent in the deceleration phase
    +
    a = -pow(sin(deceleration_time * M_PI / kAccelerationTime), 2) * a_max;
    +
    }
    +
    v += a * kTimeStep;
    +
    t += kTimeStep;
    +
    trajectory.push_back(v);
    +
    }
    +
    return trajectory;
    +
    }
    +
    +
    } // anonymous namespace
    +
    +
    void writeLogToFile(const std::vector<franka::Record>& log);
    +
    +
    int main(int argc, char** argv) {
    +
    if (argc != 2) {
    +
    std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
    +
    return -1;
    +
    }
    +
    +
    // Parameters
    +
    const size_t joint_number{3};
    +
    const size_t filter_size{5};
    +
    +
    // NOLINTNEXTLINE(readability-identifier-naming)
    +
    const std::array<double, 7> K_P{{200.0, 200.0, 200.0, 200.0, 200.0, 200.0, 200.0}};
    +
    // NOLINTNEXTLINE(readability-identifier-naming)
    +
    const std::array<double, 7> K_D{{10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0}};
    +
    const double max_acceleration{1.0};
    +
    +
    Controller controller(filter_size, K_P, K_D);
    +
    +
    try {
    +
    franka::Robot robot(argv[1]);
    + +
    +
    // First move the robot to a suitable joint configuration
    +
    std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
    +
    MotionGenerator motion_generator(0.5, q_goal);
    +
    std::cout << "WARNING: This example will move the robot! "
    +
    << "Please make sure to have the user stop button at hand!" << std::endl
    +
    << "Press Enter to continue..." << std::endl;
    +
    std::cin.ignore();
    +
    robot.control(motion_generator);
    +
    std::cout << "Finished moving to initial joint configuration." << std::endl;
    +
    +
    // Set additional parameters always before the control loop, NEVER in the control loop!
    +
    // Set collision behavior.
    +
    robot.setCollisionBehavior(
    +
    {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
    +
    {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
    +
    {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
    +
    {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
    +
    +
    size_t index = 0;
    +
    std::vector<double> trajectory = generateTrajectory(max_acceleration);
    +
    +
    robot.control(
    +
    [&](const franka::RobotState& robot_state, franka::Duration) -> franka::Torques {
    +
    return controller.step(robot_state);
    +
    },
    + +
    index += period.toMSec();
    +
    +
    if (index >= trajectory.size()) {
    +
    index = trajectory.size() - 1;
    +
    }
    +
    +
    franka::JointVelocities velocities{{0, 0, 0, 0, 0, 0, 0}};
    +
    velocities.dq[joint_number] = trajectory[index];
    +
    +
    if (index >= trajectory.size() - 1) {
    +
    return franka::MotionFinished(velocities);
    +
    }
    +
    return velocities;
    +
    });
    +
    } catch (const franka::ControlException& e) {
    +
    std::cout << e.what() << std::endl;
    +
    writeLogToFile(e.log);
    +
    return -1;
    +
    } catch (const franka::Exception& e) {
    +
    std::cout << e.what() << std::endl;
    +
    return -1;
    +
    }
    +
    +
    return 0;
    +
    }
    +
    +
    void writeLogToFile(const std::vector<franka::Record>& log) {
    +
    if (log.empty()) {
    +
    return;
    +
    }
    +
    try {
    +
    Poco::Path temp_dir_path(Poco::Path::temp());
    +
    temp_dir_path.pushDirectory("libfranka-logs");
    +
    +
    Poco::File temp_dir(temp_dir_path);
    +
    temp_dir.createDirectories();
    +
    +
    std::string now_string =
    +
    Poco::DateTimeFormatter::format(Poco::Timestamp{}, "%Y-%m-%d-%h-%m-%S-%i");
    +
    std::string filename = std::string{"log-" + now_string + ".csv"};
    +
    Poco::File log_file(Poco::Path(temp_dir_path, filename));
    +
    if (!log_file.createFile()) {
    +
    std::cout << "Failed to write log file." << std::endl;
    +
    return;
    +
    }
    +
    std::ofstream log_stream(log_file.path().c_str());
    +
    log_stream << franka::logToCSV(log);
    +
    +
    std::cout << "Log file written to: " << log_file.path() << std::endl;
    +
    } catch (...) {
    +
    std::cout << "Failed to write log file." << std::endl;
    +
    }
    +
    }
    +
    An example showing how to generate a joint pose motion to a goal position.
    Definition: examples_common.h:31
    +
    Represents a duration with millisecond resolution.
    Definition: duration.h:19
    +
    Stores values for joint velocity motion generation.
    Definition: control_types.h:99
    +
    std::array< double, 7 > dq
    Desired joint velocities in .
    Definition: control_types.h:121
    +
    Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
    Definition: robot.h:68
    +
    Stores joint-level torque commands without gravity and friction.
    Definition: control_types.h:45
    +
    Torques MotionFinished(Torques command) noexcept
    Helper method to indicate that a motion should stop after processing the given command.
    Definition: control_types.h:294
    +
    Contains common types and functions for the examples.
    +
    void setDefaultBehavior(franka::Robot &robot)
    Sets a default collision behavior, joint impedance and Cartesian impedance.
    Definition: examples_common.cpp:12
    +
    Contains exception definitions.
    +
    std::string logToCSV(const std::vector< Record > &log)
    Writes the log to a string in CSV format.
    +
    Contains the franka::Robot type.
    +
    ControlException is thrown if an error occurs during motion generation or torque control.
    Definition: exception.h:73
    +
    const std::vector< franka::Record > log
    Vector of states and commands logged just before the exception occurred.
    Definition: exception.h:85
    +
    Base class for all exceptions used by libfranka.
    Definition: exception.h:20
    +
    Describes the robot state.
    Definition: robot_state.h:34
    +
    std::array< double, 7 > q_d
    Desired joint position.
    Definition: robot_state.h:239
    +
    std::array< double, 7 > q
    Measured joint position.
    Definition: robot_state.h:233
    +
    std::array< double, 7 > dq
    Measured joint velocity.
    Definition: robot_state.h:245
    +
    + + + + diff --git a/motion_with_control_external_control_loop_8cpp-example.html b/motion_with_control_external_control_loop_8cpp-example.html new file mode 100644 index 00000000..dd24277c --- /dev/null +++ b/motion_with_control_external_control_loop_8cpp-example.html @@ -0,0 +1,326 @@ + + + + + + + +libfranka: motion_with_control_external_control_loop.cpp + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + +
    + +
    +
    + + +
    + +
    + +
    +
    +
    motion_with_control_external_control_loop.cpp
    +
    +
    +

    An example showing how to use a joint velocity motion generator and torque control with an external control loop.Additionally, this example shows how to capture and write logs in case an exception is thrown during a motion.

    +
    Warning
    Before executing this example, make sure there is enough space in front of the robot.
    +
    // Copyright (c) 2023 Franka Robotics GmbH
    +
    // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    #include <cmath>
    +
    #include <fstream>
    +
    #include <iomanip>
    +
    #include <iostream>
    +
    #include <vector>
    +
    +
    #include <Poco/DateTimeFormatter.h>
    +
    #include <Poco/File.h>
    +
    #include <Poco/Path.h>
    +
    + + + +
    #include <franka/robot.h>
    +
    + +
    +
    namespace {
    +
    +
    class Controller {
    +
    public:
    +
    Controller(size_t dq_filter_size,
    +
    const std::array<double, 7>& K_P, // NOLINT(readability-identifier-naming)
    +
    const std::array<double, 7>& K_D) // NOLINT(readability-identifier-naming)
    +
    : dq_current_filter_position_(0), dq_filter_size_(dq_filter_size), K_P_(K_P), K_D_(K_D) {
    +
    std::fill(dq_d_.begin(), dq_d_.end(), 0);
    +
    dq_buffer_ = std::make_unique<double[]>(dq_filter_size_ * 7);
    +
    std::fill(&dq_buffer_.get()[0], &dq_buffer_.get()[dq_filter_size_ * 7], 0);
    +
    }
    +
    +
    inline franka::Torques step(const franka::RobotState& state) {
    +
    updateDQFilter(state);
    +
    +
    std::array<double, 7> tau_J_d; // NOLINT(readability-identifier-naming)
    +
    for (size_t i = 0; i < 7; i++) {
    +
    tau_J_d[i] = K_P_[i] * (state.q_d[i] - state.q[i]) + K_D_[i] * (dq_d_[i] - getDQFiltered(i));
    +
    }
    +
    return tau_J_d;
    +
    }
    +
    +
    void updateDQFilter(const franka::RobotState& state) {
    +
    for (size_t i = 0; i < 7; i++) {
    +
    dq_buffer_.get()[dq_current_filter_position_ * 7 + i] = state.dq[i];
    +
    }
    +
    dq_current_filter_position_ = (dq_current_filter_position_ + 1) % dq_filter_size_;
    +
    }
    +
    +
    double getDQFiltered(size_t index) const {
    +
    double value = 0;
    +
    for (size_t i = index; i < 7 * dq_filter_size_; i += 7) {
    +
    value += dq_buffer_.get()[i];
    +
    }
    +
    return value / dq_filter_size_;
    +
    }
    +
    +
    private:
    +
    size_t dq_current_filter_position_;
    +
    size_t dq_filter_size_;
    +
    +
    const std::array<double, 7> K_P_; // NOLINT(readability-identifier-naming)
    +
    const std::array<double, 7> K_D_; // NOLINT(readability-identifier-naming)
    +
    +
    std::array<double, 7> dq_d_;
    +
    std::unique_ptr<double[]> dq_buffer_;
    +
    };
    +
    +
    std::vector<double> generateTrajectory(double a_max) {
    +
    // Generating a motion with smooth velocity and acceleration.
    +
    // Squared sine is used for the acceleration/deceleration phase.
    +
    std::vector<double> trajectory;
    +
    constexpr double kTimeStep = 0.001; // [s]
    +
    constexpr double kAccelerationTime = 1; // time spend accelerating and decelerating [s]
    +
    constexpr double kConstantVelocityTime = 1; // time spend with constant speed [s]
    +
    // obtained during the speed up
    +
    // and slow down [rad/s^2]
    +
    double a = 0; // [rad/s^2]
    +
    double v = 0; // [rad/s]
    +
    double t = 0; // [s]
    +
    while (t < (2 * kAccelerationTime + kConstantVelocityTime)) {
    +
    if (t <= kAccelerationTime) {
    +
    a = pow(sin(t * M_PI / kAccelerationTime), 2) * a_max;
    +
    } else if (t <= (kAccelerationTime + kConstantVelocityTime)) {
    +
    a = 0;
    +
    } else {
    +
    const double deceleration_time =
    +
    (kAccelerationTime + kConstantVelocityTime) - t; // time spent in the deceleration phase
    +
    a = -pow(sin(deceleration_time * M_PI / kAccelerationTime), 2) * a_max;
    +
    }
    +
    v += a * kTimeStep;
    +
    t += kTimeStep;
    +
    trajectory.push_back(v);
    +
    }
    +
    return trajectory;
    +
    }
    +
    +
    } // anonymous namespace
    +
    +
    void writeLogToFile(const std::vector<franka::Record>& log);
    +
    +
    int main(int argc, char** argv) {
    +
    // Check whether the required arguments were passed
    +
    if (argc != 2) {
    +
    std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
    +
    return -1;
    +
    }
    +
    +
    // Parameters
    +
    const size_t joint_number{3};
    +
    const size_t filter_size{5};
    +
    +
    // NOLINTNEXTLINE(readability-identifier-naming)
    +
    const std::array<double, 7> K_P{{200.0, 200.0, 200.0, 200.0, 200.0, 200.0, 200.0}};
    +
    // NOLINTNEXTLINE(readability-identifier-naming)
    +
    const std::array<double, 7> K_D{{10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0}};
    +
    const double max_acceleration{1.0};
    +
    +
    Controller controller(filter_size, K_P, K_D);
    +
    +
    try {
    +
    franka::Robot robot(argv[1]);
    + +
    +
    // First move the robot to a suitable joint configuration
    +
    std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
    +
    MotionGenerator motion_generator(0.5, q_goal);
    +
    std::cout << "WARNING: This example will move the robot! "
    +
    << "Please make sure to have the user stop button at hand!" << std::endl
    +
    << "Press Enter to continue..." << std::endl;
    +
    std::cin.ignore();
    +
    robot.control(motion_generator);
    +
    std::cout << "Finished moving to initial joint configuration." << std::endl;
    +
    +
    // Set additional parameters always before the control loop, NEVER in the control loop!
    +
    // Set collision behavior.
    +
    robot.setCollisionBehavior(
    +
    {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
    +
    {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
    +
    {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
    +
    {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
    +
    +
    size_t index = 0;
    +
    std::vector<double> trajectory = generateTrajectory(max_acceleration);
    +
    +
    auto callback_control = [&](const franka::RobotState& robot_state,
    + +
    return controller.step(robot_state);
    +
    };
    +
    +
    auto callback_motion_generator = [&](const franka::RobotState&,
    + +
    index += period.toMSec();
    +
    +
    if (index >= trajectory.size()) {
    +
    index = trajectory.size() - 1;
    +
    }
    +
    +
    franka::JointVelocities velocities{{0, 0, 0, 0, 0, 0, 0}};
    +
    velocities.dq[joint_number] = trajectory[index];
    +
    +
    if (index >= trajectory.size() - 1) {
    +
    return franka::MotionFinished(velocities);
    +
    }
    +
    return velocities;
    +
    };
    +
    +
    bool motion_finished = false;
    +
    auto active_control = robot.startJointVelocityControl(
    +
    research_interface::robot::Move::ControllerMode::kExternalController);
    +
    while (!motion_finished) {
    +
    auto read_once_return = active_control->readOnce();
    +
    auto robot_state = read_once_return.first;
    +
    auto duration = read_once_return.second;
    +
    auto cartesian_velocities = callback_motion_generator(robot_state, duration);
    +
    auto torques = callback_control(robot_state, duration);
    +
    motion_finished = cartesian_velocities.motion_finished;
    +
    active_control->writeOnce(cartesian_velocities, torques);
    +
    }
    +
    +
    } catch (const franka::ControlException& e) {
    +
    std::cout << e.what() << std::endl;
    +
    writeLogToFile(e.log);
    +
    return -1;
    +
    } catch (const franka::Exception& e) {
    +
    std::cout << e.what() << std::endl;
    +
    return -1;
    +
    }
    +
    +
    return 0;
    +
    }
    +
    +
    void writeLogToFile(const std::vector<franka::Record>& log) {
    +
    if (log.empty()) {
    +
    return;
    +
    }
    +
    try {
    +
    Poco::Path temp_dir_path(Poco::Path::temp());
    +
    temp_dir_path.pushDirectory("libfranka-logs");
    +
    +
    Poco::File temp_dir(temp_dir_path);
    +
    temp_dir.createDirectories();
    +
    +
    std::string now_string =
    +
    Poco::DateTimeFormatter::format(Poco::Timestamp{}, "%Y-%m-%d-%h-%m-%S-%i");
    +
    std::string filename = std::string{"log-" + now_string + ".csv"};
    +
    Poco::File log_file(Poco::Path(temp_dir_path, filename));
    +
    if (!log_file.createFile()) {
    +
    std::cout << "Failed to write log file." << std::endl;
    +
    return;
    +
    }
    +
    std::ofstream log_stream(log_file.path().c_str());
    +
    log_stream << franka::logToCSV(log);
    +
    +
    std::cout << "Log file written to: " << log_file.path() << std::endl;
    +
    } catch (...) {
    +
    std::cout << "Failed to write log file." << std::endl;
    +
    }
    +
    }
    +
    Implements the ActiveControlBase abstract class.
    +
    Contains the franka::ActiveMotionGenerator type.
    +
    An example showing how to generate a joint pose motion to a goal position.
    Definition: examples_common.h:31
    +
    Represents a duration with millisecond resolution.
    Definition: duration.h:19
    +
    Stores values for joint velocity motion generation.
    Definition: control_types.h:99
    +
    std::array< double, 7 > dq
    Desired joint velocities in .
    Definition: control_types.h:121
    +
    Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
    Definition: robot.h:68
    +
    Stores joint-level torque commands without gravity and friction.
    Definition: control_types.h:45
    +
    Torques MotionFinished(Torques command) noexcept
    Helper method to indicate that a motion should stop after processing the given command.
    Definition: control_types.h:294
    +
    Contains common types and functions for the examples.
    +
    void setDefaultBehavior(franka::Robot &robot)
    Sets a default collision behavior, joint impedance and Cartesian impedance.
    Definition: examples_common.cpp:12
    +
    Contains exception definitions.
    +
    std::string logToCSV(const std::vector< Record > &log)
    Writes the log to a string in CSV format.
    +
    Contains the franka::Robot type.
    +
    ControlException is thrown if an error occurs during motion generation or torque control.
    Definition: exception.h:73
    +
    const std::vector< franka::Record > log
    Vector of states and commands logged just before the exception occurred.
    Definition: exception.h:85
    +
    Base class for all exceptions used by libfranka.
    Definition: exception.h:20
    +
    Describes the robot state.
    Definition: robot_state.h:34
    +
    std::array< double, 7 > q_d
    Desired joint position.
    Definition: robot_state.h:239
    +
    std::array< double, 7 > q
    Measured joint position.
    Definition: robot_state.h:233
    +
    std::array< double, 7 > dq
    Measured joint velocity.
    Definition: robot_state.h:245
    +
    + + + + diff --git a/nav_f.png b/nav_f.png new file mode 100644 index 00000000..72a58a52 Binary files /dev/null and b/nav_f.png differ diff --git a/nav_g.png b/nav_g.png new file mode 100644 index 00000000..2093a237 Binary files /dev/null and b/nav_g.png differ diff --git a/nav_h.png b/nav_h.png new file mode 100644 index 00000000..33389b10 Binary files /dev/null and b/nav_h.png differ diff --git a/open.png b/open.png new file mode 100644 index 00000000..30f75c7e Binary files /dev/null and b/open.png differ diff --git a/print_joint_poses_8cpp-example.html b/print_joint_poses_8cpp-example.html new file mode 100644 index 00000000..b6ab40b2 --- /dev/null +++ b/print_joint_poses_8cpp-example.html @@ -0,0 +1,133 @@ + + + + + + + +libfranka: print_joint_poses.cpp + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + +
    + +
    +
    + + +
    + +
    + +
    +
    +
    print_joint_poses.cpp
    +
    +
    +

    An example showing how to use the model library that prints the transformation matrix of each joint with respect to the base frame.

    +
    // Copyright (c) 2023 Franka Robotics GmbH
    +
    // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    #include <iostream>
    +
    #include <iterator>
    +
    + +
    #include <franka/model.h>
    +
    +
    template <class T, size_t N>
    +
    std::ostream& operator<<(std::ostream& ostream, const std::array<T, N>& array) {
    +
    ostream << "[";
    +
    std::copy(array.cbegin(), array.cend() - 1, std::ostream_iterator<T>(ostream, ","));
    +
    std::copy(array.cend() - 1, array.cend(), std::ostream_iterator<T>(ostream));
    +
    ostream << "]";
    +
    return ostream;
    +
    }
    +
    +
    int main(int argc, char** argv) {
    +
    if (argc != 2) {
    +
    std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
    +
    return -1;
    +
    }
    +
    +
    try {
    +
    franka::Robot robot(argv[1]);
    +
    +
    franka::RobotState state = robot.readOnce();
    +
    +
    franka::Model model(robot.loadModel());
    +
    for (franka::Frame frame = franka::Frame::kJoint1; frame <= franka::Frame::kEndEffector;
    +
    frame++) {
    +
    std::cout << model.pose(frame, state) << std::endl;
    +
    }
    +
    } catch (franka::Exception const& e) {
    +
    std::cout << e.what() << std::endl;
    +
    return -1;
    +
    }
    +
    +
    return 0;
    +
    }
    +
    Calculates poses of joints and dynamic properties of the robot.
    Definition: model.h:52
    +
    Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
    Definition: robot.h:68
    +
    std::ostream & operator<<(std::ostream &ostream, const Errors &errors)
    Streams the errors as JSON array.
    +
    Contains exception definitions.
    +
    Contains model library types.
    +
    Frame
    Enumerates the seven joints, the flange, and the end effector of a robot.
    Definition: model.h:22
    +
    Base class for all exceptions used by libfranka.
    Definition: exception.h:20
    +
    Describes the robot state.
    Definition: robot_state.h:34
    +
    + + + + diff --git a/rate__limiting_8h.html b/rate__limiting_8h.html new file mode 100644 index 00000000..20f008f3 --- /dev/null +++ b/rate__limiting_8h.html @@ -0,0 +1,1095 @@ + + + + + + + +libfranka: include/franka/rate_limiting.h File Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    rate_limiting.h File Reference
    +
    +
    + +

    Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity. +More...

    +
    #include <algorithm>
    +#include <array>
    +#include <cmath>
    +#include <limits>
    +
    +Include dependency graph for rate_limiting.h:
    +
    +
    + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

    +Functions

    std::array< double, 7 > franka::computeUpperLimitsJointVelocity (const std::array< double, 7 > &q)
     Computes the maximum joint velocity based on joint position. More...
     
    std::array< double, 7 > franka::computeLowerLimitsJointVelocity (const std::array< double, 7 > &q)
     Computes the minimum joint velocity based on joint position. More...
     
    std::array< double, 7 > franka::limitRate (const std::array< double, 7 > &max_derivatives, const std::array< double, 7 > &commanded_values, const std::array< double, 7 > &last_commanded_values)
     Limits the rate of an input vector of per-joint commands considering the maximum allowed time derivatives. More...
     
    double franka::limitRate (double upper_limits_velocity, double lower_limits_velocity, double max_acceleration, double max_jerk, double commanded_velocity, double last_commanded_velocity, double last_commanded_acceleration)
     Limits the rate of a desired joint velocity considering the limits provided. More...
     
    double franka::limitRate (double upper_limits_velocity, double lower_limits_velocity, double max_acceleration, double max_jerk, double commanded_position, double last_commanded_position, double last_commanded_velocity, double last_commanded_acceleration)
     Limits the rate of a desired joint position considering the limits provided. More...
     
    std::array< double, 7 > franka::limitRate (const std::array< double, 7 > &upper_limits_velocity, const std::array< double, 7 > &lower_limits_velocity, const std::array< double, 7 > &max_acceleration, const std::array< double, 7 > &max_jerk, const std::array< double, 7 > &commanded_velocities, const std::array< double, 7 > &last_commanded_velocities, const std::array< double, 7 > &last_commanded_accelerations)
     Limits the rate of a desired joint velocity considering the limits provided. More...
     
    std::array< double, 7 > franka::limitRate (const std::array< double, 7 > &upper_limits_velocity, const std::array< double, 7 > &lower_limits_velocity, const std::array< double, 7 > &max_acceleration, const std::array< double, 7 > &max_jerk, const std::array< double, 7 > &commanded_positions, const std::array< double, 7 > &last_commanded_positions, const std::array< double, 7 > &last_commanded_velocities, const std::array< double, 7 > &last_commanded_accelerations)
     Limits the rate of a desired joint position considering the limits provided. More...
     
    std::array< double, 6 > franka::limitRate (double max_translational_velocity, double max_translational_acceleration, double max_translational_jerk, double max_rotational_velocity, double max_rotational_acceleration, double max_rotational_jerk, const std::array< double, 6 > &O_dP_EE_c, const std::array< double, 6 > &last_O_dP_EE_c, const std::array< double, 6 > &last_O_ddP_EE_c)
     Limits the rate of a desired Cartesian velocity considering the limits provided. More...
     
    std::array< double, 16 > franka::limitRate (double max_translational_velocity, double max_translational_acceleration, double max_translational_jerk, double max_rotational_velocity, double max_rotational_acceleration, double max_rotational_jerk, const std::array< double, 16 > &O_T_EE_c, const std::array< double, 16 > &last_O_T_EE_c, const std::array< double, 6 > &last_O_dP_EE_c, const std::array< double, 6 > &last_O_ddP_EE_c)
     Limits the rate of a desired Cartesian pose considering the limits provided. More...
     
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

    +Variables

    +constexpr double franka::kDeltaT = 1e-3
     Sample time constant.
     
    +constexpr double franka::kLimitEps = 1e-3
     Epsilon value for checking limits.
     
    +constexpr double franka::kNormEps = std::numeric_limits<double>::epsilon()
     Epsilon value for limiting Cartesian accelerations/jerks or not.
     
    constexpr double franka::kTolNumberPacketsLost = 0.0
     Number of packets lost considered for the definition of velocity limits. More...
     
    +constexpr double franka::kFactorCartesianRotationPoseInterface = 0.99
     Factor for the definition of rotational limits using the Cartesian Pose interface.
     
    constexpr std::array< double, 7 > franka::kMaxTorqueRate
     Maximum torque rate. More...
     
    constexpr std::array< double, 7 > franka::kMaxJointJerk
     Maximum joint jerk. More...
     
    constexpr std::array< double, 7 > franka::kMaxJointAcceleration
     Maximum joint acceleration. More...
     
    constexpr std::array< double, 7 > franka::kJointVelocityLimitsTolerance
     Tolerance value for joint velocity limits to deal with numerical errors and data losses. More...
     
    +constexpr double franka::kMaxTranslationalJerk = 4500.0 - kLimitEps
     Maximum translational jerk.
     
    +constexpr double franka::kMaxTranslationalAcceleration = 9.0000 - kLimitEps
     Maximum translational acceleration.
     
    constexpr double franka::kMaxTranslationalVelocity
     Maximum translational velocity. More...
     
    +constexpr double franka::kMaxRotationalJerk = 8500.0 - kLimitEps
     Maximum rotational jerk.
     
    +constexpr double franka::kMaxRotationalAcceleration = 17.0000 - kLimitEps
     Maximum rotational acceleration.
     
    constexpr double franka::kMaxRotationalVelocity
     Maximum rotational velocity. More...
     
    +constexpr double franka::kMaxElbowJerk = 5000 - kLimitEps
     Maximum elbow jerk.
     
    +constexpr double franka::kMaxElbowAcceleration = 10.0000 - kLimitEps
     Maximum elbow acceleration.
     
    constexpr double franka::kMaxElbowVelocity
     Maximum elbow velocity. More...
     
    +

    Detailed Description

    +

    Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity.

    +

    Function Documentation

    + +

    ◆ computeLowerLimitsJointVelocity()

    + +
    +
    + + + + + +
    + + + + + + + + +
    std::array<double, 7> franka::computeLowerLimitsJointVelocity (const std::array< double, 7 > & q)
    +
    +inline
    +
    + +

    Computes the minimum joint velocity based on joint position.

    +
    Note
    The implementation is based on https://frankaemika.github.io/docs/control_parameters.html#limits-for-franka-research-3.
    +
    Parameters
    + + +
    [in]qjoint position.
    +
    +
    +
    Returns
    Lower limits of joint velocity at the given joint position.
    + +
    +
    + +

    ◆ computeUpperLimitsJointVelocity()

    + +
    +
    + + + + + +
    + + + + + + + + +
    std::array<double, 7> franka::computeUpperLimitsJointVelocity (const std::array< double, 7 > & q)
    +
    +inline
    +
    + +

    Computes the maximum joint velocity based on joint position.

    +
    Note
    The implementation is based on https://frankaemika.github.io/docs/control_parameters.html#limits-for-franka-research-3.
    +
    Parameters
    + + +
    [in]qjoint position.
    +
    +
    +
    Returns
    Upper limits of joint velocity at the given joint position.
    + +
    +
    + +

    ◆ limitRate() [1/7]

    + +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + +
    std::array<double, 7> franka::limitRate (const std::array< double, 7 > & max_derivatives,
    const std::array< double, 7 > & commanded_values,
    const std::array< double, 7 > & last_commanded_values 
    )
    +
    + +

    Limits the rate of an input vector of per-joint commands considering the maximum allowed time derivatives.

    +
    Note
    FCI filters must be deactivated to work properly.
    +
    Parameters
    + + + + +
    [in]max_derivativesPer-joint maximum allowed time derivative.
    [in]commanded_valuesCommanded values of the current time step.
    [in]last_commanded_valuesCommanded values of the previous time step.
    +
    +
    +
    Exceptions
    + + +
    std::invalid_argumentif commanded_values are infinite or NaN.
    +
    +
    +
    Returns
    Rate-limited vector of desired values.
    +
    Examples
    joint_impedance_control.cpp.
    +
    + +
    +
    + +

    ◆ limitRate() [2/7]

    + +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    std::array<double, 7> franka::limitRate (const std::array< double, 7 > & upper_limits_velocity,
    const std::array< double, 7 > & lower_limits_velocity,
    const std::array< double, 7 > & max_acceleration,
    const std::array< double, 7 > & max_jerk,
    const std::array< double, 7 > & commanded_positions,
    const std::array< double, 7 > & last_commanded_positions,
    const std::array< double, 7 > & last_commanded_velocities,
    const std::array< double, 7 > & last_commanded_accelerations 
    )
    +
    + +

    Limits the rate of a desired joint position considering the limits provided.

    +
    Note
    FCI filters must be deactivated to work properly.
    +
    Parameters
    + + + + + + + + + +
    [in]upper_limits_velocityPer-joint upper limits of allowed velocity.
    [in]lower_limits_velocityPer-joint lower limits of allowed velocity.
    [in]max_accelerationPer-joint maximum allowed acceleration.
    [in]max_jerkPer-joint maximum allowed jerk.
    [in]commanded_positionsCommanded joint positions of the current time step.
    [in]last_commanded_positionsCommanded joint positions of the previous time step.
    [in]last_commanded_velocitiesCommanded joint velocities of the previous time step.
    [in]last_commanded_accelerationsCommanded joint accelerations of the previous time step.
    +
    +
    +
    Exceptions
    + + +
    std::invalid_argumentif commanded_positions are infinite or NaN.
    +
    +
    +
    Returns
    Rate-limited vector of desired joint positions.
    + +
    +
    + +

    ◆ limitRate() [3/7]

    + +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    std::array<double, 7> franka::limitRate (const std::array< double, 7 > & upper_limits_velocity,
    const std::array< double, 7 > & lower_limits_velocity,
    const std::array< double, 7 > & max_acceleration,
    const std::array< double, 7 > & max_jerk,
    const std::array< double, 7 > & commanded_velocities,
    const std::array< double, 7 > & last_commanded_velocities,
    const std::array< double, 7 > & last_commanded_accelerations 
    )
    +
    + +

    Limits the rate of a desired joint velocity considering the limits provided.

    +
    Note
    FCI filters must be deactivated to work properly.
    +
    Parameters
    + + + + + + + + +
    [in]upper_limits_velocityPer-joint upper limits of allowed velocity.
    [in]lower_limits_velocityPer-joint lower limits of allowed velocity.
    [in]max_accelerationPer-joint maximum allowed acceleration.
    [in]max_jerkPer-joint maximum allowed jerk.
    [in]commanded_velocitiesCommanded joint velocity of the current time step.
    [in]last_commanded_velocitiesCommanded joint velocities of the previous time step.
    [in]last_commanded_accelerationsCommanded joint accelerations of the previous time step.
    +
    +
    +
    Exceptions
    + + +
    std::invalid_argumentif commanded_velocities are infinite or NaN.
    +
    +
    +
    Returns
    Rate-limited vector of desired joint velocities.
    + +
    +
    + +

    ◆ limitRate() [4/7]

    + +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    std::array<double, 16> franka::limitRate (double max_translational_velocity,
    double max_translational_acceleration,
    double max_translational_jerk,
    double max_rotational_velocity,
    double max_rotational_acceleration,
    double max_rotational_jerk,
    const std::array< double, 16 > & O_T_EE_c,
    const std::array< double, 16 > & last_O_T_EE_c,
    const std::array< double, 6 > & last_O_dP_EE_c,
    const std::array< double, 6 > & last_O_ddP_EE_c 
    )
    +
    + +

    Limits the rate of a desired Cartesian pose considering the limits provided.

    +
    Note
    FCI filters must be deactivated to work properly.
    +
    Parameters
    + + + + + + + + + + + +
    [in]max_translational_velocityMaximum translational velocity.
    [in]max_translational_accelerationMaximum translational acceleration.
    [in]max_translational_jerkMaximum translational jerk.
    [in]max_rotational_velocityMaximum rotational velocity.
    [in]max_rotational_accelerationMaximum rotational acceleration.
    [in]max_rotational_jerkMaximum rotational jerk.
    [in]O_T_EE_cCommanded pose of the current time step.
    [in]last_O_T_EE_cCommanded pose of the previous time step.
    [in]last_O_dP_EE_cCommanded end effector twist of the previous time step.
    [in]last_O_ddP_EE_cCommanded end effector acceleration of the previous time step.
    +
    +
    +
    Exceptions
    + + +
    std::invalid_argumentif an element of O_T_EE_c is infinite or NaN.
    +
    +
    +
    Returns
    Rate-limited desired pose.
    + +
    +
    + +

    ◆ limitRate() [5/7]

    + +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    std::array<double, 6> franka::limitRate (double max_translational_velocity,
    double max_translational_acceleration,
    double max_translational_jerk,
    double max_rotational_velocity,
    double max_rotational_acceleration,
    double max_rotational_jerk,
    const std::array< double, 6 > & O_dP_EE_c,
    const std::array< double, 6 > & last_O_dP_EE_c,
    const std::array< double, 6 > & last_O_ddP_EE_c 
    )
    +
    + +

    Limits the rate of a desired Cartesian velocity considering the limits provided.

    +
    Note
    FCI filters must be deactivated to work properly.
    +
    Parameters
    + + + + + + + + + + +
    [in]max_translational_velocityMaximum translational velocity.
    [in]max_translational_accelerationMaximum translational acceleration.
    [in]max_translational_jerkMaximum translational jerk.
    [in]max_rotational_velocityMaximum rotational velocity.
    [in]max_rotational_accelerationMaximum rotational acceleration.
    [in]max_rotational_jerkMaximum rotational jerk.
    [in]O_dP_EE_cCommanded end effector twist of the current time step.
    [in]last_O_dP_EE_cCommanded end effector twist of the previous time step.
    [in]last_O_ddP_EE_cCommanded end effector acceleration of the previous time step.
    +
    +
    +
    Exceptions
    + + +
    std::invalid_argumentif an element of O_dP_EE_c is infinite or NaN.
    +
    +
    +
    Returns
    Rate-limited desired end effector twist.
    + +
    +
    + +

    ◆ limitRate() [6/7]

    + +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    double franka::limitRate (double upper_limits_velocity,
    double lower_limits_velocity,
    double max_acceleration,
    double max_jerk,
    double commanded_position,
    double last_commanded_position,
    double last_commanded_velocity,
    double last_commanded_acceleration 
    )
    +
    + +

    Limits the rate of a desired joint position considering the limits provided.

    +
    Note
    FCI filters must be deactivated to work properly.
    +
    Parameters
    + + + + + + + + + +
    [in]upper_limits_velocityUpper limits of allowed velocity.
    [in]lower_limits_velocityLower limits of allowed velocity.
    [in]max_accelerationMaximum allowed acceleration.
    [in]max_jerkMaximum allowed jerk.
    [in]commanded_positionCommanded joint position of the current time step.
    [in]last_commanded_positionCommanded joint position of the previous time step.
    [in]last_commanded_velocityCommanded joint velocity of the previous time step.
    [in]last_commanded_accelerationCommanded joint acceleration of the previous time step.
    +
    +
    +
    Exceptions
    + + +
    std::invalid_argumentif commanded_position is infinite or NaN.
    +
    +
    +
    Returns
    Rate-limited desired joint position.
    + +
    +
    + +

    ◆ limitRate() [7/7]

    + +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    double franka::limitRate (double upper_limits_velocity,
    double lower_limits_velocity,
    double max_acceleration,
    double max_jerk,
    double commanded_velocity,
    double last_commanded_velocity,
    double last_commanded_acceleration 
    )
    +
    + +

    Limits the rate of a desired joint velocity considering the limits provided.

    +
    Note
    FCI filters must be deactivated to work properly.
    +
    Parameters
    + + + + + + + + +
    [in]upper_limits_velocityUpper limits of allowed velocity.
    [in]lower_limits_velocityLower limits of allowed velocity.
    [in]max_accelerationMaximum allowed acceleration.
    [in]max_jerkMaximum allowed jerk.
    [in]commanded_velocityCommanded joint velocity of the current time step.
    [in]last_commanded_velocityCommanded joint velocity of the previous time step.
    [in]last_commanded_accelerationCommanded joint acceleration of the previous time step.
    +
    +
    +
    Exceptions
    + + +
    std::invalid_argumentif commanded_velocity is infinite or NaN.
    +
    +
    +
    Returns
    Rate-limited desired joint velocity.
    + +
    +
    +

    Variable Documentation

    + +

    ◆ kJointVelocityLimitsTolerance

    + +
    +
    + + + + + +
    + + + + +
    constexpr std::array<double, 7> franka::kJointVelocityLimitsTolerance
    +
    +constexpr
    +
    +Initial value:
    {
    + + + + + + + +
    }
    +
    constexpr double kDeltaT
    Sample time constant.
    Definition: rate_limiting.h:20
    +
    constexpr double kTolNumberPacketsLost
    Number of packets lost considered for the definition of velocity limits.
    Definition: rate_limiting.h:35
    +
    constexpr std::array< double, 7 > kMaxJointAcceleration
    Maximum joint acceleration.
    Definition: rate_limiting.h:55
    +
    constexpr double kLimitEps
    Epsilon value for checking limits.
    Definition: rate_limiting.h:24
    +
    +

    Tolerance value for joint velocity limits to deal with numerical errors and data losses.

    + +
    +
    + +

    ◆ kMaxElbowVelocity

    + +
    +
    + + + + + +
    + + + + +
    constexpr double franka::kMaxElbowVelocity
    +
    +constexpr
    +
    +Initial value:
    =
    + +
    constexpr double kMaxElbowAcceleration
    Maximum elbow acceleration.
    Definition: rate_limiting.h:103
    +
    +

    Maximum elbow velocity.

    + +
    +
    + +

    ◆ kMaxJointAcceleration

    + +
    +
    + + + + + +
    + + + + +
    constexpr std::array<double, 7> franka::kMaxJointAcceleration
    +
    +constexpr
    +
    +Initial value:
    {
    +
    {10.0000 - kLimitEps, 10.0000 - kLimitEps, 10.0000 - kLimitEps, 10.0000 - kLimitEps,
    +
    10.0000 - kLimitEps, 10.0000 - kLimitEps, 10.0000 - kLimitEps}}
    +
    +

    Maximum joint acceleration.

    + +
    +
    + +

    ◆ kMaxJointJerk

    + +
    +
    + + + + + +
    + + + + +
    constexpr std::array<double, 7> franka::kMaxJointJerk
    +
    +constexpr
    +
    +Initial value:
    {
    +
    {5000.0 - kLimitEps, 5000.0 - kLimitEps, 5000.0 - kLimitEps, 5000.0 - kLimitEps,
    +
    5000.0 - kLimitEps, 5000.0 - kLimitEps, 5000.0 - kLimitEps}}
    +
    +

    Maximum joint jerk.

    + +
    +
    + +

    ◆ kMaxRotationalVelocity

    + +
    +
    + + + + + +
    + + + + +
    constexpr double franka::kMaxRotationalVelocity
    +
    +constexpr
    +
    +Initial value:
    =
    + +
    constexpr double kMaxRotationalAcceleration
    Maximum rotational acceleration.
    Definition: rate_limiting.h:90
    +
    +

    Maximum rotational velocity.

    + +
    +
    + +

    ◆ kMaxTorqueRate

    + +
    +
    + + + + + +
    + + + + +
    constexpr std::array<double, 7> franka::kMaxTorqueRate
    +
    +constexpr
    +
    +Initial value:
    {
    +
    {1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps,
    +
    1000 - kLimitEps, 1000 - kLimitEps}}
    +
    +

    Maximum torque rate.

    +
    Examples
    joint_impedance_control.cpp.
    +
    + +
    +
    + +

    ◆ kMaxTranslationalVelocity

    + +
    +
    + + + + + +
    + + + + +
    constexpr double franka::kMaxTranslationalVelocity
    +
    +constexpr
    +
    +Initial value:
    =
    + +
    constexpr double kMaxTranslationalAcceleration
    Maximum translational acceleration.
    Definition: rate_limiting.h:77
    +
    +

    Maximum translational velocity.

    + +
    +
    + +

    ◆ kTolNumberPacketsLost

    + +
    +
    + + + + + +
    + + + + +
    constexpr double franka::kTolNumberPacketsLost = 0.0
    +
    +constexpr
    +
    + +

    Number of packets lost considered for the definition of velocity limits.

    +

    When a packet is lost, FCI assumes a constant acceleration model. For FR3 there are no expected package loses. Therefore this number is set to 0. If you encounter package loses with your setup you can increase this number

    + +
    +
    +
    + + + + diff --git a/rate__limiting_8h__incl.map b/rate__limiting_8h__incl.map new file mode 100644 index 00000000..5d754c94 --- /dev/null +++ b/rate__limiting_8h__incl.map @@ -0,0 +1,7 @@ + + + + + + + diff --git a/rate__limiting_8h__incl.md5 b/rate__limiting_8h__incl.md5 new file mode 100644 index 00000000..d8bb1bc3 --- /dev/null +++ b/rate__limiting_8h__incl.md5 @@ -0,0 +1 @@ +57c627e80ba2707574cf3a9c16db283a \ No newline at end of file diff --git a/rate__limiting_8h__incl.png b/rate__limiting_8h__incl.png new file mode 100644 index 00000000..3737d46e Binary files /dev/null and b/rate__limiting_8h__incl.png differ diff --git a/rate__limiting_8h_source.html b/rate__limiting_8h_source.html new file mode 100644 index 00000000..7ab4d341 --- /dev/null +++ b/rate__limiting_8h_source.html @@ -0,0 +1,255 @@ + + + + + + + +libfranka: include/franka/rate_limiting.h Source File + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    rate_limiting.h
    +
    +
    +Go to the documentation of this file.
    1 // Copyright (c) 2023 Franka Robotics GmbH
    +
    2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    3 #pragma once
    +
    4 
    +
    5 #include <algorithm>
    +
    6 #include <array>
    +
    7 #include <cmath>
    +
    8 #include <limits>
    +
    9 
    +
    16 namespace franka {
    +
    20 constexpr double kDeltaT = 1e-3;
    +
    24 constexpr double kLimitEps = 1e-3;
    +
    28 constexpr double kNormEps = std::numeric_limits<double>::epsilon();
    +
    35 constexpr double kTolNumberPacketsLost = 0.0;
    +
    39 constexpr double kFactorCartesianRotationPoseInterface = 0.99;
    +
    43 constexpr std::array<double, 7> kMaxTorqueRate{
    +
    44  {1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps,
    +
    45  1000 - kLimitEps, 1000 - kLimitEps}};
    +
    49 constexpr std::array<double, 7> kMaxJointJerk{
    +
    50  {5000.0 - kLimitEps, 5000.0 - kLimitEps, 5000.0 - kLimitEps, 5000.0 - kLimitEps,
    +
    51  5000.0 - kLimitEps, 5000.0 - kLimitEps, 5000.0 - kLimitEps}};
    +
    55 constexpr std::array<double, 7> kMaxJointAcceleration{
    +
    56  {10.0000 - kLimitEps, 10.0000 - kLimitEps, 10.0000 - kLimitEps, 10.0000 - kLimitEps,
    +
    57  10.0000 - kLimitEps, 10.0000 - kLimitEps, 10.0000 - kLimitEps}};
    +
    61 constexpr std::array<double, 7> kJointVelocityLimitsTolerance{
    + + + + + + + +
    69 };
    +
    73 constexpr double kMaxTranslationalJerk = 4500.0 - kLimitEps;
    +
    77 constexpr double kMaxTranslationalAcceleration = 9.0000 - kLimitEps;
    +
    81 constexpr double kMaxTranslationalVelocity =
    + +
    86 constexpr double kMaxRotationalJerk = 8500.0 - kLimitEps;
    +
    90 constexpr double kMaxRotationalAcceleration = 17.0000 - kLimitEps;
    +
    94 constexpr double kMaxRotationalVelocity =
    + +
    99 constexpr double kMaxElbowJerk = 5000 - kLimitEps;
    +
    103 constexpr double kMaxElbowAcceleration = 10.0000 - kLimitEps;
    +
    107 constexpr double kMaxElbowVelocity =
    + +
    109 
    +
    120 inline std::array<double, 7> computeUpperLimitsJointVelocity(const std::array<double, 7>& q) {
    +
    121  return std::array<double, 7>{
    +
    122  std::min(2.62, std::max(0.0, -0.30 + std::sqrt(std::max(0.0, 12.0 * (2.75010 - q[0]))))) -
    + +
    124  std::min(2.62, std::max(0.0, -0.20 + std::sqrt(std::max(0.0, 5.17 * (1.79180 - q[1]))))) -
    + +
    126  std::min(2.62, std::max(0.0, -0.20 + std::sqrt(std::max(0.0, 7.00 * (2.90650 - q[2]))))) -
    + +
    128  std::min(2.62, std::max(0.0, -0.30 + std::sqrt(std::max(0.0, 8.00 * (-0.1458 - q[3]))))) -
    + +
    130  std::min(5.26, std::max(0.0, -0.35 + std::sqrt(std::max(0.0, 34.0 * (2.81010 - q[4]))))) -
    + +
    132  std::min(4.18, std::max(0.0, -0.35 + std::sqrt(std::max(0.0, 11.0 * (4.52050 - q[5]))))) -
    + +
    134  std::min(5.26, std::max(0.0, -0.35 + std::sqrt(std::max(0.0, 34.0 * (3.01960 - q[6]))))) -
    + +
    136  };
    +
    137 }
    +
    138 
    +
    149 inline std::array<double, 7> computeLowerLimitsJointVelocity(const std::array<double, 7>& q) {
    +
    150  return std::array<double, 7>{
    +
    151  std::max(-2.62, std::min(0.0, 0.30 - std::sqrt(std::max(0.0, 12.0 * (2.750100 + q[0]))))) +
    + +
    153  std::max(-2.62, std::min(0.0, 0.20 - std::sqrt(std::max(0.0, 5.17 * (1.791800 + q[1]))))) +
    + +
    155  std::max(-2.62, std::min(0.0, 0.20 - std::sqrt(std::max(0.0, 7.00 * (2.906500 + q[2]))))) +
    + +
    157  std::max(-2.62, std::min(0.0, 0.30 - std::sqrt(std::max(0.0, 8.00 * (3.048100 + q[3]))))) +
    + +
    159  std::max(-5.26, std::min(0.0, 0.35 - std::sqrt(std::max(0.0, 34.0 * (2.810100 + q[4]))))) +
    + +
    161  std::max(-4.18, std::min(0.0, 0.35 - std::sqrt(std::max(0.0, 11.0 * (-0.54092 + q[5]))))) +
    + +
    163  std::max(-5.26, std::min(0.0, 0.35 - std::sqrt(std::max(0.0, 34.0 * (3.019600 + q[6]))))) +
    + +
    165  };
    +
    166 }
    +
    167 
    +
    183 std::array<double, 7> limitRate(const std::array<double, 7>& max_derivatives,
    +
    184  const std::array<double, 7>& commanded_values,
    +
    185  const std::array<double, 7>& last_commanded_values);
    +
    186 
    +
    205 double limitRate(double upper_limits_velocity,
    +
    206  double lower_limits_velocity,
    +
    207  double max_acceleration,
    +
    208  double max_jerk,
    +
    209  double commanded_velocity,
    +
    210  double last_commanded_velocity,
    +
    211  double last_commanded_acceleration);
    +
    212 
    +
    232 double limitRate(double upper_limits_velocity,
    +
    233  double lower_limits_velocity,
    +
    234  double max_acceleration,
    +
    235  double max_jerk,
    +
    236  double commanded_position,
    +
    237  double last_commanded_position,
    +
    238  double last_commanded_velocity,
    +
    239  double last_commanded_acceleration);
    +
    240 
    +
    259 std::array<double, 7> limitRate(const std::array<double, 7>& upper_limits_velocity,
    +
    260  const std::array<double, 7>& lower_limits_velocity,
    +
    261  const std::array<double, 7>& max_acceleration,
    +
    262  const std::array<double, 7>& max_jerk,
    +
    263  const std::array<double, 7>& commanded_velocities,
    +
    264  const std::array<double, 7>& last_commanded_velocities,
    +
    265  const std::array<double, 7>& last_commanded_accelerations);
    +
    266 
    +
    286 std::array<double, 7> limitRate(const std::array<double, 7>& upper_limits_velocity,
    +
    287  const std::array<double, 7>& lower_limits_velocity,
    +
    288  const std::array<double, 7>& max_acceleration,
    +
    289  const std::array<double, 7>& max_jerk,
    +
    290  const std::array<double, 7>& commanded_positions,
    +
    291  const std::array<double, 7>& last_commanded_positions,
    +
    292  const std::array<double, 7>& last_commanded_velocities,
    +
    293  const std::array<double, 7>& last_commanded_accelerations);
    +
    294 
    +
    315 std::array<double, 6> limitRate(
    +
    316  double max_translational_velocity,
    +
    317  double max_translational_acceleration,
    +
    318  double max_translational_jerk,
    +
    319  double max_rotational_velocity,
    +
    320  double max_rotational_acceleration,
    +
    321  double max_rotational_jerk,
    +
    322  const std::array<double, 6>& O_dP_EE_c, // NOLINT(readability-identifier-naming)
    +
    323  const std::array<double, 6>& last_O_dP_EE_c, // NOLINT(readability-identifier-naming)
    +
    324  const std::array<double, 6>& last_O_ddP_EE_c); // NOLINT(readability-identifier-naming)
    +
    325 
    +
    347 std::array<double, 16> limitRate(
    +
    348  double max_translational_velocity,
    +
    349  double max_translational_acceleration,
    +
    350  double max_translational_jerk,
    +
    351  double max_rotational_velocity,
    +
    352  double max_rotational_acceleration,
    +
    353  double max_rotational_jerk,
    +
    354  const std::array<double, 16>& O_T_EE_c, // NOLINT(readability-identifier-naming)
    +
    355  const std::array<double, 16>& last_O_T_EE_c, // NOLINT(readability-identifier-naming)
    +
    356  const std::array<double, 6>& last_O_dP_EE_c, // NOLINT(readability-identifier-naming)
    +
    357  const std::array<double, 6>& last_O_ddP_EE_c); // NOLINT(readability-identifier-naming)
    +
    358 
    +
    359 } // namespace franka
    +
    constexpr double kFactorCartesianRotationPoseInterface
    Factor for the definition of rotational limits using the Cartesian Pose interface.
    Definition: rate_limiting.h:39
    +
    constexpr double kDeltaT
    Sample time constant.
    Definition: rate_limiting.h:20
    +
    constexpr double kMaxRotationalJerk
    Maximum rotational jerk.
    Definition: rate_limiting.h:86
    +
    constexpr double kMaxElbowVelocity
    Maximum elbow velocity.
    Definition: rate_limiting.h:107
    +
    constexpr double kMaxTranslationalAcceleration
    Maximum translational acceleration.
    Definition: rate_limiting.h:77
    +
    constexpr std::array< double, 7 > kJointVelocityLimitsTolerance
    Tolerance value for joint velocity limits to deal with numerical errors and data losses.
    Definition: rate_limiting.h:61
    +
    std::array< double, 7 > computeUpperLimitsJointVelocity(const std::array< double, 7 > &q)
    Computes the maximum joint velocity based on joint position.
    Definition: rate_limiting.h:120
    +
    constexpr double kNormEps
    Epsilon value for limiting Cartesian accelerations/jerks or not.
    Definition: rate_limiting.h:28
    +
    constexpr double kMaxTranslationalJerk
    Maximum translational jerk.
    Definition: rate_limiting.h:73
    +
    constexpr double kMaxRotationalAcceleration
    Maximum rotational acceleration.
    Definition: rate_limiting.h:90
    +
    constexpr std::array< double, 7 > kMaxJointJerk
    Maximum joint jerk.
    Definition: rate_limiting.h:49
    +
    constexpr double kTolNumberPacketsLost
    Number of packets lost considered for the definition of velocity limits.
    Definition: rate_limiting.h:35
    +
    constexpr std::array< double, 7 > kMaxTorqueRate
    Maximum torque rate.
    Definition: rate_limiting.h:43
    +
    std::array< double, 7 > computeLowerLimitsJointVelocity(const std::array< double, 7 > &q)
    Computes the minimum joint velocity based on joint position.
    Definition: rate_limiting.h:149
    +
    constexpr std::array< double, 7 > kMaxJointAcceleration
    Maximum joint acceleration.
    Definition: rate_limiting.h:55
    +
    constexpr double kMaxTranslationalVelocity
    Maximum translational velocity.
    Definition: rate_limiting.h:81
    +
    constexpr double kLimitEps
    Epsilon value for checking limits.
    Definition: rate_limiting.h:24
    +
    constexpr double kMaxRotationalVelocity
    Maximum rotational velocity.
    Definition: rate_limiting.h:94
    +
    constexpr double kMaxElbowJerk
    Maximum elbow jerk.
    Definition: rate_limiting.h:99
    +
    std::array< double, 7 > limitRate(const std::array< double, 7 > &max_derivatives, const std::array< double, 7 > &commanded_values, const std::array< double, 7 > &last_commanded_values)
    Limits the rate of an input vector of per-joint commands considering the maximum allowed time derivat...
    +
    constexpr double kMaxElbowAcceleration
    Maximum elbow acceleration.
    Definition: rate_limiting.h:103
    +
    + + + + diff --git a/robot_8h.html b/robot_8h.html new file mode 100644 index 00000000..d0d44bb5 --- /dev/null +++ b/robot_8h.html @@ -0,0 +1,155 @@ + + + + + + + +libfranka: include/franka/robot.h File Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    robot.h File Reference
    +
    +
    + +

    Contains the franka::Robot type. +More...

    +
    #include <functional>
    +#include <memory>
    +#include <mutex>
    +#include <string>
    +#include <franka/control_types.h>
    +#include <franka/duration.h>
    +#include <franka/lowpass_filter.h>
    +#include <franka/robot_model_base.h>
    +#include <franka/robot_state.h>
    +#include <research_interface/robot/service_types.h>
    +#include <franka/commands/get_robot_model_command.hpp>
    +
    +Include dependency graph for robot.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  franka::Robot
     Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot. More...
     
    +

    Detailed Description

    +

    Contains the franka::Robot type.

    +
    + + + + diff --git a/robot_8h__dep__incl.map b/robot_8h__dep__incl.map new file mode 100644 index 00000000..c0c7a777 --- /dev/null +++ b/robot_8h__dep__incl.map @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/robot_8h__dep__incl.md5 b/robot_8h__dep__incl.md5 new file mode 100644 index 00000000..edf1ab76 --- /dev/null +++ b/robot_8h__dep__incl.md5 @@ -0,0 +1 @@ +593b8bcdeee6aad6acb905fdb2260cdb \ No newline at end of file diff --git a/robot_8h__dep__incl.png b/robot_8h__dep__incl.png new file mode 100644 index 00000000..decc00c1 Binary files /dev/null and b/robot_8h__dep__incl.png differ diff --git a/robot_8h__incl.map b/robot_8h__incl.map new file mode 100644 index 00000000..48f1474d --- /dev/null +++ b/robot_8h__incl.map @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/robot_8h__incl.md5 b/robot_8h__incl.md5 new file mode 100644 index 00000000..6c2962c0 --- /dev/null +++ b/robot_8h__incl.md5 @@ -0,0 +1 @@ +a6644437af3a66f09ecd13125262b89a \ No newline at end of file diff --git a/robot_8h__incl.png b/robot_8h__incl.png new file mode 100644 index 00000000..ac389ba5 Binary files /dev/null and b/robot_8h__incl.png differ diff --git a/robot_8h_source.html b/robot_8h_source.html new file mode 100644 index 00000000..09f4605d --- /dev/null +++ b/robot_8h_source.html @@ -0,0 +1,300 @@ + + + + + + + +libfranka: include/franka/robot.h Source File + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    robot.h
    +
    +
    +Go to the documentation of this file.
    1 // Copyright (c) 2023 Franka Robotics 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/control_types.h>
    +
    11 #include <franka/duration.h>
    +
    12 #include <franka/lowpass_filter.h>
    +
    13 #include <franka/robot_model_base.h>
    +
    14 #include <franka/robot_state.h>
    +
    15 #include <research_interface/robot/service_types.h>
    +
    16 #include <franka/commands/get_robot_model_command.hpp>
    +
    17 
    +
    22 namespace franka {
    +
    23 
    +
    24 class Model;
    +
    25 
    +
    26 class ActiveControlBase;
    +
    27 
    +
    68 class Robot {
    +
    69  public:
    +
    73  using ServerVersion = uint16_t;
    +
    74 
    +
    87  explicit Robot(const std::string& franka_address,
    +
    88  RealtimeConfig realtime_config = RealtimeConfig::kEnforce,
    +
    89  size_t log_size = 50);
    +
    90 
    +
    96  Robot(Robot&& other) noexcept;
    +
    97 
    +
    105  Robot& operator=(Robot&& other) noexcept;
    +
    106 
    +
    110  virtual ~Robot() noexcept;
    +
    111 
    +
    175  void control(std::function<Torques(const RobotState&, franka::Duration)> control_callback,
    +
    176  bool limit_rate = false,
    +
    177  double cutoff_frequency = kDefaultCutoffFrequency);
    +
    178 
    +
    203  void control(
    +
    204  std::function<Torques(const RobotState&, franka::Duration)> control_callback,
    +
    205  std::function<JointPositions(const RobotState&, franka::Duration)> motion_generator_callback,
    +
    206  bool limit_rate = false,
    +
    207  double cutoff_frequency = kDefaultCutoffFrequency);
    +
    208 
    +
    233  void control(
    +
    234  std::function<Torques(const RobotState&, franka::Duration)> control_callback,
    +
    235  std::function<JointVelocities(const RobotState&, franka::Duration)> motion_generator_callback,
    +
    236  bool limit_rate = false,
    +
    237  double cutoff_frequency = kDefaultCutoffFrequency);
    +
    238 
    +
    263  void control(
    +
    264  std::function<Torques(const RobotState&, franka::Duration)> control_callback,
    +
    265  std::function<CartesianPose(const RobotState&, franka::Duration)> motion_generator_callback,
    +
    266  bool limit_rate = false,
    +
    267  double cutoff_frequency = kDefaultCutoffFrequency);
    +
    268 
    +
    293  void control(std::function<Torques(const RobotState&, franka::Duration)> control_callback,
    +
    294  std::function<CartesianVelocities(const RobotState&, franka::Duration)>
    +
    295  motion_generator_callback,
    +
    296  bool limit_rate = false,
    +
    297  double cutoff_frequency = kDefaultCutoffFrequency);
    +
    298 
    +
    321  void control(
    +
    322  std::function<JointPositions(const RobotState&, franka::Duration)> motion_generator_callback,
    +
    323  ControllerMode controller_mode = ControllerMode::kJointImpedance,
    +
    324  bool limit_rate = false,
    +
    325  double cutoff_frequency = kDefaultCutoffFrequency);
    +
    326 
    +
    349  void control(
    +
    350  std::function<JointVelocities(const RobotState&, franka::Duration)> motion_generator_callback,
    +
    351  ControllerMode controller_mode = ControllerMode::kJointImpedance,
    +
    352  bool limit_rate = false,
    +
    353  double cutoff_frequency = kDefaultCutoffFrequency);
    +
    354 
    +
    377  void control(
    +
    378  std::function<CartesianPose(const RobotState&, franka::Duration)> motion_generator_callback,
    +
    379  ControllerMode controller_mode = ControllerMode::kJointImpedance,
    +
    380  bool limit_rate = false,
    +
    381  double cutoff_frequency = kDefaultCutoffFrequency);
    +
    382 
    +
    405  void control(std::function<CartesianVelocities(const RobotState&, franka::Duration)>
    +
    406  motion_generator_callback,
    +
    407  ControllerMode controller_mode = ControllerMode::kJointImpedance,
    +
    408  bool limit_rate = false,
    +
    409  double cutoff_frequency = kDefaultCutoffFrequency);
    +
    410 
    +
    435  void read(std::function<bool(const RobotState&)> read_callback);
    +
    436 
    +
    449  virtual RobotState readOnce();
    +
    450 
    +
    465  auto getRobotModel() -> std::string;
    +
    466 
    +
    503  void setCollisionBehavior(const std::array<double, 7>& lower_torque_thresholds_acceleration,
    +
    504  const std::array<double, 7>& upper_torque_thresholds_acceleration,
    +
    505  const std::array<double, 7>& lower_torque_thresholds_nominal,
    +
    506  const std::array<double, 7>& upper_torque_thresholds_nominal,
    +
    507  const std::array<double, 6>& lower_force_thresholds_acceleration,
    +
    508  const std::array<double, 6>& upper_force_thresholds_acceleration,
    +
    509  const std::array<double, 6>& lower_force_thresholds_nominal,
    +
    510  const std::array<double, 6>& upper_force_thresholds_nominal);
    +
    511 
    +
    538  void setCollisionBehavior(const std::array<double, 7>& lower_torque_thresholds,
    +
    539  const std::array<double, 7>& upper_torque_thresholds,
    +
    540  const std::array<double, 6>& lower_force_thresholds,
    +
    541  const std::array<double, 6>& upper_force_thresholds);
    +
    542 
    + +
    555  const std::array<double, 7>& K_theta); // NOLINT(readability-identifier-naming)
    +
    556 
    + +
    572  const std::array<double, 6>& K_x); // NOLINT(readability-identifier-naming)
    +
    573 
    +
    588  void setGuidingMode(const std::array<bool, 6>& guiding_mode, bool elbow);
    +
    589 
    +
    602  void setK(const std::array<double, 16>& EE_T_K); // NOLINT(readability-identifier-naming)
    +
    603 
    +
    619  void setEE(const std::array<double, 16>& NE_T_EE); // NOLINT(readability-identifier-naming)
    +
    620 
    +
    637  void setLoad(double load_mass,
    +
    638  const std::array<double, 3>& F_x_Cload, // NOLINT(readability-identifier-naming)
    +
    639  const std::array<double, 9>& load_inertia);
    +
    640 
    + +
    650 
    +
    662  virtual std::unique_ptr<ActiveControlBase> startTorqueControl();
    +
    663 
    + +
    678  const research_interface::robot::Move::ControllerMode& control_type);
    +
    679 
    + +
    693  const research_interface::robot::Move::ControllerMode& control_type);
    +
    694 
    + +
    708  const research_interface::robot::Move::ControllerMode& control_type);
    +
    709 
    + +
    724  const research_interface::robot::Move::ControllerMode& control_type);
    +
    725 
    +
    735  void stop();
    +
    736 
    + +
    750 
    +
    751  // Loads the model library for the unittests mockRobotModel
    +
    752  Model loadModel(std::unique_ptr<RobotModelBase> robot_model);
    +
    753 
    +
    759  ServerVersion serverVersion() const noexcept;
    +
    760 
    +
    762  Robot(const Robot&) = delete;
    +
    763  Robot& operator=(const Robot&) = delete;
    +
    765 
    +
    766  class Impl;
    +
    767 
    +
    768  protected:
    +
    774  Robot(std::shared_ptr<Impl> robot_impl);
    +
    775 
    +
    779  Robot() = default;
    +
    780 
    +
    781  private:
    +
    796  template <typename T>
    +
    797  std::unique_ptr<ActiveControlBase> startControl(
    +
    798  const research_interface::robot::Move::ControllerMode& controller_type);
    +
    799 
    +
    800  std::shared_ptr<Impl> impl_;
    +
    801  std::mutex control_mutex_;
    +
    802 };
    +
    803 
    +
    804 } // namespace franka
    +
    Robot dynamic parameters computed from the URDF model with Pinocchio.
    Definition: robot_model_base.h:10
    +
    Allows the user to read the state of a Robot and to send new control commands after starting a contro...
    Definition: active_control_base.h:27
    +
    Stores values for Cartesian pose motion generation.
    Definition: control_types.h:127
    +
    Stores values for Cartesian velocity motion generation.
    Definition: control_types.h:211
    +
    Represents a duration with millisecond resolution.
    Definition: duration.h:19
    +
    Stores values for joint position motion generation.
    Definition: control_types.h:72
    +
    Stores values for joint velocity motion generation.
    Definition: control_types.h:99
    +
    Calculates poses of joints and dynamic properties of the robot.
    Definition: model.h:52
    +
    Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
    Definition: robot.h:68
    +
    void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
    Starts a control loop for sending joint-level torque commands.
    +
    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.
    +
    Model loadModel()
    Loads the model library from the robot.
    +
    Robot & operator=(Robot &&other) noexcept
    Move-assigns this Robot from another Robot instance.
    +
    Robot(Robot &&other) noexcept
    Move-constructs a new Robot instance.
    +
    virtual std::unique_ptr< ActiveControlBase > startCartesianPoseControl(const research_interface::robot::Move::ControllerMode &control_type)
    Starts a new cartesian position motion generator.
    +
    ServerVersion serverVersion() const noexcept
    Returns the software version reported by the connected server.
    +
    auto getRobotModel() -> std::string
    +
    void stop()
    Stops all currently running motions.
    +
    void setGuidingMode(const std::array< bool, 6 > &guiding_mode, bool elbow)
    Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw).
    +
    virtual std::unique_ptr< ActiveControlBase > startTorqueControl()
    Starts a new torque controller.
    +
    void read(std::function< bool(const RobotState &)> read_callback)
    Starts a loop for reading the current robot state.
    +
    virtual std::unique_ptr< ActiveControlBase > startCartesianVelocityControl(const research_interface::robot::Move::ControllerMode &control_type)
    Starts a new cartesian velocity motion generator.
    +
    void setJointImpedance(const std::array< double, 7 > &K_theta)
    Sets the impedance for each joint in the internal controller.
    +
    virtual ~Robot() noexcept
    Closes the connection.
    +
    void setCartesianImpedance(const std::array< double, 6 > &K_x)
    Sets the Cartesian stiffness/compliance (for x, y, z, roll, pitch, yaw) in the internal controller.
    +
    virtual std::unique_ptr< ActiveControlBase > startJointPositionControl(const research_interface::robot::Move::ControllerMode &control_type)
    Starts a new joint position motion generator.
    +
    void setK(const std::array< double, 16 > &EE_T_K)
    Sets the transformation from end effector frame to stiffness frame.
    +
    uint16_t ServerVersion
    Version of the robot server.
    Definition: robot.h:73
    +
    virtual RobotState readOnce()
    Waits for a robot state update and returns it.
    +
    Robot(const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50)
    Establishes a connection with the robot.
    +
    virtual std::unique_ptr< ActiveControlBase > startJointVelocityControl(const research_interface::robot::Move::ControllerMode &control_type)
    Starts a new joint velocity motion generator.
    +
    void setEE(const std::array< double, 16 > &NE_T_EE)
    Sets the transformation from nominal end effector to end effector frame.
    +
    void automaticErrorRecovery()
    Runs automatic error recovery on the robot.
    +
    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.
    +
    Stores joint-level torque commands without gravity and friction.
    Definition: control_types.h:45
    +
    Contains helper types for returning motion generation and joint-level torque commands.
    +
    ControllerMode
    Available controller modes for a franka::Robot.
    Definition: control_types.h:19
    +
    RealtimeConfig
    Used to decide whether to enforce realtime mode for a control loop thread.
    Definition: control_types.h:26
    +
    Contains the franka::Duration type.
    +
    Contains functions for filtering signals with a low-pass filter.
    +
    Contains the franka::RobotState types.
    +
    Describes the robot state.
    Definition: robot_state.h:34
    +
    + + + + diff --git a/robot__model_8h_source.html b/robot__model_8h_source.html new file mode 100644 index 00000000..e91ed570 --- /dev/null +++ b/robot__model_8h_source.html @@ -0,0 +1,146 @@ + + + + + + + +libfranka: include/franka/robot_model.h Source File + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    robot_model.h
    +
    +
    +
    1 // Copyright (c) 2024 Franka Robotics GmbH
    +
    2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    3 #pragma once
    +
    4 
    +
    5 #include <pinocchio/algorithm/centroidal.hpp>
    +
    6 #include <pinocchio/algorithm/crba.hpp>
    +
    7 #include <pinocchio/algorithm/rnea.hpp>
    +
    8 #include <pinocchio/multibody/model.hpp>
    +
    9 #include <pinocchio/parsers/urdf.hpp>
    +
    10 #include <string>
    +
    11 
    +
    12 #include "franka/robot_model_base.h"
    +
    13 
    +
    14 namespace franka {
    +
    15 
    +
    19 class RobotModel : public RobotModelBase {
    +
    20  public:
    +
    21  RobotModel(const std::string& urdf);
    +
    22  void coriolis(const std::array<double, 7>& q,
    +
    23  const std::array<double, 7>& dq,
    +
    24  const std::array<double, 9>& i_total,
    +
    25  double m_total,
    +
    26  const std::array<double, 3>& f_x_ctotal,
    +
    27  std::array<double, 7>& c_ne) override;
    +
    28  void gravity(const std::array<double, 7>& q,
    +
    29  const std::array<double, 3>& g_earth,
    +
    30  double m_total,
    +
    31  const std::array<double, 3>& f_x_ctotal,
    +
    32  std::array<double, 7>& g_ne) override;
    +
    33  void mass(const std::array<double, 7>& q,
    +
    34  const std::array<double, 9>& i_total,
    +
    35  double m_total,
    +
    36  const std::array<double, 3>& f_x_ctotal,
    +
    37  std::array<double, 49>& m_ne) override;
    +
    38 
    +
    39  private:
    +
    44  void addInertiaToLastLink(const std::array<double, 9>& i_total,
    +
    45  double m_total,
    +
    46  const std::array<double, 3>& f_x_ctotal);
    +
    51  void computeDynamics(
    +
    52  const std::array<double, 9>& i_total,
    +
    53  double m_total,
    +
    54  const std::array<double, 3>& f_x_ctotal,
    +
    55  pinocchio::Data& data,
    +
    56  const std::function<void(pinocchio::Model&, pinocchio::Data&)>& compute_func);
    +
    57 
    +
    58  pinocchio::Model pinocchio_model_;
    +
    59  pinocchio::Inertia initial_last_link_inertia_;
    +
    60  pinocchio::FrameIndex last_link_frame_index_;
    +
    61  pinocchio::JointIndex last_joint_index_;
    +
    62 };
    +
    63 
    +
    64 } // namespace franka
    +
    Robot dynamic parameters computed from the URDF model with Pinocchio.
    Definition: robot_model_base.h:10
    +
    Implements RobotModelBase using Pinocchio.
    Definition: robot_model.h:19
    +
    void gravity(const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne) override
    Calculates the gravity vector.
    +
    void mass(const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne) override
    Calculates the 7x7 mass matrix.
    +
    void coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne) override
    Calculates the Coriolis force vector (state-space equation): , in .
    +
    + + + + diff --git a/robot__model__base_8h_source.html b/robot__model__base_8h_source.html new file mode 100644 index 00000000..1ab8372f --- /dev/null +++ b/robot__model__base_8h_source.html @@ -0,0 +1,119 @@ + + + + + + + +libfranka: include/franka/robot_model_base.h Source File + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    robot_model_base.h
    +
    +
    +
    1 // Copyright (c) 2024 Franka Robotics GmbH
    +
    2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    3 #pragma once
    +
    4 
    +
    5 #include <array>
    +
    6 
    + +
    11  public:
    +
    12  virtual ~RobotModelBase() = default;
    +
    27  virtual void coriolis(const std::array<double, 7>& q,
    +
    28  const std::array<double, 7>& dq,
    +
    29  const std::array<double, 9>& i_total,
    +
    30  double m_total,
    +
    31  const std::array<double, 3>& f_x_ctotal,
    +
    32  std::array<double, 7>& c_ne) = 0;
    +
    43  virtual void gravity(const std::array<double, 7>& q,
    +
    44  const std::array<double, 3>& g_earth,
    +
    45  double m_total,
    +
    46  const std::array<double, 3>& f_x_ctotal,
    +
    47  std::array<double, 7>& g_ne) = 0;
    +
    48 
    +
    61  virtual void mass(const std::array<double, 7>& q,
    +
    62  const std::array<double, 9>& i_total,
    +
    63  double m_total,
    +
    64  const std::array<double, 3>& f_x_ctotal,
    +
    65  std::array<double, 49>& m_ne) = 0;
    +
    66 };
    +
    Robot dynamic parameters computed from the URDF model with Pinocchio.
    Definition: robot_model_base.h:10
    +
    virtual void coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne)=0
    Calculates the Coriolis force vector (state-space equation): , in .
    +
    virtual void gravity(const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne)=0
    Calculates the gravity vector.
    +
    virtual void mass(const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne)=0
    Calculates the 7x7 mass matrix.
    +
    + + + + diff --git a/robot__state_8h.html b/robot__state_8h.html new file mode 100644 index 00000000..00f70e9a --- /dev/null +++ b/robot__state_8h.html @@ -0,0 +1,244 @@ + + + + + + + +libfranka: include/franka/robot_state.h File Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    robot_state.h File Reference
    +
    +
    + +

    Contains the franka::RobotState types. +More...

    +
    #include <array>
    +#include <ostream>
    +#include <franka/duration.h>
    +#include <franka/errors.h>
    +
    +Include dependency graph for robot_state.h:
    +
    +
    + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    struct  franka::RobotState
     Describes the robot state. More...
     
    + + + + +

    +Enumerations

    enum class  franka::RobotMode {
    +  kOther +, kIdle +, kMove +, kGuiding +,
    +  kReflex +, kUserStopped +, kAutomaticErrorRecovery +
    + }
     Describes the robot's current mode.
     
    + + + + + + + +

    +Functions

    std::ostream & franka::operator<< (std::ostream &ostream, const franka::RobotState &robot_state)
     Streams the robot state as JSON object: {"field_name_1": [0,0,0,0,0,0,0], "field_name_2": [0,0,0,0,0,0], ...}. More...
     
    std::ostream & franka::operator<< (std::ostream &ostream, RobotMode robot_mode)
     Streams RobotMode in human-readable form. More...
     
    +

    Detailed Description

    +

    Contains the franka::RobotState types.

    +

    Function Documentation

    + +

    ◆ operator<<() [1/2]

    + +
    +
    + + + + + + + + + + + + + + + + + + +
    std::ostream& franka::operator<< (std::ostream & ostream,
    const franka::RobotStaterobot_state 
    )
    +
    + +

    Streams the robot state as JSON object: {"field_name_1": [0,0,0,0,0,0,0], "field_name_2": [0,0,0,0,0,0], ...}.

    +
    Parameters
    + + + +
    [in]ostreamOstream instance
    [in]robot_stateRobotState instance to stream
    +
    +
    +
    Returns
    Ostream instance
    + +
    +
    + +

    ◆ operator<<() [2/2]

    + +
    +
    + + + + + + + + + + + + + + + + + + +
    std::ostream& franka::operator<< (std::ostream & ostream,
    RobotMode robot_mode 
    )
    +
    + +

    Streams RobotMode in human-readable form.

    +
    Parameters
    + + + +
    [in]ostreamOstream instance
    [in]robot_modeRobotMode to stream
    +
    +
    +
    Returns
    Ostream instance
    + +
    +
    +
    + + + + diff --git a/robot__state_8h__dep__incl.map b/robot__state_8h__dep__incl.map new file mode 100644 index 00000000..0fad4be3 --- /dev/null +++ b/robot__state_8h__dep__incl.map @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/robot__state_8h__dep__incl.md5 b/robot__state_8h__dep__incl.md5 new file mode 100644 index 00000000..8fa8f224 --- /dev/null +++ b/robot__state_8h__dep__incl.md5 @@ -0,0 +1 @@ +973a36e4032513bb7f4d07a325676715 \ No newline at end of file diff --git a/robot__state_8h__dep__incl.png b/robot__state_8h__dep__incl.png new file mode 100644 index 00000000..b05ab8d2 Binary files /dev/null and b/robot__state_8h__dep__incl.png differ diff --git a/robot__state_8h__incl.map b/robot__state_8h__incl.map new file mode 100644 index 00000000..09049e04 --- /dev/null +++ b/robot__state_8h__incl.map @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/robot__state_8h__incl.md5 b/robot__state_8h__incl.md5 new file mode 100644 index 00000000..f027b933 --- /dev/null +++ b/robot__state_8h__incl.md5 @@ -0,0 +1 @@ +aeacef374b3e8fe87bf91bcf6657c6de \ No newline at end of file diff --git a/robot__state_8h__incl.png b/robot__state_8h__incl.png new file mode 100644 index 00000000..fbae517d Binary files /dev/null and b/robot__state_8h__incl.png differ diff --git a/robot__state_8h_source.html b/robot__state_8h_source.html new file mode 100644 index 00000000..c626e0cb --- /dev/null +++ b/robot__state_8h_source.html @@ -0,0 +1,265 @@ + + + + + + + +libfranka: include/franka/robot_state.h Source File + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    robot_state.h
    +
    +
    +Go to the documentation of this file.
    1 // Copyright (c) 2024 Franka Robotics GmbH
    +
    2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    3 #pragma once
    +
    4 
    +
    5 #include <array>
    +
    6 #include <ostream>
    +
    7 
    +
    8 #include <franka/duration.h>
    +
    9 #include <franka/errors.h>
    +
    10 
    +
    16 namespace franka {
    +
    17 
    +
    21 enum class RobotMode {
    +
    22  kOther,
    +
    23  kIdle,
    +
    24  kMove,
    +
    25  kGuiding,
    +
    26  kReflex,
    +
    27  kUserStopped,
    +
    28  kAutomaticErrorRecovery
    +
    29 };
    +
    30 
    +
    34 struct RobotState {
    +
    40  std::array<double, 16> O_T_EE{}; // NOLINT(readability-identifier-naming)
    +
    41 
    +
    47  std::array<double, 16> O_T_EE_d{}; // NOLINT(readability-identifier-naming)
    +
    48 
    +
    58  std::array<double, 16> F_T_EE{}; // NOLINT(readability-identifier-naming)
    +
    59 
    +
    69  std::array<double, 16> F_T_NE{}; // NOLINT(readability-identifier-naming)
    +
    70 
    +
    81  std::array<double, 16> NE_T_EE{}; // NOLINT(readability-identifier-naming)
    +
    82 
    +
    90  std::array<double, 16> EE_T_K{}; // NOLINT(readability-identifier-naming)
    +
    91 
    +
    96  double m_ee{};
    +
    97 
    +
    102  std::array<double, 9> I_ee{}; // NOLINT(readability-identifier-naming)
    +
    103 
    +
    108  std::array<double, 3> F_x_Cee{}; // NOLINT(readability-identifier-naming)
    +
    109 
    +
    114  double m_load{};
    +
    115 
    +
    120  std::array<double, 9> I_load{}; // NOLINT(readability-identifier-naming)
    +
    121 
    +
    126  std::array<double, 3> F_x_Cload{}; // NOLINT(readability-identifier-naming)
    +
    127 
    +
    132  double m_total{};
    +
    133 
    +
    139  std::array<double, 9> I_total{}; // NOLINT(readability-identifier-naming)
    +
    140 
    +
    146  std::array<double, 3> F_x_Ctotal{}; // NOLINT(readability-identifier-naming)
    +
    147 
    +
    161  std::array<double, 2> elbow{};
    +
    162 
    +
    176  std::array<double, 2> elbow_d{};
    +
    177 
    +
    191  std::array<double, 2> elbow_c{};
    +
    192 
    +
    200  std::array<double, 2> delbow_c{};
    +
    201 
    +
    209  std::array<double, 2> ddelbow_c{};
    +
    210 
    +
    215  std::array<double, 7> tau_J{}; // NOLINT(readability-identifier-naming)
    +
    216 
    +
    221  std::array<double, 7> tau_J_d{}; // NOLINT(readability-identifier-naming)
    +
    222 
    +
    227  std::array<double, 7> dtau_J{}; // NOLINT(readability-identifier-naming)
    +
    228 
    +
    233  std::array<double, 7> q{};
    +
    234 
    +
    239  std::array<double, 7> q_d{};
    +
    240 
    +
    245  std::array<double, 7> dq{};
    +
    246 
    +
    251  std::array<double, 7> dq_d{};
    +
    252 
    +
    257  std::array<double, 7> ddq_d{};
    +
    258 
    +
    265  std::array<double, 7> joint_contact{};
    +
    266 
    +
    273  std::array<double, 6> cartesian_contact{};
    +
    274 
    +
    282  std::array<double, 7> joint_collision{};
    +
    283 
    +
    291  std::array<double, 6> cartesian_collision{};
    +
    292 
    +
    299  std::array<double, 7> tau_ext_hat_filtered{};
    +
    300 
    +
    309  std::array<double, 6> O_F_ext_hat_K{}; // NOLINT(readability-identifier-naming)
    +
    310 
    +
    319  std::array<double, 6> K_F_ext_hat_K{}; // NOLINT(readability-identifier-naming)
    +
    320 
    +
    326  std::array<double, 6> O_dP_EE_d{}; // NOLINT(readability-identifier-naming)
    +
    327 
    +
    335  std::array<double, 3> O_ddP_O{}; // NOLINT(readability-identifier-naming)
    +
    336 
    +
    342  std::array<double, 16> O_T_EE_c{}; // NOLINT(readability-identifier-naming)
    +
    343 
    +
    349  std::array<double, 6> O_dP_EE_c{}; // NOLINT(readability-identifier-naming)
    +
    350 
    +
    357  std::array<double, 6> O_ddP_EE_c{}; // NOLINT(readability-identifier-naming)
    +
    358 
    +
    363  std::array<double, 7> theta{};
    +
    364 
    +
    369  std::array<double, 7> dtheta{};
    +
    370 
    + +
    375 
    + +
    380 
    + +
    389 
    +
    393  RobotMode robot_mode = RobotMode::kUserStopped;
    +
    394 
    + +
    402 };
    +
    403 
    +
    413 std::ostream& operator<<(std::ostream& ostream, const franka::RobotState& robot_state);
    +
    414 
    +
    423 std::ostream& operator<<(std::ostream& ostream, RobotMode robot_mode);
    +
    424 
    +
    425 } // namespace franka
    +
    Represents a duration with millisecond resolution.
    Definition: duration.h:19
    +
    Contains the franka::Duration type.
    +
    Contains the franka::Errors type.
    +
    std::ostream & operator<<(std::ostream &ostream, const Errors &errors)
    Streams the errors as JSON array.
    +
    RobotMode
    Describes the robot's current mode.
    Definition: robot_state.h:21
    +
    Enumerates errors that can occur while controlling a franka::Robot.
    Definition: errors.h:18
    +
    Describes the robot state.
    Definition: robot_state.h:34
    +
    Errors last_motion_errors
    Contains the errors that aborted the previous motion.
    Definition: robot_state.h:379
    +
    std::array< double, 2 > elbow_c
    Commanded elbow configuration.
    Definition: robot_state.h:191
    +
    std::array< double, 16 > O_T_EE
    Measured end effector pose in base frame.
    Definition: robot_state.h:40
    +
    std::array< double, 6 > O_dP_EE_d
    Desired end effector twist in base frame.
    Definition: robot_state.h:326
    +
    std::array< double, 2 > ddelbow_c
    Commanded elbow acceleration.
    Definition: robot_state.h:209
    +
    std::array< double, 7 > dtheta
    Motor velocity.
    Definition: robot_state.h:369
    +
    std::array< double, 2 > elbow_d
    Desired elbow configuration.
    Definition: robot_state.h:176
    +
    std::array< double, 7 > joint_collision
    Indicates which contact level is activated in which joint.
    Definition: robot_state.h:282
    +
    std::array< double, 16 > O_T_EE_c
    Last commanded end effector pose of motion generation in base frame.
    Definition: robot_state.h:342
    +
    std::array< double, 16 > O_T_EE_d
    Last desired end effector pose of motion generation in base frame.
    Definition: robot_state.h:47
    +
    std::array< double, 2 > elbow
    Elbow configuration.
    Definition: robot_state.h:161
    +
    std::array< double, 3 > F_x_Cload
    Configured center of mass of the external load with respect to flange frame.
    Definition: robot_state.h:126
    +
    RobotMode robot_mode
    Current robot mode.
    Definition: robot_state.h:393
    +
    std::array< double, 6 > O_dP_EE_c
    Last commanded end effector twist in base frame.
    Definition: robot_state.h:349
    +
    std::array< double, 6 > cartesian_collision
    Indicates which contact level is activated in which Cartesian dimension .
    Definition: robot_state.h:291
    +
    std::array< double, 2 > delbow_c
    Commanded elbow velocity.
    Definition: robot_state.h:200
    +
    std::array< double, 6 > O_F_ext_hat_K
    Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the base f...
    Definition: robot_state.h:309
    +
    std::array< double, 9 > I_load
    Configured rotational inertia matrix of the external load with respect to center of mass.
    Definition: robot_state.h:120
    +
    std::array< double, 7 > ddq_d
    Desired joint acceleration.
    Definition: robot_state.h:257
    +
    std::array< double, 16 > F_T_EE
    End effector frame pose in flange frame.
    Definition: robot_state.h:58
    +
    std::array< double, 7 > q_d
    Desired joint position.
    Definition: robot_state.h:239
    +
    std::array< double, 7 > tau_J_d
    Desired link-side joint torque sensor signals without gravity.
    Definition: robot_state.h:221
    +
    std::array< double, 7 > joint_contact
    Indicates which contact level is activated in which joint.
    Definition: robot_state.h:265
    +
    std::array< double, 3 > F_x_Ctotal
    Combined center of mass of the end effector load and the external load with respect to flange frame.
    Definition: robot_state.h:146
    +
    std::array< double, 9 > I_ee
    Configured rotational inertia matrix of the end effector load with respect to center of mass.
    Definition: robot_state.h:102
    +
    std::array< double, 6 > cartesian_contact
    Indicates which contact level is activated in which Cartesian dimension .
    Definition: robot_state.h:273
    +
    double m_total
    Sum of the mass of the end effector and the external load.
    Definition: robot_state.h:132
    +
    std::array< double, 16 > F_T_NE
    Nominal end effector frame pose in flange frame.
    Definition: robot_state.h:69
    +
    std::array< double, 3 > F_x_Cee
    Configured center of mass of the end effector load with respect to flange frame.
    Definition: robot_state.h:108
    +
    std::array< double, 6 > K_F_ext_hat_K
    Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the stiffn...
    Definition: robot_state.h:319
    +
    double m_load
    Configured mass of the external load.
    Definition: robot_state.h:114
    +
    std::array< double, 7 > theta
    Motor position.
    Definition: robot_state.h:363
    +
    Duration time
    Strictly monotonically increasing timestamp since robot start.
    Definition: robot_state.h:401
    +
    std::array< double, 3 > O_ddP_O
    Linear component of the acceleration of the robot's base, expressed in frame parallel to the base fra...
    Definition: robot_state.h:335
    +
    Errors current_errors
    Current error state.
    Definition: robot_state.h:374
    +
    std::array< double, 16 > NE_T_EE
    End effector frame pose in nominal end effector frame.
    Definition: robot_state.h:81
    +
    std::array< double, 6 > O_ddP_EE_c
    Last commanded end effector acceleration in base frame.
    Definition: robot_state.h:357
    +
    std::array< double, 7 > tau_ext_hat_filtered
    Low-pass filtered torques generated by external forces on the joints.
    Definition: robot_state.h:299
    +
    std::array< double, 7 > tau_J
    Measured link-side joint torque sensor signals.
    Definition: robot_state.h:215
    +
    std::array< double, 9 > I_total
    Combined rotational inertia matrix of the end effector load and the external load with respect to the...
    Definition: robot_state.h:139
    +
    std::array< double, 7 > q
    Measured joint position.
    Definition: robot_state.h:233
    +
    std::array< double, 7 > dtau_J
    Derivative of measured link-side joint torque sensor signals.
    Definition: robot_state.h:227
    +
    std::array< double, 16 > EE_T_K
    Stiffness frame pose in end effector frame.
    Definition: robot_state.h:90
    +
    std::array< double, 7 > dq_d
    Desired joint velocity.
    Definition: robot_state.h:251
    +
    double control_command_success_rate
    Percentage of the last 100 control commands that were successfully received by the robot.
    Definition: robot_state.h:388
    +
    std::array< double, 7 > dq
    Measured joint velocity.
    Definition: robot_state.h:245
    +
    double m_ee
    Configured mass of the end effector.
    Definition: robot_state.h:96
    +
    + + + + diff --git a/search/all_0.html b/search/all_0.html new file mode 100644 index 00000000..1ec5b2d5 --- /dev/null +++ b/search/all_0.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_0.js b/search/all_0.js new file mode 100644 index 00000000..5c0a85b1 --- /dev/null +++ b/search/all_0.js @@ -0,0 +1,13 @@ +var searchData= +[ + ['active_5fcontrol_2eh_0',['active_control.h',['../active__control_8h.html',1,'']]], + ['active_5fcontrol_5fbase_2eh_1',['active_control_base.h',['../active__control__base_8h.html',1,'']]], + ['active_5fmotion_5fgenerator_2eh_2',['active_motion_generator.h',['../active__motion__generator_8h.html',1,'']]], + ['active_5ftorque_5fcontrol_2eh_3',['active_torque_control.h',['../active__torque__control_8h.html',1,'']]], + ['activecontrol_4',['ActiveControl',['../classfranka_1_1ActiveControl.html#a4aa09537fddbec6cf1eed05fdc147b30',1,'franka::ActiveControl::ActiveControl()'],['../classfranka_1_1ActiveControl.html',1,'franka::ActiveControl']]], + ['activecontrolbase_5',['ActiveControlBase',['../classfranka_1_1ActiveControlBase.html',1,'franka']]], + ['activemotiongenerator_6',['ActiveMotionGenerator',['../classfranka_1_1ActiveMotionGenerator.html',1,'franka']]], + ['activetorquecontrol_7',['ActiveTorqueControl',['../classfranka_1_1ActiveTorqueControl.html',1,'franka']]], + ['actual_5fpower_8',['actual_power',['../structfranka_1_1VacuumGripperState.html#a4230c68698cdbf6c1c560e181133bdc3',1,'franka::VacuumGripperState']]], + ['automaticerrorrecovery_9',['automaticErrorRecovery',['../classfranka_1_1Robot.html#af682aa673415718715bd859116bc2fed',1,'franka::Robot']]] +]; diff --git a/search/all_1.html b/search/all_1.html new file mode 100644 index 00000000..9f80e904 --- /dev/null +++ b/search/all_1.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_1.js b/search/all_1.js new file mode 100644 index 00000000..65296956 --- /dev/null +++ b/search/all_1.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['base_5facceleration_5finitialization_5ftimeout_10',['base_acceleration_initialization_timeout',['../structfranka_1_1Errors.html#a4dc331a7ae3242ea43e6fbf7e21c695a',1,'franka::Errors']]], + ['base_5facceleration_5finvalid_5freading_11',['base_acceleration_invalid_reading',['../structfranka_1_1Errors.html#a8467b7b8a3a68c3e0be7adc39933cb0e',1,'franka::Errors']]], + ['bodyjacobian_12',['bodyJacobian',['../classfranka_1_1Model.html#a914a197a900a275799cf8d7461bb9d8a',1,'franka::Model::bodyJacobian(Frame frame, const franka::RobotState &robot_state) const'],['../classfranka_1_1Model.html#a9ceca00546fa221f15ddaa7c0d27c40e',1,'franka::Model::bodyJacobian(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const']]] +]; diff --git a/search/all_10.html b/search/all_10.html new file mode 100644 index 00000000..3bf11961 --- /dev/null +++ b/search/all_10.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_10.js b/search/all_10.js new file mode 100644 index 00000000..c78c24a9 --- /dev/null +++ b/search/all_10.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['q_213',['q',['../classfranka_1_1JointPositions.html#a40e9098abe1c51cd48e17e41fbf78337',1,'franka::JointPositions::q()'],['../structfranka_1_1RobotState.html#ade3335d1ac2f6c44741a916d565f7091',1,'franka::RobotState::q()']]], + ['q_5fd_214',['q_d',['../structfranka_1_1RobotState.html#a706045af1b176049e9e56df755325bd2',1,'franka::RobotState']]] +]; diff --git a/search/all_11.html b/search/all_11.html new file mode 100644 index 00000000..c9f79d28 --- /dev/null +++ b/search/all_11.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_11.js b/search/all_11.js new file mode 100644 index 00000000..49a9fe70 --- /dev/null +++ b/search/all_11.js @@ -0,0 +1,19 @@ +var searchData= +[ + ['rate_5flimiting_2eh_215',['rate_limiting.h',['../rate__limiting_8h.html',1,'']]], + ['read_216',['read',['../classfranka_1_1Robot.html#a82f85eed20426901a7e77b66c041664b',1,'franka::Robot']]], + ['readonce_217',['readOnce',['../classfranka_1_1VacuumGripper.html#aaa61bfd1027cf5dc2eb9e96536a9fabf',1,'franka::VacuumGripper::readOnce()'],['../classfranka_1_1Robot.html#ae3c3d7c5c4491a1e96a0a543931e899a',1,'franka::Robot::readOnce()'],['../classfranka_1_1Gripper.html#ab0afc8a41c9c5fff808e76851dcf23ce',1,'franka::Gripper::readOnce()'],['../classfranka_1_1ActiveControlBase.html#ae99dac6dae3b0dcd79104a1a404e42d0',1,'franka::ActiveControlBase::readOnce()'],['../classfranka_1_1ActiveControl.html#a55f5b94e5ac491e5b2ccc1782a873582',1,'franka::ActiveControl::readOnce()']]], + ['realtimeconfig_218',['RealtimeConfig',['../control__types_8h.html#aeede4f4629390fea21ca5e5a35a8a943',1,'franka']]], + ['realtimeexception_219',['RealtimeException',['../structfranka_1_1RealtimeException.html',1,'franka']]], + ['record_220',['Record',['../structfranka_1_1Record.html',1,'franka']]], + ['robot_221',['Robot',['../classfranka_1_1Robot.html',1,'franka::Robot'],['../classfranka_1_1ActiveMotionGenerator.html#a9f34d4a840b0d3e73fc3185af5fed175',1,'franka::ActiveMotionGenerator::Robot()'],['../classfranka_1_1ActiveTorqueControl.html#a9f34d4a840b0d3e73fc3185af5fed175',1,'franka::ActiveTorqueControl::Robot()'],['../classfranka_1_1Robot.html#ae63bc19390df3d54f3a270814df35eb6',1,'franka::Robot::Robot(const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50)'],['../classfranka_1_1Robot.html#a378d415475336082e81a35b9811dc6c2',1,'franka::Robot::Robot(Robot &&other) noexcept'],['../classfranka_1_1Robot.html#a7cb49336d7e8b261b590a364daff2913',1,'franka::Robot::Robot(std::shared_ptr< Impl > robot_impl)'],['../classfranka_1_1Robot.html#abf60ce0434f4dc262f04fcab0beff5ac',1,'franka::Robot::Robot()=default']]], + ['robot_2eh_222',['robot.h',['../robot_8h.html',1,'']]], + ['robot_5fimpl_223',['robot_impl',['../classfranka_1_1ActiveControl.html#a94e725adb409391547a260f204c74564',1,'franka::ActiveControl']]], + ['robot_5fmode_224',['robot_mode',['../structfranka_1_1RobotState.html#a4943ae75e0e2ec534e0afac31cbcc987',1,'franka::RobotState']]], + ['robot_5fstate_2eh_225',['robot_state.h',['../robot__state_8h.html',1,'']]], + ['robotcommand_226',['RobotCommand',['../structfranka_1_1RobotCommand.html',1,'franka']]], + ['robotmode_227',['RobotMode',['../robot__state_8h.html#adfe059ae23ebbad59e421edaa879651a',1,'franka']]], + ['robotmodel_228',['RobotModel',['../classfranka_1_1RobotModel.html',1,'franka']]], + ['robotmodelbase_229',['RobotModelBase',['../classRobotModelBase.html',1,'']]], + ['robotstate_230',['RobotState',['../structfranka_1_1RobotState.html',1,'franka']]] +]; diff --git a/search/all_12.html b/search/all_12.html new file mode 100644 index 00000000..ab934722 --- /dev/null +++ b/search/all_12.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_12.js b/search/all_12.js new file mode 100644 index 00000000..e977989b --- /dev/null +++ b/search/all_12.js @@ -0,0 +1,24 @@ +var searchData= +[ + ['self_5fcollision_5favoidance_5fviolation_231',['self_collision_avoidance_violation',['../structfranka_1_1Errors.html#adf68f6333624cb5558864441a991de8c',1,'franka::Errors']]], + ['server_5fversion_232',['server_version',['../structfranka_1_1IncompatibleVersionException.html#a0928098d8c32f405d17b65a0f004b5ab',1,'franka::IncompatibleVersionException']]], + ['serverversion_233',['ServerVersion',['../classfranka_1_1Gripper.html#a613bf52d9433b733685d0fb9ea71602e',1,'franka::Gripper::ServerVersion()'],['../classfranka_1_1Robot.html#ad1dd3dccff6f33691d2c66eaa5ac5a10',1,'franka::Robot::ServerVersion()'],['../classfranka_1_1VacuumGripper.html#a7b1d752680134e2a9df347002c6ace61',1,'franka::VacuumGripper::ServerVersion()']]], + ['serverversion_234',['serverVersion',['../classfranka_1_1Gripper.html#a8b0b4246c042465fb00871b31efdbd8b',1,'franka::Gripper::serverVersion()'],['../classfranka_1_1Robot.html#a3b864e16b7accafdf1a755dc21765701',1,'franka::Robot::serverVersion()'],['../classfranka_1_1VacuumGripper.html#a19abac44be2fc6df7f54fa11078a13ca',1,'franka::VacuumGripper::serverVersion()']]], + ['setcartesianimpedance_235',['setCartesianImpedance',['../classfranka_1_1Robot.html#ac2678c5c31cc8c0627ecda7485f81f6d',1,'franka::Robot']]], + ['setcollisionbehavior_236',['setCollisionBehavior',['../classfranka_1_1Robot.html#a168e1214ac36d74ac64f894332b84534',1,'franka::Robot::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)'],['../classfranka_1_1Robot.html#aa188f58c9025594be4d1700da744a962',1,'franka::Robot::setCollisionBehavior(const std::array< double, 7 > &lower_torque_thresholds, const std::array< double, 7 > &upper_torque_thresholds, const std::array< double, 6 > &lower_force_thresholds, const std::array< double, 6 > &upper_force_thresholds)']]], + ['setcurrentthreadtohighestschedulerpriority_237',['setCurrentThreadToHighestSchedulerPriority',['../control__tools_8h.html#a5c090196bc50ead82194d3e594e61e65',1,'franka']]], + ['setdefaultbehavior_238',['setDefaultBehavior',['../examples__common_8h.html#ad0c6e1cb044845ee8a01b5aa1e801a45',1,'examples_common.cpp']]], + ['setee_239',['setEE',['../classfranka_1_1Robot.html#aec4abdefbc0f9a7400a36bfa0a6068af',1,'franka::Robot']]], + ['setguidingmode_240',['setGuidingMode',['../classfranka_1_1Robot.html#a7992cee203e66f9a61fe2f318ef88a26',1,'franka::Robot']]], + ['setjointimpedance_241',['setJointImpedance',['../classfranka_1_1Robot.html#aa18a28697cf6e3be16c6cff2dd839560',1,'franka::Robot']]], + ['setk_242',['setK',['../classfranka_1_1Robot.html#ad1cf59d1b11306d80cd3c7144a989c56',1,'franka::Robot']]], + ['setload_243',['setLoad',['../classfranka_1_1Robot.html#afcb708df10f24563dbcf7d5b907b4a15',1,'franka::Robot']]], + ['start_5felbow_5fsign_5finconsistent_244',['start_elbow_sign_inconsistent',['../structfranka_1_1Errors.html#aa6de1956ac056792a1dea6b9ddd52a50',1,'franka::Errors']]], + ['startcartesianposecontrol_245',['startCartesianPoseControl',['../classfranka_1_1Robot.html#a3822866cf931fab955d3dcfc6cf746e5',1,'franka::Robot']]], + ['startcartesianvelocitycontrol_246',['startCartesianVelocityControl',['../classfranka_1_1Robot.html#a838e2cfba6b08dd87742bbcfe62f15bf',1,'franka::Robot']]], + ['startjointpositioncontrol_247',['startJointPositionControl',['../classfranka_1_1Robot.html#aca7ecf76cf9c5af49cc5a878c91e19a9',1,'franka::Robot']]], + ['startjointvelocitycontrol_248',['startJointVelocityControl',['../classfranka_1_1Robot.html#ae9c867d10817b2485e306450f389a009',1,'franka::Robot']]], + ['starttorquecontrol_249',['startTorqueControl',['../classfranka_1_1Robot.html#a8146de9e50217068672b6f726a91de91',1,'franka::Robot']]], + ['state_250',['state',['../structfranka_1_1Record.html#a58249658c9549fbc792eea90e7b6a7cc',1,'franka::Record']]], + ['stop_251',['stop',['../classfranka_1_1Gripper.html#add7397fb6c5631650c139d26a85c8e1d',1,'franka::Gripper::stop()'],['../classfranka_1_1Robot.html#a69cb08e075a81ecf3f26e94d26a06296',1,'franka::Robot::stop()'],['../classfranka_1_1VacuumGripper.html#a3722fe5488c516b4082c878a083cc865',1,'franka::VacuumGripper::stop()']]] +]; diff --git a/search/all_13.html b/search/all_13.html new file mode 100644 index 00000000..51172c2f --- /dev/null +++ b/search/all_13.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_13.js b/search/all_13.js new file mode 100644 index 00000000..06230184 --- /dev/null +++ b/search/all_13.js @@ -0,0 +1,15 @@ +var searchData= +[ + ['tau_5fext_5fhat_5ffiltered_252',['tau_ext_hat_filtered',['../structfranka_1_1RobotState.html#acdef8005828d193e45b128085a9e363b',1,'franka::RobotState']]], + ['tau_5fj_253',['tau_J',['../classfranka_1_1Torques.html#ac2a266cc2d3b7e0fb4f8eff045dbaed8',1,'franka::Torques::tau_J()'],['../structfranka_1_1RobotState.html#ad90e2518d661da0d8fa4c864bae210e5',1,'franka::RobotState::tau_J()']]], + ['tau_5fj_5fd_254',['tau_J_d',['../structfranka_1_1RobotState.html#a7086a89a2705810f93a3a95d43df2d9d',1,'franka::RobotState']]], + ['tau_5fj_5frange_5fviolation_255',['tau_j_range_violation',['../structfranka_1_1Errors.html#a1491f8428341649befa3d088aebb317e',1,'franka::Errors']]], + ['temperature_256',['temperature',['../structfranka_1_1GripperState.html#aa6733fa786dbf3b073acbaf3779e34b3',1,'franka::GripperState']]], + ['theta_257',['theta',['../structfranka_1_1RobotState.html#aa34145d77dd411d7ca578c355f0ba2b4',1,'franka::RobotState']]], + ['time_258',['time',['../structfranka_1_1GripperState.html#a80bf474b0e4351e2eefab62d1bd10c07',1,'franka::GripperState::time()'],['../structfranka_1_1RobotState.html#aabfdabeaef8c1858c52dd32344bdd039',1,'franka::RobotState::time()'],['../structfranka_1_1VacuumGripperState.html#aaa98eb6e1888094aace2014121a468ab',1,'franka::VacuumGripperState::time()']]], + ['tomsec_259',['toMSec',['../classfranka_1_1Duration.html#a2a25ae33c8739b8f705f13798aa9e162',1,'franka::Duration']]], + ['torques_260',['Torques',['../classfranka_1_1Torques.html',1,'franka']]], + ['torques_261',['torques',['../structfranka_1_1RobotCommand.html#a8b23e8b669b1fd594988ecdbf54bfbce',1,'franka::RobotCommand']]], + ['torques_262',['Torques',['../classfranka_1_1Torques.html#a509d63195827289ffc645e4b62a9750d',1,'franka::Torques::Torques(const std::array< double, 7 > &torques) noexcept'],['../classfranka_1_1Torques.html#a744a08e16dcfc40b3a90ab6a85bac0d8',1,'franka::Torques::Torques(std::initializer_list< double > torques)']]], + ['tosec_263',['toSec',['../classfranka_1_1Duration.html#a497af77a3280159547f231f0374e9ac1',1,'franka::Duration']]] +]; diff --git a/search/all_14.html b/search/all_14.html new file mode 100644 index 00000000..afecf563 --- /dev/null +++ b/search/all_14.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_14.js b/search/all_14.js new file mode 100644 index 00000000..c4d7eeba --- /dev/null +++ b/search/all_14.js @@ -0,0 +1,9 @@ +var searchData= +[ + ['vacuum_264',['vacuum',['../structfranka_1_1VacuumGripperState.html#ae94720737193caa696a47563a8efe6a8',1,'franka::VacuumGripperState::vacuum()'],['../classfranka_1_1VacuumGripper.html#a517d95d9800990ca1a5892473c2def89',1,'franka::VacuumGripper::vacuum()']]], + ['vacuum_5fgripper_2eh_265',['vacuum_gripper.h',['../vacuum__gripper_8h.html',1,'']]], + ['vacuum_5fgripper_5fstate_2eh_266',['vacuum_gripper_state.h',['../vacuum__gripper__state_8h.html',1,'']]], + ['vacuumgripper_267',['VacuumGripper',['../classfranka_1_1VacuumGripper.html',1,'franka::VacuumGripper'],['../classfranka_1_1VacuumGripper.html#ab5d8483a0bb16136da684cfac721eae1',1,'franka::VacuumGripper::VacuumGripper(const std::string &franka_address)'],['../classfranka_1_1VacuumGripper.html#ab80730b14b5948eea37395e87800ce5f',1,'franka::VacuumGripper::VacuumGripper(VacuumGripper &&vacuum_gripper) noexcept']]], + ['vacuumgripperdevicestatus_268',['VacuumGripperDeviceStatus',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611',1,'franka']]], + ['vacuumgripperstate_269',['VacuumGripperState',['../structfranka_1_1VacuumGripperState.html',1,'franka']]] +]; diff --git a/search/all_15.html b/search/all_15.html new file mode 100644 index 00000000..69f382b3 --- /dev/null +++ b/search/all_15.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_15.js b/search/all_15.js new file mode 100644 index 00000000..ddb3f645 --- /dev/null +++ b/search/all_15.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['width_270',['width',['../structfranka_1_1GripperState.html#adf095f446ec39a9a48e120b209dcd6e9',1,'franka::GripperState']]], + ['writeonce_271',['writeOnce',['../classfranka_1_1ActiveControlBase.html#a070846c3bd259aa703848d984a82e43d',1,'franka::ActiveControlBase::writeOnce()'],['../classfranka_1_1ActiveTorqueControl.html#acc3b1d8c41cd191786e384887adf5da2',1,'franka::ActiveTorqueControl::writeOnce()'],['../classfranka_1_1ActiveMotionGenerator.html#aae24c0819a0bd0996657063832245d69',1,'franka::ActiveMotionGenerator::writeOnce()'],['../classfranka_1_1ActiveControlBase.html#a35ad38e4c512e34b0c82b081cefe4020',1,'franka::ActiveControlBase::writeOnce(const CartesianVelocities &motion_generator_input)=0'],['../classfranka_1_1ActiveControlBase.html#a9b05a521b8ab9d1af6c58b3d1fbcf12f',1,'franka::ActiveControlBase::writeOnce(const CartesianPose &motion_generator_input)=0'],['../classfranka_1_1ActiveControlBase.html#ae00c5b9387e21b76443ddfd173f7d01e',1,'franka::ActiveControlBase::writeOnce(const JointVelocities &motion_generator_input)=0'],['../classfranka_1_1ActiveControlBase.html#a800a13f3d6d12408dbff3afc8d072af2',1,'franka::ActiveControlBase::writeOnce(const JointPositions &motion_generator_input)=0'],['../classfranka_1_1ActiveControlBase.html#ac94d472225bbe8b6322b9f3cbf98bd3b',1,'franka::ActiveControlBase::writeOnce(const CartesianVelocities &, const std::optional< const Torques > &)=0'],['../classfranka_1_1ActiveControlBase.html#a61ffd2a40b082e275784175f7a38aa08',1,'franka::ActiveControlBase::writeOnce(const CartesianPose &, const std::optional< const Torques > &)=0'],['../classfranka_1_1ActiveControlBase.html#a46f54e3366ad083c9dedf62b9f4e1fea',1,'franka::ActiveControlBase::writeOnce(const JointVelocities &, const std::optional< const Torques > &)=0'],['../classfranka_1_1ActiveControlBase.html#ab0b5421122071fa0d578dcd0f4cabc36',1,'franka::ActiveControlBase::writeOnce(const JointPositions &, const std::optional< const Torques > &)=0'],['../classfranka_1_1ActiveControl.html#ad4bf06b3e873fd95a2261d67d89a4d1f',1,'franka::ActiveControl::writeOnce(const CartesianVelocities &motion_generator_input) override'],['../classfranka_1_1ActiveControl.html#a6b6265ccad26dc2e32c7b6329b74fb80',1,'franka::ActiveControl::writeOnce(const CartesianPose &motion_generator_input) override'],['../classfranka_1_1ActiveControl.html#a7f54a6bc037fa63f14e1a3f1329d4bf5',1,'franka::ActiveControl::writeOnce(const JointVelocities &motion_generator_input) override'],['../classfranka_1_1ActiveControl.html#a8166a590c84c749cd90c874bd2f1aca4',1,'franka::ActiveControl::writeOnce(const JointPositions &motion_generator_input) override'],['../classfranka_1_1ActiveControl.html#a12c3c6916e26e66dae41eb624daabb4a',1,'franka::ActiveControl::writeOnce(const CartesianVelocities &, const std::optional< const Torques > &) override'],['../classfranka_1_1ActiveControl.html#a52f9ce19182359732bddee7b52a87419',1,'franka::ActiveControl::writeOnce(const CartesianPose &, const std::optional< const Torques > &) override'],['../classfranka_1_1ActiveControl.html#a2a27360ae8203fa8a413c47708e03ede',1,'franka::ActiveControl::writeOnce(const JointVelocities &, const std::optional< const Torques > &) override'],['../classfranka_1_1ActiveControl.html#a762615a1a3d5cf18064bfbd0b45effa6',1,'franka::ActiveControl::writeOnce(const JointPositions &, const std::optional< const Torques > &) override'],['../classfranka_1_1ActiveControl.html#a888b87832cd3def156c07a0b57d95663',1,'franka::ActiveControl::writeOnce(const Torques &) override']]] +]; diff --git a/search/all_16.html b/search/all_16.html new file mode 100644 index 00000000..b19867ad --- /dev/null +++ b/search/all_16.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_16.js b/search/all_16.js new file mode 100644 index 00000000..6cb08b00 --- /dev/null +++ b/search/all_16.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['zerojacobian_272',['zeroJacobian',['../classfranka_1_1Model.html#a6fb6347b571a6759bad10b3a9e28a28f',1,'franka::Model::zeroJacobian(Frame frame, const franka::RobotState &robot_state) const'],['../classfranka_1_1Model.html#a6522f1079e1dc5f6799dde6197b45259',1,'franka::Model::zeroJacobian(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const']]] +]; diff --git a/search/all_17.html b/search/all_17.html new file mode 100644 index 00000000..1ad5d34b --- /dev/null +++ b/search/all_17.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_17.js b/search/all_17.js new file mode 100644 index 00000000..ea52df44 --- /dev/null +++ b/search/all_17.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['_7egripper_273',['~Gripper',['../classfranka_1_1Gripper.html#ade253b8a35312d52c636c6aafb7b2e1d',1,'franka::Gripper']]], + ['_7emodel_274',['~Model',['../classfranka_1_1Model.html#a1d6ffa26afc6cfdff7e329d15b8bd65e',1,'franka::Model']]], + ['_7erobot_275',['~Robot',['../classfranka_1_1Robot.html#ac19400de0fd39852d5825b1f1ccc85e2',1,'franka::Robot']]], + ['_7evacuumgripper_276',['~VacuumGripper',['../classfranka_1_1VacuumGripper.html#af43f640f3cb9ca873b02bb464d3c279b',1,'franka::VacuumGripper']]] +]; diff --git a/search/all_2.html b/search/all_2.html new file mode 100644 index 00000000..02cfffc2 --- /dev/null +++ b/search/all_2.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_2.js b/search/all_2.js new file mode 100644 index 00000000..8350f02f --- /dev/null +++ b/search/all_2.js @@ -0,0 +1,46 @@ +var searchData= +[ + ['cartesian_5fcollision_13',['cartesian_collision',['../structfranka_1_1RobotState.html#a52c20478f4c1e162df38582ea9bda044',1,'franka::RobotState']]], + ['cartesian_5fcontact_14',['cartesian_contact',['../structfranka_1_1RobotState.html#a7fc1f0358d2104d39d301d70544fa6c1',1,'franka::RobotState']]], + ['cartesian_5fmotion_5fgenerator_5facceleration_5fdiscontinuity_15',['cartesian_motion_generator_acceleration_discontinuity',['../structfranka_1_1Errors.html#a10c6ac36bf48b4a9edf91e74d9bc4837',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5felbow_5flimit_5fviolation_16',['cartesian_motion_generator_elbow_limit_violation',['../structfranka_1_1Errors.html#ac21ebdc1e0e8fb3099a7dce284550c4c',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5felbow_5fsign_5finconsistent_17',['cartesian_motion_generator_elbow_sign_inconsistent',['../structfranka_1_1Errors.html#a58b0e1199c9dded5a32bfeb110e63037',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fjoint_5facceleration_5fdiscontinuity_18',['cartesian_motion_generator_joint_acceleration_discontinuity',['../structfranka_1_1Errors.html#a2e223ef3c771709a6a3f094adf12f9cb',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fjoint_5fposition_5flimits_5fviolation_19',['cartesian_motion_generator_joint_position_limits_violation',['../structfranka_1_1Errors.html#a73aef7473fd6d1d5b207e68fa35948c5',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fjoint_5fvelocity_5fdiscontinuity_20',['cartesian_motion_generator_joint_velocity_discontinuity',['../structfranka_1_1Errors.html#a1c8c56766fefc19fda5d5de909ca5b37',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fjoint_5fvelocity_5flimits_5fviolation_21',['cartesian_motion_generator_joint_velocity_limits_violation',['../structfranka_1_1Errors.html#a435d16d62a123bfbf578bc76e3780605',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fstart_5felbow_5finvalid_22',['cartesian_motion_generator_start_elbow_invalid',['../structfranka_1_1Errors.html#a6d905b803bbe8a7be8490f2a94ba524a',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fvelocity_5fdiscontinuity_23',['cartesian_motion_generator_velocity_discontinuity',['../structfranka_1_1Errors.html#a17e4a9b6b7dc4cc12c1328d36cac3eaf',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fvelocity_5flimits_5fviolation_24',['cartesian_motion_generator_velocity_limits_violation',['../structfranka_1_1Errors.html#a91437c081452ef708563346b102ba894',1,'franka::Errors']]], + ['cartesian_5fpose_25',['cartesian_pose',['../structfranka_1_1RobotCommand.html#acce2090d696ebb9759fd0f37fd35a298',1,'franka::RobotCommand']]], + ['cartesian_5fposition_5flimits_5fviolation_26',['cartesian_position_limits_violation',['../structfranka_1_1Errors.html#a41c8b50ecbb015a2dba1a3dbbff694b6',1,'franka::Errors']]], + ['cartesian_5fposition_5fmotion_5fgenerator_5finvalid_5fframe_27',['cartesian_position_motion_generator_invalid_frame',['../structfranka_1_1Errors.html#aa1952c6da2f81578861a19b947c97b85',1,'franka::Errors']]], + ['cartesian_5fposition_5fmotion_5fgenerator_5fstart_5fpose_5finvalid_28',['cartesian_position_motion_generator_start_pose_invalid',['../structfranka_1_1Errors.html#aa910fad4992b91be1ea1c321ee9b7a1e',1,'franka::Errors']]], + ['cartesian_5freflex_29',['cartesian_reflex',['../structfranka_1_1Errors.html#a47bd58b0ab2198e4d038e0a24eafb310',1,'franka::Errors']]], + ['cartesian_5fspline_5fmotion_5fgenerator_5fviolation_30',['cartesian_spline_motion_generator_violation',['../structfranka_1_1Errors.html#a5617689cd7e875baebcecf054513f0c4',1,'franka::Errors']]], + ['cartesian_5fvelocities_31',['cartesian_velocities',['../structfranka_1_1RobotCommand.html#a04b4841130fab920936190be1bc5dba3',1,'franka::RobotCommand']]], + ['cartesian_5fvelocity_5fprofile_5fsafety_5fviolation_32',['cartesian_velocity_profile_safety_violation',['../structfranka_1_1Errors.html#afc093fc5f99e1f6cab6de4fa9bc32692',1,'franka::Errors']]], + ['cartesian_5fvelocity_5fviolation_33',['cartesian_velocity_violation',['../structfranka_1_1Errors.html#a382fbec6b463ddcc2cbfd90340021ff1',1,'franka::Errors']]], + ['cartesianlowpassfilter_34',['cartesianLowpassFilter',['../lowpass__filter_8h.html#ac25e174345ea5e2ea9099287ad43cd2b',1,'franka']]], + ['cartesianpose_35',['CartesianPose',['../classfranka_1_1CartesianPose.html#a5559a53a898f9b369b1df9d51f9351b5',1,'franka::CartesianPose::CartesianPose(const std::array< double, 16 > &cartesian_pose) noexcept'],['../classfranka_1_1CartesianPose.html#a17272cb33af9aa4b726fa96b31cf0101',1,'franka::CartesianPose::CartesianPose(const std::array< double, 16 > &cartesian_pose, const std::array< double, 2 > &elbow) noexcept'],['../classfranka_1_1CartesianPose.html#a70b6460e98bc763a49c53accd48d54a2',1,'franka::CartesianPose::CartesianPose(std::initializer_list< double > cartesian_pose)'],['../classfranka_1_1CartesianPose.html#ab7fb1dfd7cdb89c0caebab95c669ba49',1,'franka::CartesianPose::CartesianPose(std::initializer_list< double > cartesian_pose, std::initializer_list< double > elbow)'],['../classfranka_1_1CartesianPose.html',1,'franka::CartesianPose']]], + ['cartesianvelocities_36',['CartesianVelocities',['../classfranka_1_1CartesianVelocities.html#a95f6feec3539ed9f96d555447717eb72',1,'franka::CartesianVelocities::CartesianVelocities(const std::array< double, 6 > &cartesian_velocities, const std::array< double, 2 > &elbow) noexcept'],['../classfranka_1_1CartesianVelocities.html#a39c4b06c315c963460e24324de8ad079',1,'franka::CartesianVelocities::CartesianVelocities(std::initializer_list< double > cartesian_velocities)'],['../classfranka_1_1CartesianVelocities.html#aec434afa3f92e462ad3ab4766d3456a4',1,'franka::CartesianVelocities::CartesianVelocities(std::initializer_list< double > cartesian_velocities, std::initializer_list< double > elbow)'],['../classfranka_1_1CartesianVelocities.html#a713380954e1f10c1be3033b95ca00657',1,'franka::CartesianVelocities::CartesianVelocities(const std::array< double, 6 > &cartesian_velocities) noexcept'],['../classfranka_1_1CartesianVelocities.html',1,'franka::CartesianVelocities']]], + ['checkelbow_37',['checkElbow',['../control__tools_8h.html#add0cd2cd1401ac0b2393a84ca1577cde',1,'franka']]], + ['checkfinite_38',['checkFinite',['../control__tools_8h.html#a80d02c11ba41e5973ee76624bf1d4466',1,'franka']]], + ['checkmatrix_39',['checkMatrix',['../control__tools_8h.html#ab38ee604eecfedfb591ddb8327805ea4',1,'franka']]], + ['command_40',['command',['../structfranka_1_1Record.html#a8106f2ba9c2cf5ec7cbcf914c4c99e9c',1,'franka::Record']]], + ['commandexception_41',['CommandException',['../structfranka_1_1CommandException.html',1,'franka']]], + ['communication_5fconstraints_5fviolation_42',['communication_constraints_violation',['../structfranka_1_1Errors.html#a4d17af86c1ebb698c218796fa15f9bd7',1,'franka::Errors']]], + ['computelowerlimitsjointvelocity_43',['computeLowerLimitsJointVelocity',['../rate__limiting_8h.html#a75fe6c28325d7631f7bdb6c2b388b268',1,'franka']]], + ['computeupperlimitsjointvelocity_44',['computeUpperLimitsJointVelocity',['../rate__limiting_8h.html#a3a025c3c8f71f59627fe4f7e801021ac',1,'franka']]], + ['control_45',['control',['../classfranka_1_1Robot.html#a4ce9fd531f97c8cc943dd2479298a55f',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#aeb276d0a0e55f032841976de7db86f5a',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a7fef8f6418cff168f680ac7c61a6b5cd',1,'franka::Robot::control(std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a6ba6193e52178899dc8c6a34aa4c537c',1,'franka::Robot::control(std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#adce4add23b47befadccd30e3dbe9f2f4',1,'franka::Robot::control(std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a2176c99664b83bb394f0b2dfd416a8ee',1,'franka::Robot::control(std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a76e8b7a9c7e2b874c3e300ba7cdeb8ca',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a4b625b781d388f3379e0961c724239d5',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a0d5effba5daff2fee123802bbd5f95d1',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)']]], + ['control_5fcommand_5fsuccess_5frate_46',['control_command_success_rate',['../structfranka_1_1RobotState.html#af208572613a6afcdc61a24970c71fa28',1,'franka::RobotState']]], + ['control_5ffinished_47',['control_finished',['../classfranka_1_1ActiveControl.html#afa521707548926e9d1e38e4b83496db2',1,'franka::ActiveControl']]], + ['control_5flock_48',['control_lock',['../classfranka_1_1ActiveControl.html#aed53605877b237435581e36f4c0b34a4',1,'franka::ActiveControl']]], + ['control_5ftools_2eh_49',['control_tools.h',['../control__tools_8h.html',1,'']]], + ['control_5ftypes_2eh_50',['control_types.h',['../control__types_8h.html',1,'']]], + ['controlexception_51',['ControlException',['../structfranka_1_1ControlException.html#a2efb9628eef80a3819031dbf2e2cb518',1,'franka::ControlException::ControlException()'],['../structfranka_1_1ControlException.html',1,'franka::ControlException']]], + ['controller_5ftorque_5fdiscontinuity_52',['controller_torque_discontinuity',['../structfranka_1_1Errors.html#af40d93759ace9ee6026208110692a732',1,'franka::Errors']]], + ['controllermode_53',['ControllerMode',['../control__types_8h.html#a3e20bc77587e2c0c53598753e3f4816b',1,'franka']]], + ['coriolis_54',['coriolis',['../classfranka_1_1RobotModel.html#ae8b6b42f32ffb0ca654e76080c8ee347',1,'franka::RobotModel::coriolis()'],['../classRobotModelBase.html#a45226fbc547a27d5e7cff8a78e9bd0b4',1,'RobotModelBase::coriolis()'],['../classfranka_1_1Model.html#a3445ad932ddda2e3540768af9b7b4852',1,'franka::Model::coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept'],['../classfranka_1_1Model.html#a91424f181a93bb47bda6af2d3567c65c',1,'franka::Model::coriolis(const franka::RobotState &robot_state) const noexcept']]], + ['current_5ferrors_55',['current_errors',['../structfranka_1_1RobotState.html#abc5515f7a27f5de82396ea792a5ecb48',1,'franka::RobotState']]] +]; diff --git a/search/all_3.html b/search/all_3.html new file mode 100644 index 00000000..39767b85 --- /dev/null +++ b/search/all_3.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_3.js b/search/all_3.js new file mode 100644 index 00000000..636e3cba --- /dev/null +++ b/search/all_3.js @@ -0,0 +1,14 @@ +var searchData= +[ + ['ddelbow_5fc_56',['ddelbow_c',['../structfranka_1_1RobotState.html#a1e5b6caf84249b1129491dbbcb1fc2e6',1,'franka::RobotState']]], + ['ddq_5fd_57',['ddq_d',['../structfranka_1_1RobotState.html#a6251e748cf72f4b86bcfdcb97d77ace2',1,'franka::RobotState']]], + ['delbow_5fc_58',['delbow_c',['../structfranka_1_1RobotState.html#a57c2c145e9f79010adf23085b8a9c5ad',1,'franka::RobotState']]], + ['device_5fstatus_59',['device_status',['../structfranka_1_1VacuumGripperState.html#ab44560b09c4a959c06ddafbd7f21da02',1,'franka::VacuumGripperState']]], + ['dq_60',['dq',['../classfranka_1_1JointVelocities.html#a14fddb6fe7a7c4034dc82c283de8c2d3',1,'franka::JointVelocities::dq()'],['../structfranka_1_1RobotState.html#af372a0081d72bc7b4fe873f99c7b2d8c',1,'franka::RobotState::dq()']]], + ['dq_5fd_61',['dq_d',['../structfranka_1_1RobotState.html#aed294a088be27b927be9575a18bec949',1,'franka::RobotState']]], + ['dropoff_62',['dropOff',['../classfranka_1_1VacuumGripper.html#a04645348e97b946a788205c8b1168cac',1,'franka::VacuumGripper']]], + ['dtau_5fj_63',['dtau_J',['../structfranka_1_1RobotState.html#ae6b0d4ee0d7b36240a2165e6ded6f4b9',1,'franka::RobotState']]], + ['dtheta_64',['dtheta',['../structfranka_1_1RobotState.html#a271db0a55dd346715ed8a0daf3f8887c',1,'franka::RobotState']]], + ['duration_65',['Duration',['../classfranka_1_1Duration.html#af721da321423772b4ce7ff11280d38d5',1,'franka::Duration::Duration() noexcept'],['../classfranka_1_1Duration.html#a46f0cea3e05c27cdaaba5ff25e0e6cd6',1,'franka::Duration::Duration(uint64_t milliseconds) noexcept'],['../classfranka_1_1Duration.html#a389dfef50f34e9cc5be69838fbdafba7',1,'franka::Duration::Duration(std::chrono::duration< uint64_t, std::milli > duration) noexcept'],['../classfranka_1_1Duration.html#a886575e716b45e85de1bb78def2eb133',1,'franka::Duration::Duration(const Duration &)=default'],['../classfranka_1_1Duration.html',1,'franka::Duration']]], + ['duration_2eh_66',['duration.h',['../duration_8h.html',1,'']]] +]; diff --git a/search/all_4.html b/search/all_4.html new file mode 100644 index 00000000..fc40463c --- /dev/null +++ b/search/all_4.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_4.js b/search/all_4.js new file mode 100644 index 00000000..31a0e066 --- /dev/null +++ b/search/all_4.js @@ -0,0 +1,12 @@ +var searchData= +[ + ['ee_5ft_5fk_67',['EE_T_K',['../structfranka_1_1RobotState.html#aeb78a3b4b76d4f57b9898cbea3a0f7aa',1,'franka::RobotState']]], + ['elbow_68',['elbow',['../classfranka_1_1CartesianPose.html#abef660743df9cf94d11c556d9c3d25be',1,'franka::CartesianPose::elbow()'],['../classfranka_1_1CartesianVelocities.html#a6419df1399d3dfab79b1654b94ced344',1,'franka::CartesianVelocities::elbow()'],['../structfranka_1_1RobotState.html#a43485841c427d70e7f36a912cc3116d1',1,'franka::RobotState::elbow()']]], + ['elbow_5fc_69',['elbow_c',['../structfranka_1_1RobotState.html#a16cfc844894e8b5b1ad829be529962f0',1,'franka::RobotState']]], + ['elbow_5fd_70',['elbow_d',['../structfranka_1_1RobotState.html#a295dada05d8588fc3c19a74fd427dcc0',1,'franka::RobotState']]], + ['errors_71',['Errors',['../structfranka_1_1Errors.html#aedd6b6af230c01b6f106b5050b29d9ae',1,'franka::Errors::Errors()'],['../structfranka_1_1Errors.html#a4548a72089cc6d61c9249a1b8f4cc480',1,'franka::Errors::Errors(const Errors &other)'],['../structfranka_1_1Errors.html#adffc6f8b2235e566c4a43ce69a86634e',1,'franka::Errors::Errors(const std::array< bool, 41 > &errors)'],['../structfranka_1_1Errors.html',1,'franka::Errors']]], + ['errors_2eh_72',['errors.h',['../errors_8h.html',1,'']]], + ['examples_5fcommon_2eh_73',['examples_common.h',['../examples__common_8h.html',1,'']]], + ['exception_74',['Exception',['../structfranka_1_1Exception.html',1,'franka']]], + ['exception_2eh_75',['exception.h',['../exception_8h.html',1,'']]] +]; diff --git a/search/all_5.html b/search/all_5.html new file mode 100644 index 00000000..9dd9344b --- /dev/null +++ b/search/all_5.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_5.js b/search/all_5.js new file mode 100644 index 00000000..b6f342be --- /dev/null +++ b/search/all_5.js @@ -0,0 +1,12 @@ +var searchData= +[ + ['f_5ft_5fee_76',['F_T_EE',['../structfranka_1_1RobotState.html#a705b85049fef747008b0eba8284c8057',1,'franka::RobotState']]], + ['f_5ft_5fne_77',['F_T_NE',['../structfranka_1_1RobotState.html#a88142795c453775c360e18d8a6570d15',1,'franka::RobotState']]], + ['f_5fx_5fcee_78',['F_x_Cee',['../structfranka_1_1RobotState.html#a907c4561d8f1c1a2af7980cf58ceb112',1,'franka::RobotState']]], + ['f_5fx_5fcload_79',['F_x_Cload',['../structfranka_1_1RobotState.html#a48e921e6215ad32f36e424b4d7b66a89',1,'franka::RobotState']]], + ['f_5fx_5fctotal_80',['F_x_Ctotal',['../structfranka_1_1RobotState.html#a72ee7362018e3c9e95e3c41e857bfd8d',1,'franka::RobotState']]], + ['finishable_81',['Finishable',['../structfranka_1_1Finishable.html',1,'franka']]], + ['force_5fcontrol_5fsafety_5fviolation_82',['force_control_safety_violation',['../structfranka_1_1Errors.html#ae7b19674da28b11ba970c30c7d800923',1,'franka::Errors']]], + ['force_5fcontroller_5fdesired_5fforce_5ftolerance_5fviolation_83',['force_controller_desired_force_tolerance_violation',['../structfranka_1_1Errors.html#ae474f20a64b2585dbe6496966dddff0a',1,'franka::Errors']]], + ['frame_84',['Frame',['../model_8h.html#a00b729ddce916481d3f0d10febec4f5b',1,'franka']]] +]; diff --git a/search/all_6.html b/search/all_6.html new file mode 100644 index 00000000..f1e516d7 --- /dev/null +++ b/search/all_6.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_6.js b/search/all_6.js new file mode 100644 index 00000000..5c8458c6 --- /dev/null +++ b/search/all_6.js @@ -0,0 +1,10 @@ +var searchData= +[ + ['getrobotmodel_85',['getRobotModel',['../classfranka_1_1Robot.html#a54565ca0eb7b58727f88a8dcbf2f98ab',1,'franka::Robot']]], + ['grasp_86',['grasp',['../classfranka_1_1Gripper.html#abff6a03a6c75b9079bd4b9b5ca380254',1,'franka::Gripper']]], + ['gravity_87',['gravity',['../classfranka_1_1Model.html#a9b28a648cf413297d80f383e62363ab9',1,'franka::Model::gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexcept'],['../classfranka_1_1Model.html#a76a94e1ddb45cf1cdded25be4cf2dcae',1,'franka::Model::gravity(const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const noexcept'],['../classfranka_1_1Model.html#a983611785e894e1cd1f07a2df97ddbdd',1,'franka::Model::gravity(const franka::RobotState &robot_state) const noexcept'],['../classfranka_1_1RobotModel.html#a027d8e2e713b66cdbaf17201a30236f1',1,'franka::RobotModel::gravity()'],['../classRobotModelBase.html#ace835cdef4ae60d965c9faf57c3914e1',1,'RobotModelBase::gravity()']]], + ['gripper_88',['Gripper',['../classfranka_1_1Gripper.html',1,'franka::Gripper'],['../classfranka_1_1Gripper.html#a02b30632b08001592c62d3563561afc5',1,'franka::Gripper::Gripper(const std::string &franka_address)'],['../classfranka_1_1Gripper.html#aa045ea81b36f22420f9bc6f2a256a4f0',1,'franka::Gripper::Gripper(Gripper &&gripper) noexcept']]], + ['gripper_2eh_89',['gripper.h',['../gripper_8h.html',1,'']]], + ['gripper_5fstate_2eh_90',['gripper_state.h',['../gripper__state_8h.html',1,'']]], + ['gripperstate_91',['GripperState',['../structfranka_1_1GripperState.html',1,'franka']]] +]; diff --git a/search/all_7.html b/search/all_7.html new file mode 100644 index 00000000..8ddbf6c8 --- /dev/null +++ b/search/all_7.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_7.js b/search/all_7.js new file mode 100644 index 00000000..fbb80051 --- /dev/null +++ b/search/all_7.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['haselbow_92',['hasElbow',['../classfranka_1_1CartesianPose.html#a5fa9f47dbf73ab45f671d89e11f89ccf',1,'franka::CartesianPose::hasElbow()'],['../classfranka_1_1CartesianVelocities.html#a51a41893b10250982597fe367abb2ca6',1,'franka::CartesianVelocities::hasElbow()']]], + ['hasrealtimekernel_93',['hasRealtimeKernel',['../control__tools_8h.html#ad165a74da105c78586c0cd4c1ed57bd2',1,'franka']]], + ['homing_94',['homing',['../classfranka_1_1Gripper.html#aef356f93a4c3b9d6b2532c29126d478c',1,'franka::Gripper']]] +]; diff --git a/search/all_8.html b/search/all_8.html new file mode 100644 index 00000000..83c55ae2 --- /dev/null +++ b/search/all_8.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_8.js b/search/all_8.js new file mode 100644 index 00000000..e43b89b4 --- /dev/null +++ b/search/all_8.js @@ -0,0 +1,13 @@ +var searchData= +[ + ['i_5fee_95',['I_ee',['../structfranka_1_1RobotState.html#a74cee1beb5d400694133deea2846e611',1,'franka::RobotState']]], + ['i_5fload_96',['I_load',['../structfranka_1_1RobotState.html#a5b194153497eff98049681f852118f82',1,'franka::RobotState']]], + ['i_5ftotal_97',['I_total',['../structfranka_1_1RobotState.html#ad9120ae7b7613e77df8c1c3eba8fb033',1,'franka::RobotState']]], + ['in_5fcontrol_5frange_98',['in_control_range',['../structfranka_1_1VacuumGripperState.html#a70c1b14b10c2a79511fcada258c7e0ba',1,'franka::VacuumGripperState']]], + ['incompatibleversionexception_99',['IncompatibleVersionException',['../structfranka_1_1IncompatibleVersionException.html',1,'franka::IncompatibleVersionException'],['../structfranka_1_1IncompatibleVersionException.html#a518f40d994ed7e970c6f7fdafb673239',1,'franka::IncompatibleVersionException::IncompatibleVersionException()']]], + ['instability_5fdetected_100',['instability_detected',['../structfranka_1_1Errors.html#aebb701987262097687d21b3cf1bc8930',1,'franka::Errors']]], + ['invalidoperationexception_101',['InvalidOperationException',['../structfranka_1_1InvalidOperationException.html',1,'franka']]], + ['is_5fgrasped_102',['is_grasped',['../structfranka_1_1GripperState.html#aa65b46313e740454ead9c9ea27e7bf8d',1,'franka::GripperState']]], + ['ishomogeneoustransformation_103',['isHomogeneousTransformation',['../control__tools_8h.html#ad81c99e8af3f2536ae3c6ec1ce8dce1e',1,'franka']]], + ['isvalidelbow_104',['isValidElbow',['../control__tools_8h.html#a4eda3eda0514fabf6d630a6d8c0373a0',1,'franka']]] +]; diff --git a/search/all_9.html b/search/all_9.html new file mode 100644 index 00000000..1e263c13 --- /dev/null +++ b/search/all_9.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_9.js b/search/all_9.js new file mode 100644 index 00000000..e2d659dc --- /dev/null +++ b/search/all_9.js @@ -0,0 +1,20 @@ +var searchData= +[ + ['joint_5fcollision_105',['joint_collision',['../structfranka_1_1RobotState.html#a38757bafd4dd8e138410de1dca0c36f8',1,'franka::RobotState']]], + ['joint_5fcontact_106',['joint_contact',['../structfranka_1_1RobotState.html#a7243c652a8efe58c343a0d1252302fa4',1,'franka::RobotState']]], + ['joint_5fmotion_5fgenerator_5facceleration_5fdiscontinuity_107',['joint_motion_generator_acceleration_discontinuity',['../structfranka_1_1Errors.html#a633195adca91f5ecaf1506da12f3311f',1,'franka::Errors']]], + ['joint_5fmotion_5fgenerator_5fposition_5flimits_5fviolation_108',['joint_motion_generator_position_limits_violation',['../structfranka_1_1Errors.html#a9536ad072868b90525c56143cbb956ef',1,'franka::Errors']]], + ['joint_5fmotion_5fgenerator_5fvelocity_5fdiscontinuity_109',['joint_motion_generator_velocity_discontinuity',['../structfranka_1_1Errors.html#abd6da8e6a32d817a7b4848a24efd9379',1,'franka::Errors']]], + ['joint_5fmotion_5fgenerator_5fvelocity_5flimits_5fviolation_110',['joint_motion_generator_velocity_limits_violation',['../structfranka_1_1Errors.html#ae211638df9b0e23905c8a9d36e249207',1,'franka::Errors']]], + ['joint_5fmove_5fin_5fwrong_5fdirection_111',['joint_move_in_wrong_direction',['../structfranka_1_1Errors.html#a7d3a6480cbe572fd46e579b43732edc9',1,'franka::Errors']]], + ['joint_5fp2p_5finsufficient_5ftorque_5ffor_5fplanning_112',['joint_p2p_insufficient_torque_for_planning',['../structfranka_1_1Errors.html#a1c78be870253b510a4516acf14c2d3e3',1,'franka::Errors']]], + ['joint_5fposition_5flimits_5fviolation_113',['joint_position_limits_violation',['../structfranka_1_1Errors.html#a44ba0d45e52639280d32cf447f967e29',1,'franka::Errors']]], + ['joint_5fposition_5fmotion_5fgenerator_5fstart_5fpose_5finvalid_114',['joint_position_motion_generator_start_pose_invalid',['../structfranka_1_1Errors.html#a7af91cbf61dc79304bff3ffadc51ea86',1,'franka::Errors']]], + ['joint_5fpositions_115',['joint_positions',['../structfranka_1_1RobotCommand.html#a086afcec596eae5284b6c39dc1452280',1,'franka::RobotCommand']]], + ['joint_5freflex_116',['joint_reflex',['../structfranka_1_1Errors.html#afb0928680c586e73d4e2cd4b42c7fe48',1,'franka::Errors']]], + ['joint_5fvelocities_117',['joint_velocities',['../structfranka_1_1RobotCommand.html#a049657cf2bbbb53d6ffa5581721e7b71',1,'franka::RobotCommand']]], + ['joint_5fvelocity_5fviolation_118',['joint_velocity_violation',['../structfranka_1_1Errors.html#a803ac4acbc26350602ea2eb02b7b30c4',1,'franka::Errors']]], + ['joint_5fvia_5fmotion_5fgenerator_5fplanning_5fjoint_5flimit_5fviolation_119',['joint_via_motion_generator_planning_joint_limit_violation',['../structfranka_1_1Errors.html#aef3c74f48978545187ee2dc3a96db1c8',1,'franka::Errors']]], + ['jointpositions_120',['JointPositions',['../classfranka_1_1JointPositions.html',1,'franka::JointPositions'],['../classfranka_1_1JointPositions.html#a57bc9d7e033493b1182333276af5ce84',1,'franka::JointPositions::JointPositions(const std::array< double, 7 > &joint_positions) noexcept'],['../classfranka_1_1JointPositions.html#a1e2006bccc9de89d8eb1a4d1c4da2fb8',1,'franka::JointPositions::JointPositions(std::initializer_list< double > joint_positions)']]], + ['jointvelocities_121',['JointVelocities',['../classfranka_1_1JointVelocities.html',1,'franka::JointVelocities'],['../classfranka_1_1JointVelocities.html#a1130f851055de3b7ebe9e6fbac960826',1,'franka::JointVelocities::JointVelocities(const std::array< double, 7 > &joint_velocities) noexcept'],['../classfranka_1_1JointVelocities.html#aed384fad8e302638c2e5baea6378c2d2',1,'franka::JointVelocities::JointVelocities(std::initializer_list< double > joint_velocities)']]] +]; diff --git a/search/all_a.html b/search/all_a.html new file mode 100644 index 00000000..3a6cac10 --- /dev/null +++ b/search/all_a.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_a.js b/search/all_a.js new file mode 100644 index 00000000..e4defc51 --- /dev/null +++ b/search/all_a.js @@ -0,0 +1,28 @@ +var searchData= +[ + ['k_5ff_5fext_5fhat_5fk_122',['K_F_ext_hat_K',['../structfranka_1_1RobotState.html#a96267d443c05fcc58d7ac32f63912649',1,'franka::RobotState']]], + ['kdefaultcutofffrequency_123',['kDefaultCutoffFrequency',['../lowpass__filter_8h.html#ad8e3b7da346e03181ab5ac138a4171d4',1,'franka']]], + ['kdeltat_124',['kDeltaT',['../rate__limiting_8h.html#a1e207a0d5a6e90c1e1a78e6e1057120a',1,'franka']]], + ['kfactorcartesianrotationposeinterface_125',['kFactorCartesianRotationPoseInterface',['../rate__limiting_8h.html#a19166d1a64c5a84f80b4ed3aa0bfb3a0',1,'franka']]], + ['kgreen_126',['kGreen',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611a1299e6e2ec6371a79385cd3a862f7cc9',1,'franka']]], + ['kjointvelocitylimitstolerance_127',['kJointVelocityLimitsTolerance',['../rate__limiting_8h.html#a39b6d9504e2844d289f834471994d889',1,'franka']]], + ['klimiteps_128',['kLimitEps',['../rate__limiting_8h.html#aad1f9b575274830b8da9e638559d424b',1,'franka']]], + ['kmaxcutofffrequency_129',['kMaxCutoffFrequency',['../lowpass__filter_8h.html#adb10b364af8deb9e17d9bcc1ff2695be',1,'franka']]], + ['kmaxelbowacceleration_130',['kMaxElbowAcceleration',['../rate__limiting_8h.html#af365e574ad7b1580ce15e30dd909b3ba',1,'franka']]], + ['kmaxelbowjerk_131',['kMaxElbowJerk',['../rate__limiting_8h.html#adc70178204d4da073c78de777a2dff74',1,'franka']]], + ['kmaxelbowvelocity_132',['kMaxElbowVelocity',['../rate__limiting_8h.html#a2896b2e0c8bd96f9ee242c1203ac3483',1,'franka']]], + ['kmaxjointacceleration_133',['kMaxJointAcceleration',['../rate__limiting_8h.html#a826ecf0b7d214df69c1ee416d3e66b93',1,'franka']]], + ['kmaxjointjerk_134',['kMaxJointJerk',['../rate__limiting_8h.html#a600a21a6151ff2eee38294293dd8aeec',1,'franka']]], + ['kmaxrotationalacceleration_135',['kMaxRotationalAcceleration',['../rate__limiting_8h.html#a5e3d5c95ba72f9660f17f8ebf1e0aa2e',1,'franka']]], + ['kmaxrotationaljerk_136',['kMaxRotationalJerk',['../rate__limiting_8h.html#a259520ce1b6b5b85a88d05262286820d',1,'franka']]], + ['kmaxrotationalvelocity_137',['kMaxRotationalVelocity',['../rate__limiting_8h.html#aafb1f5ef8f8a7abd546edea498c18b45',1,'franka']]], + ['kmaxtorquerate_138',['kMaxTorqueRate',['../rate__limiting_8h.html#a6c1a0e9a5e1f375d2aad61edac907d4e',1,'franka']]], + ['kmaxtranslationalacceleration_139',['kMaxTranslationalAcceleration',['../rate__limiting_8h.html#a3803b1a54ba526ccaa4fa0d15446f3db',1,'franka']]], + ['kmaxtranslationaljerk_140',['kMaxTranslationalJerk',['../rate__limiting_8h.html#a46b8f11959ed3f731a0914f524af8e69',1,'franka']]], + ['kmaxtranslationalvelocity_141',['kMaxTranslationalVelocity',['../rate__limiting_8h.html#a857e1e5e18d688ec7095264a629bf474',1,'franka']]], + ['knormeps_142',['kNormEps',['../rate__limiting_8h.html#a420d72830a872ef375d9d6cbb1c439b5',1,'franka']]], + ['korange_143',['kOrange',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611a11e1aa07606f098e5025e37830a1b22e',1,'franka']]], + ['kred_144',['kRed',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611afb0136b923af8c04b31a9d1b5e989acf',1,'franka']]], + ['ktolnumberpacketslost_145',['kTolNumberPacketsLost',['../rate__limiting_8h.html#a664b546834ceecd4e3220ffa92f1172c',1,'franka']]], + ['kyellow_146',['kYellow',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611a4c6c30a3642462190739bb7f13af9c7b',1,'franka']]] +]; diff --git a/search/all_b.html b/search/all_b.html new file mode 100644 index 00000000..130deb4e --- /dev/null +++ b/search/all_b.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_b.js b/search/all_b.js new file mode 100644 index 00000000..cb4ac48f --- /dev/null +++ b/search/all_b.js @@ -0,0 +1,14 @@ +var searchData= +[ + ['last_5fmotion_5ferrors_147',['last_motion_errors',['../structfranka_1_1RobotState.html#a06d7019f85339409e932dc086b7a260b',1,'franka::RobotState']]], + ['last_5fread_5faccess_148',['last_read_access',['../classfranka_1_1ActiveControl.html#a226304deac8032ed6c8428caa60c9fb4',1,'franka::ActiveControl']]], + ['libfranka_3a_20c_2b_2b_20library_20for_20franka_20robotics_20research_20robots_149',['libfranka: C++ library for Franka Robotics research robots',['../index.html',1,'']]], + ['library_5fversion_150',['library_version',['../structfranka_1_1IncompatibleVersionException.html#a81e6d7f01965ed7ee34f83dc3883ad01',1,'franka::IncompatibleVersionException']]], + ['limitrate_151',['limitRate',['../rate__limiting_8h.html#ae425f551c62b289a93ad471f94f87b7c',1,'franka::limitRate(double upper_limits_velocity, double lower_limits_velocity, double max_acceleration, double max_jerk, double commanded_velocity, double last_commanded_velocity, double last_commanded_acceleration)'],['../rate__limiting_8h.html#a9288f438fcfc1aedf7e0b52aa95b23ba',1,'franka::limitRate(double max_translational_velocity, double max_translational_acceleration, double max_translational_jerk, double max_rotational_velocity, double max_rotational_acceleration, double max_rotational_jerk, const std::array< double, 16 > &O_T_EE_c, const std::array< double, 16 > &last_O_T_EE_c, const std::array< double, 6 > &last_O_dP_EE_c, const std::array< double, 6 > &last_O_ddP_EE_c)'],['../rate__limiting_8h.html#ad3e0243f9be5335ae3d04f87852dfccb',1,'franka::limitRate(double max_translational_velocity, double max_translational_acceleration, double max_translational_jerk, double max_rotational_velocity, double max_rotational_acceleration, double max_rotational_jerk, const std::array< double, 6 > &O_dP_EE_c, const std::array< double, 6 > &last_O_dP_EE_c, const std::array< double, 6 > &last_O_ddP_EE_c)'],['../rate__limiting_8h.html#aaaa22e0873d0630465e506ddc877083f',1,'franka::limitRate(const std::array< double, 7 > &upper_limits_velocity, const std::array< double, 7 > &lower_limits_velocity, const std::array< double, 7 > &max_acceleration, const std::array< double, 7 > &max_jerk, const std::array< double, 7 > &commanded_positions, const std::array< double, 7 > &last_commanded_positions, const std::array< double, 7 > &last_commanded_velocities, const std::array< double, 7 > &last_commanded_accelerations)'],['../rate__limiting_8h.html#a62ebac6ebbef784d44135855a899abef',1,'franka::limitRate(const std::array< double, 7 > &upper_limits_velocity, const std::array< double, 7 > &lower_limits_velocity, const std::array< double, 7 > &max_acceleration, const std::array< double, 7 > &max_jerk, const std::array< double, 7 > &commanded_velocities, const std::array< double, 7 > &last_commanded_velocities, const std::array< double, 7 > &last_commanded_accelerations)'],['../rate__limiting_8h.html#afacb3c087c76dded71874eaa7862b05d',1,'franka::limitRate(double upper_limits_velocity, double lower_limits_velocity, double max_acceleration, double max_jerk, double commanded_position, double last_commanded_position, double last_commanded_velocity, double last_commanded_acceleration)'],['../rate__limiting_8h.html#aea6895d6bf209a86319c6cd5180e4b60',1,'franka::limitRate(const std::array< double, 7 > &max_derivatives, const std::array< double, 7 > &commanded_values, const std::array< double, 7 > &last_commanded_values)']]], + ['loadmodel_152',['loadModel',['../classfranka_1_1Robot.html#a2da598c539469827409ac7e3bb61d5da',1,'franka::Robot']]], + ['log_153',['log',['../structfranka_1_1ControlException.html#ae57f0ac0a9aa195057af1f1cc712b41e',1,'franka::ControlException']]], + ['log_2eh_154',['log.h',['../log_8h.html',1,'']]], + ['logtocsv_155',['logToCSV',['../log_8h.html#a01fbdb37b0e6beb04ba108d5f5024fd9',1,'franka']]], + ['lowpass_5ffilter_2eh_156',['lowpass_filter.h',['../lowpass__filter_8h.html',1,'']]], + ['lowpassfilter_157',['lowpassFilter',['../lowpass__filter_8h.html#a94c21b0e87afce0147a9cd6025c239ca',1,'franka']]] +]; diff --git a/search/all_c.html b/search/all_c.html new file mode 100644 index 00000000..3dd5af06 --- /dev/null +++ b/search/all_c.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_c.js b/search/all_c.js new file mode 100644 index 00000000..1c12c259 --- /dev/null +++ b/search/all_c.js @@ -0,0 +1,18 @@ +var searchData= +[ + ['m_5fee_158',['m_ee',['../structfranka_1_1RobotState.html#af982a16246e33c1495ec02972a36bce3',1,'franka::RobotState']]], + ['m_5fload_159',['m_load',['../structfranka_1_1RobotState.html#a99ea4ab9c5a42a5c17365ed8fd730cd1',1,'franka::RobotState']]], + ['m_5ftotal_160',['m_total',['../structfranka_1_1RobotState.html#a87880d4693c8f576ebdabf00f4d4f981',1,'franka::RobotState']]], + ['mass_161',['mass',['../classfranka_1_1Model.html#ad5f6156064bc18e42fc0b6d2f36b2006',1,'franka::Model::mass(const franka::RobotState &robot_state) const noexcept'],['../classfranka_1_1Model.html#a61c3a8968e927c8629f1d549d20aaf85',1,'franka::Model::mass(const std::array< double, 7 > &q, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept'],['../classfranka_1_1RobotModel.html#abbff56dc8a77bb3bead7efb7f891f8ed',1,'franka::RobotModel::mass()'],['../classRobotModelBase.html#ad6205b8405cc76be5b3e8fe3a3a2c1f9',1,'RobotModelBase::mass()']]], + ['max_5fgoal_5fpose_5fdeviation_5fviolation_162',['max_goal_pose_deviation_violation',['../structfranka_1_1Errors.html#ac55d3624087e606cb4ffab121869d580',1,'franka::Errors']]], + ['max_5fpath_5fpose_5fdeviation_5fviolation_163',['max_path_pose_deviation_violation',['../structfranka_1_1Errors.html#ad90cffe703ca1b782007f3ba49da587c',1,'franka::Errors']]], + ['max_5fwidth_164',['max_width',['../structfranka_1_1GripperState.html#ab71a26356c2898c49609bf991843e166',1,'franka::GripperState']]], + ['model_165',['Model',['../classfranka_1_1Model.html',1,'franka::Model'],['../classfranka_1_1Model.html#a8b58ff37f62512aecdcd0e6aabfd9548',1,'franka::Model::Model(Model &&model) noexcept'],['../classfranka_1_1Model.html#a8bf08984ec15c041ff1cbbe870945b82',1,'franka::Model::Model(franka::Network &network, const std::string &urdf_model)'],['../classfranka_1_1Model.html#a8148cf270e52ad9e967d4651fc37d690',1,'franka::Model::Model(franka::Network &network, std::unique_ptr< RobotModelBase > robot_model)']]], + ['model_2eh_166',['model.h',['../model_8h.html',1,'']]], + ['modelexception_167',['ModelException',['../structfranka_1_1ModelException.html',1,'franka']]], + ['motion_5ffinished_168',['motion_finished',['../structfranka_1_1Finishable.html#a5d48028c0f912d4a089e6220d8715f7f',1,'franka::Finishable']]], + ['motion_5fid_169',['motion_id',['../classfranka_1_1ActiveControl.html#a0852a7d4b5a67df218440c2cc629f638',1,'franka::ActiveControl']]], + ['motionfinished_170',['MotionFinished',['../control__types_8h.html#a20791f7142d78bbbe3c957cc66a23ade',1,'franka::MotionFinished(Torques command) noexcept'],['../control__types_8h.html#a7f505509951b6568b08b3aec8ffb9098',1,'franka::MotionFinished(JointPositions command) noexcept'],['../control__types_8h.html#ab478c128d691a46c0ab85bbf3b5caac5',1,'franka::MotionFinished(JointVelocities command) noexcept'],['../control__types_8h.html#ab0b308e2a9348fd3eb5fd1d08db12dcf',1,'franka::MotionFinished(CartesianPose command) noexcept'],['../control__types_8h.html#a5898ad5e3bbc2682c24c0415bf7e9a95',1,'franka::MotionFinished(CartesianVelocities command) noexcept']]], + ['motiongenerator_171',['MotionGenerator',['../classMotionGenerator.html',1,'MotionGenerator'],['../classMotionGenerator.html#a23dd564a60401c539fb7f1bf63470894',1,'MotionGenerator::MotionGenerator()']]], + ['move_172',['move',['../classfranka_1_1Gripper.html#a047bc39267d66d6fb26c4c70669d68c2',1,'franka::Gripper']]] +]; diff --git a/search/all_d.html b/search/all_d.html new file mode 100644 index 00000000..af7f2f0f --- /dev/null +++ b/search/all_d.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_d.js b/search/all_d.js new file mode 100644 index 00000000..af99487c --- /dev/null +++ b/search/all_d.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['ne_5ft_5fee_173',['NE_T_EE',['../structfranka_1_1RobotState.html#ac53f1046fe758cfdda438a8e3ba08fff',1,'franka::RobotState']]], + ['networkexception_174',['NetworkException',['../structfranka_1_1NetworkException.html',1,'franka']]] +]; diff --git a/search/all_e.html b/search/all_e.html new file mode 100644 index 00000000..e25df423 --- /dev/null +++ b/search/all_e.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_e.js b/search/all_e.js new file mode 100644 index 00000000..293334bb --- /dev/null +++ b/search/all_e.js @@ -0,0 +1,35 @@ +var searchData= +[ + ['duration_3c_20uint64_5ft_2c_20std_3a_3amilli_20_3e_175',['duration< uint64_t, std::milli >',['../classfranka_1_1Duration.html#ae58e283f511f9de8ac7e145db5cac1cf',1,'franka::Duration']]], + ['o_5fddp_5fee_5fc_176',['O_ddP_EE_c',['../structfranka_1_1RobotState.html#ac8dfcf78ddbb27852484e921d6d66ca1',1,'franka::RobotState']]], + ['o_5fddp_5fo_177',['O_ddP_O',['../structfranka_1_1RobotState.html#ab24d7982942d316459fc35337dc38ecd',1,'franka::RobotState']]], + ['o_5fdp_5fee_178',['O_dP_EE',['../classfranka_1_1CartesianVelocities.html#ab7a42c7c1ee7109025aff5c43a56b398',1,'franka::CartesianVelocities']]], + ['o_5fdp_5fee_5fc_179',['O_dP_EE_c',['../structfranka_1_1RobotState.html#a4be112bd1a9a7d777a67aea4a18a8dcc',1,'franka::RobotState']]], + ['o_5fdp_5fee_5fd_180',['O_dP_EE_d',['../structfranka_1_1RobotState.html#a1e0a82b98534929c3061295d5761d607',1,'franka::RobotState']]], + ['o_5ff_5fext_5fhat_5fk_181',['O_F_ext_hat_K',['../structfranka_1_1RobotState.html#a5a830b4f9d6a3c2dc92e4a9cc6050493',1,'franka::RobotState']]], + ['o_5ft_5fee_182',['O_T_EE',['../classfranka_1_1CartesianPose.html#a406e53e3d8fe594a11888f516eb4bf7d',1,'franka::CartesianPose::O_T_EE()'],['../structfranka_1_1RobotState.html#a193781d47722b32925e0ea7ac415f442',1,'franka::RobotState::O_T_EE()']]], + ['o_5ft_5fee_5fc_183',['O_T_EE_c',['../structfranka_1_1RobotState.html#a395c48eff099419ea5d42eaf0870fc18',1,'franka::RobotState']]], + ['o_5ft_5fee_5fd_184',['O_T_EE_d',['../structfranka_1_1RobotState.html#a3e5b4b7687856e92d826044be7d15733',1,'franka::RobotState']]], + ['operator_20bool_185',['operator bool',['../structfranka_1_1Errors.html#a50cb6e50c1ce2b5ec281dcad83f1779e',1,'franka::Errors']]], + ['operator_21_3d_186',['operator!=',['../classfranka_1_1Duration.html#a61603353e39361af2f405c1df7097e84',1,'franka::Duration']]], + ['operator_25_187',['operator%',['../classfranka_1_1Duration.html#a5e472345c1bec29b645bee938932fdb1',1,'franka::Duration::operator%(const Duration &rhs) const noexcept'],['../classfranka_1_1Duration.html#af06ff91f24d881c479768c1bcbf31a1e',1,'franka::Duration::operator%(uint64_t rhs) const noexcept']]], + ['operator_25_3d_188',['operator%=',['../classfranka_1_1Duration.html#a97a6ea669877875ffc54c801ac0b152d',1,'franka::Duration::operator%=(const Duration &rhs) noexcept'],['../classfranka_1_1Duration.html#acd85bab22062a2258af83ac5b3b7a647',1,'franka::Duration::operator%=(uint64_t rhs) noexcept']]], + ['operator_28_29_189',['operator()',['../classMotionGenerator.html#aefd763e7c31c54b56404f33d2295fda9',1,'MotionGenerator']]], + ['operator_2a_190',['operator*',['../duration_8h.html#ab3a36a47682756845ef855994aadd7b6',1,'franka::operator*()'],['../classfranka_1_1Duration.html#a3eebc39550880fb2d23d45ba34d8acc5',1,'franka::Duration::operator*(uint64_t rhs) const noexcept']]], + ['operator_2a_3d_191',['operator*=',['../classfranka_1_1Duration.html#a73f971b2efb29a8ce663e8675d1ec09a',1,'franka::Duration']]], + ['operator_2b_192',['operator+',['../classfranka_1_1Duration.html#adb459e7bf5c6b02f9e72c808f5f30237',1,'franka::Duration']]], + ['operator_2b_2b_193',['operator++',['../model_8h.html#ae39c3a098fdb1bc9a097a262312454d0',1,'franka']]], + ['operator_2b_3d_194',['operator+=',['../classfranka_1_1Duration.html#ac55eb81937a12e736560bd856a8f23ae',1,'franka::Duration']]], + ['operator_2d_195',['operator-',['../classfranka_1_1Duration.html#a2a3bc1a8278b91bebe88d7498d410de9',1,'franka::Duration']]], + ['operator_2d_3d_196',['operator-=',['../classfranka_1_1Duration.html#acb24af377db86646918bcfb3e1e2ebe6',1,'franka::Duration']]], + ['operator_2f_197',['operator/',['../classfranka_1_1Duration.html#a15b7299198f36734b62ac98da1ef8c9c',1,'franka::Duration::operator/(uint64_t rhs) const noexcept'],['../classfranka_1_1Duration.html#a90c76be31b53e11f5761416a05d990be',1,'franka::Duration::operator/(const Duration &rhs) const noexcept']]], + ['operator_2f_3d_198',['operator/=',['../classfranka_1_1Duration.html#ac866dd8d0e8f2dbb92089dbd78418571',1,'franka::Duration']]], + ['operator_3c_199',['operator<',['../classfranka_1_1Duration.html#af1650b31c1226a447406fc243f4a2ac1',1,'franka::Duration']]], + ['operator_3c_3c_200',['operator<<',['../vacuum__gripper__state_8h.html#aa2caece6baf774e998b6dec6e803cf24',1,'franka::operator<<(std::ostream &ostream, const franka::VacuumGripperState &vacuum_gripper_state)'],['../robot__state_8h.html#a7d75ab63150979690a639f432c166755',1,'franka::operator<<(std::ostream &ostream, RobotMode robot_mode)'],['../robot__state_8h.html#aee38e87180cc96476d0f11335da29e20',1,'franka::operator<<(std::ostream &ostream, const franka::RobotState &robot_state)'],['../gripper__state_8h.html#ab66181a74d1d3b7e90ae3b424ee85f4f',1,'franka::operator<<(std::ostream &ostream, const franka::GripperState &gripper_state)'],['../errors_8h.html#ad1027058086c3c154f4bbc9cade1f197',1,'franka::operator<<(std::ostream &ostream, const Errors &errors)']]], + ['operator_3c_3d_201',['operator<=',['../classfranka_1_1Duration.html#ae4b9c8646fd50a2105d36f3848a5b949',1,'franka::Duration']]], + ['operator_3d_202',['operator=',['../classfranka_1_1VacuumGripper.html#a21d59603ac4deb8d9de5e074a57d080d',1,'franka::VacuumGripper::operator=()'],['../classfranka_1_1Robot.html#a35465b8497a7adbd277e70e98b7d97a7',1,'franka::Robot::operator=()'],['../classfranka_1_1Model.html#a625529a4c9aed7783c9c6e150dbba793',1,'franka::Model::operator=()'],['../classfranka_1_1Gripper.html#a3c99c6973f8951ca489c4177cfacb069',1,'franka::Gripper::operator=()'],['../structfranka_1_1Errors.html#a6fefa4083d79362080b79f3492fd4cb6',1,'franka::Errors::operator=()'],['../classfranka_1_1Duration.html#adf2fec0c87fe1668e42f217ab029df19',1,'franka::Duration::operator=(const Duration &)=default']]], + ['operator_3d_3d_203',['operator==',['../classfranka_1_1Duration.html#add0c7bcdfe51b563016236b223d74eae',1,'franka::Duration']]], + ['operator_3e_204',['operator>',['../classfranka_1_1Duration.html#a1702ec9121fe6cff1de533d116edcce0',1,'franka::Duration']]], + ['operator_3e_3d_205',['operator>=',['../classfranka_1_1Duration.html#a5bc498cf96d96f5908d6bd93eea491aa',1,'franka::Duration']]], + ['string_206',['string',['../structfranka_1_1Errors.html#a63ed1948f69db5be95a9c70107955d68',1,'franka::Errors']]] +]; diff --git a/search/all_f.html b/search/all_f.html new file mode 100644 index 00000000..b23da6ce --- /dev/null +++ b/search/all_f.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/all_f.js b/search/all_f.js new file mode 100644 index 00000000..35236d40 --- /dev/null +++ b/search/all_f.js @@ -0,0 +1,9 @@ +var searchData= +[ + ['part_5fdetached_207',['part_detached',['../structfranka_1_1VacuumGripperState.html#aa27a2b4b9d19bdcb059995a8121ba309',1,'franka::VacuumGripperState']]], + ['part_5fpresent_208',['part_present',['../structfranka_1_1VacuumGripperState.html#aeb5664ab2a9784c9e31ce5f67c914107',1,'franka::VacuumGripperState']]], + ['pose_209',['pose',['../classfranka_1_1Model.html#a593c39dae76a6801cdd2402c2a783157',1,'franka::Model::pose(Frame frame, const franka::RobotState &robot_state) const'],['../classfranka_1_1Model.html#adf4fdf0404c2acf783493f7e646a6281',1,'franka::Model::pose(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const']]], + ['power_5flimit_5fviolation_210',['power_limit_violation',['../structfranka_1_1Errors.html#a6c4d8cb1fb314567ebd07a6195b840f5',1,'franka::Errors']]], + ['productionsetupprofile_211',['ProductionSetupProfile',['../classfranka_1_1VacuumGripper.html#a0c81171a75c385780a82ff8dc36ef51e',1,'franka::VacuumGripper']]], + ['protocolexception_212',['ProtocolException',['../structfranka_1_1ProtocolException.html',1,'franka']]] +]; diff --git a/search/classes_0.html b/search/classes_0.html new file mode 100644 index 00000000..af8159ee --- /dev/null +++ b/search/classes_0.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_0.js b/search/classes_0.js new file mode 100644 index 00000000..7157bbca --- /dev/null +++ b/search/classes_0.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['activecontrol_277',['ActiveControl',['../classfranka_1_1ActiveControl.html',1,'franka']]], + ['activecontrolbase_278',['ActiveControlBase',['../classfranka_1_1ActiveControlBase.html',1,'franka']]], + ['activemotiongenerator_279',['ActiveMotionGenerator',['../classfranka_1_1ActiveMotionGenerator.html',1,'franka']]], + ['activetorquecontrol_280',['ActiveTorqueControl',['../classfranka_1_1ActiveTorqueControl.html',1,'franka']]] +]; diff --git a/search/classes_1.html b/search/classes_1.html new file mode 100644 index 00000000..576e9168 --- /dev/null +++ b/search/classes_1.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_1.js b/search/classes_1.js new file mode 100644 index 00000000..3a1a0473 --- /dev/null +++ b/search/classes_1.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['cartesianpose_281',['CartesianPose',['../classfranka_1_1CartesianPose.html',1,'franka']]], + ['cartesianvelocities_282',['CartesianVelocities',['../classfranka_1_1CartesianVelocities.html',1,'franka']]], + ['commandexception_283',['CommandException',['../structfranka_1_1CommandException.html',1,'franka']]], + ['controlexception_284',['ControlException',['../structfranka_1_1ControlException.html',1,'franka']]] +]; diff --git a/search/classes_2.html b/search/classes_2.html new file mode 100644 index 00000000..956405e5 --- /dev/null +++ b/search/classes_2.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_2.js b/search/classes_2.js new file mode 100644 index 00000000..e097eea7 --- /dev/null +++ b/search/classes_2.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['duration_285',['Duration',['../classfranka_1_1Duration.html',1,'franka']]] +]; diff --git a/search/classes_3.html b/search/classes_3.html new file mode 100644 index 00000000..d33343bc --- /dev/null +++ b/search/classes_3.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_3.js b/search/classes_3.js new file mode 100644 index 00000000..337403a6 --- /dev/null +++ b/search/classes_3.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['errors_286',['Errors',['../structfranka_1_1Errors.html',1,'franka']]], + ['exception_287',['Exception',['../structfranka_1_1Exception.html',1,'franka']]] +]; diff --git a/search/classes_4.html b/search/classes_4.html new file mode 100644 index 00000000..8430b07f --- /dev/null +++ b/search/classes_4.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_4.js b/search/classes_4.js new file mode 100644 index 00000000..199a9c40 --- /dev/null +++ b/search/classes_4.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['finishable_288',['Finishable',['../structfranka_1_1Finishable.html',1,'franka']]] +]; diff --git a/search/classes_5.html b/search/classes_5.html new file mode 100644 index 00000000..c2f1b767 --- /dev/null +++ b/search/classes_5.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_5.js b/search/classes_5.js new file mode 100644 index 00000000..48324c64 --- /dev/null +++ b/search/classes_5.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['gripper_289',['Gripper',['../classfranka_1_1Gripper.html',1,'franka']]], + ['gripperstate_290',['GripperState',['../structfranka_1_1GripperState.html',1,'franka']]] +]; diff --git a/search/classes_6.html b/search/classes_6.html new file mode 100644 index 00000000..e39847ce --- /dev/null +++ b/search/classes_6.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_6.js b/search/classes_6.js new file mode 100644 index 00000000..d0820079 --- /dev/null +++ b/search/classes_6.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['incompatibleversionexception_291',['IncompatibleVersionException',['../structfranka_1_1IncompatibleVersionException.html',1,'franka']]], + ['invalidoperationexception_292',['InvalidOperationException',['../structfranka_1_1InvalidOperationException.html',1,'franka']]] +]; diff --git a/search/classes_7.html b/search/classes_7.html new file mode 100644 index 00000000..a2c4d1a3 --- /dev/null +++ b/search/classes_7.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_7.js b/search/classes_7.js new file mode 100644 index 00000000..2129c123 --- /dev/null +++ b/search/classes_7.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['jointpositions_293',['JointPositions',['../classfranka_1_1JointPositions.html',1,'franka']]], + ['jointvelocities_294',['JointVelocities',['../classfranka_1_1JointVelocities.html',1,'franka']]] +]; diff --git a/search/classes_8.html b/search/classes_8.html new file mode 100644 index 00000000..17003e48 --- /dev/null +++ b/search/classes_8.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_8.js b/search/classes_8.js new file mode 100644 index 00000000..5af84710 --- /dev/null +++ b/search/classes_8.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['model_295',['Model',['../classfranka_1_1Model.html',1,'franka']]], + ['modelexception_296',['ModelException',['../structfranka_1_1ModelException.html',1,'franka']]], + ['motiongenerator_297',['MotionGenerator',['../classMotionGenerator.html',1,'']]] +]; diff --git a/search/classes_9.html b/search/classes_9.html new file mode 100644 index 00000000..b8afa8cb --- /dev/null +++ b/search/classes_9.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_9.js b/search/classes_9.js new file mode 100644 index 00000000..094dde50 --- /dev/null +++ b/search/classes_9.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['networkexception_298',['NetworkException',['../structfranka_1_1NetworkException.html',1,'franka']]] +]; diff --git a/search/classes_a.html b/search/classes_a.html new file mode 100644 index 00000000..6788af27 --- /dev/null +++ b/search/classes_a.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_a.js b/search/classes_a.js new file mode 100644 index 00000000..b001005b --- /dev/null +++ b/search/classes_a.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['protocolexception_299',['ProtocolException',['../structfranka_1_1ProtocolException.html',1,'franka']]] +]; diff --git a/search/classes_b.html b/search/classes_b.html new file mode 100644 index 00000000..3fcb4985 --- /dev/null +++ b/search/classes_b.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_b.js b/search/classes_b.js new file mode 100644 index 00000000..7d4d33a2 --- /dev/null +++ b/search/classes_b.js @@ -0,0 +1,10 @@ +var searchData= +[ + ['realtimeexception_300',['RealtimeException',['../structfranka_1_1RealtimeException.html',1,'franka']]], + ['record_301',['Record',['../structfranka_1_1Record.html',1,'franka']]], + ['robot_302',['Robot',['../classfranka_1_1Robot.html',1,'franka']]], + ['robotcommand_303',['RobotCommand',['../structfranka_1_1RobotCommand.html',1,'franka']]], + ['robotmodel_304',['RobotModel',['../classfranka_1_1RobotModel.html',1,'franka']]], + ['robotmodelbase_305',['RobotModelBase',['../classRobotModelBase.html',1,'']]], + ['robotstate_306',['RobotState',['../structfranka_1_1RobotState.html',1,'franka']]] +]; diff --git a/search/classes_c.html b/search/classes_c.html new file mode 100644 index 00000000..2f7b1f3d --- /dev/null +++ b/search/classes_c.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_c.js b/search/classes_c.js new file mode 100644 index 00000000..20cb6ae7 --- /dev/null +++ b/search/classes_c.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['torques_307',['Torques',['../classfranka_1_1Torques.html',1,'franka']]] +]; diff --git a/search/classes_d.html b/search/classes_d.html new file mode 100644 index 00000000..f9011e70 --- /dev/null +++ b/search/classes_d.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/classes_d.js b/search/classes_d.js new file mode 100644 index 00000000..d75692a4 --- /dev/null +++ b/search/classes_d.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['vacuumgripper_308',['VacuumGripper',['../classfranka_1_1VacuumGripper.html',1,'franka']]], + ['vacuumgripperstate_309',['VacuumGripperState',['../structfranka_1_1VacuumGripperState.html',1,'franka']]] +]; diff --git a/search/close.svg b/search/close.svg new file mode 100644 index 00000000..a933eea1 --- /dev/null +++ b/search/close.svg @@ -0,0 +1,31 @@ + + + + + + image/svg+xml + + + + + + + + diff --git a/search/enums_0.html b/search/enums_0.html new file mode 100644 index 00000000..141fff57 --- /dev/null +++ b/search/enums_0.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/enums_0.js b/search/enums_0.js new file mode 100644 index 00000000..4a1a85e9 --- /dev/null +++ b/search/enums_0.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['controllermode_558',['ControllerMode',['../control__types_8h.html#a3e20bc77587e2c0c53598753e3f4816b',1,'franka']]] +]; diff --git a/search/enums_1.html b/search/enums_1.html new file mode 100644 index 00000000..d29f3b16 --- /dev/null +++ b/search/enums_1.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/enums_1.js b/search/enums_1.js new file mode 100644 index 00000000..82501c9c --- /dev/null +++ b/search/enums_1.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['frame_559',['Frame',['../model_8h.html#a00b729ddce916481d3f0d10febec4f5b',1,'franka']]] +]; diff --git a/search/enums_2.html b/search/enums_2.html new file mode 100644 index 00000000..59aadf2c --- /dev/null +++ b/search/enums_2.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/enums_2.js b/search/enums_2.js new file mode 100644 index 00000000..6d2b52f4 --- /dev/null +++ b/search/enums_2.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['productionsetupprofile_560',['ProductionSetupProfile',['../classfranka_1_1VacuumGripper.html#a0c81171a75c385780a82ff8dc36ef51e',1,'franka::VacuumGripper']]] +]; diff --git a/search/enums_3.html b/search/enums_3.html new file mode 100644 index 00000000..87c17443 --- /dev/null +++ b/search/enums_3.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/enums_3.js b/search/enums_3.js new file mode 100644 index 00000000..914bcc8d --- /dev/null +++ b/search/enums_3.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['realtimeconfig_561',['RealtimeConfig',['../control__types_8h.html#aeede4f4629390fea21ca5e5a35a8a943',1,'franka']]], + ['robotmode_562',['RobotMode',['../robot__state_8h.html#adfe059ae23ebbad59e421edaa879651a',1,'franka']]] +]; diff --git a/search/enums_4.html b/search/enums_4.html new file mode 100644 index 00000000..90dda139 --- /dev/null +++ b/search/enums_4.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/enums_4.js b/search/enums_4.js new file mode 100644 index 00000000..f1f21824 --- /dev/null +++ b/search/enums_4.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['vacuumgripperdevicestatus_563',['VacuumGripperDeviceStatus',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611',1,'franka']]] +]; diff --git a/search/enumvalues_0.html b/search/enumvalues_0.html new file mode 100644 index 00000000..0d131d95 --- /dev/null +++ b/search/enumvalues_0.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/enumvalues_0.js b/search/enumvalues_0.js new file mode 100644 index 00000000..91e31b4b --- /dev/null +++ b/search/enumvalues_0.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['kgreen_564',['kGreen',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611a1299e6e2ec6371a79385cd3a862f7cc9',1,'franka']]], + ['korange_565',['kOrange',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611a11e1aa07606f098e5025e37830a1b22e',1,'franka']]], + ['kred_566',['kRed',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611afb0136b923af8c04b31a9d1b5e989acf',1,'franka']]], + ['kyellow_567',['kYellow',['../vacuum__gripper__state_8h.html#a423e2ce5f95933b9897c6e308d91b611a4c6c30a3642462190739bb7f13af9c7b',1,'franka']]] +]; diff --git a/search/files_0.html b/search/files_0.html new file mode 100644 index 00000000..9498842a --- /dev/null +++ b/search/files_0.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/files_0.js b/search/files_0.js new file mode 100644 index 00000000..556f5d57 --- /dev/null +++ b/search/files_0.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['active_5fcontrol_2eh_310',['active_control.h',['../active__control_8h.html',1,'']]], + ['active_5fcontrol_5fbase_2eh_311',['active_control_base.h',['../active__control__base_8h.html',1,'']]], + ['active_5fmotion_5fgenerator_2eh_312',['active_motion_generator.h',['../active__motion__generator_8h.html',1,'']]], + ['active_5ftorque_5fcontrol_2eh_313',['active_torque_control.h',['../active__torque__control_8h.html',1,'']]] +]; diff --git a/search/files_1.html b/search/files_1.html new file mode 100644 index 00000000..7050ef48 --- /dev/null +++ b/search/files_1.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/files_1.js b/search/files_1.js new file mode 100644 index 00000000..2f9676db --- /dev/null +++ b/search/files_1.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['control_5ftools_2eh_314',['control_tools.h',['../control__tools_8h.html',1,'']]], + ['control_5ftypes_2eh_315',['control_types.h',['../control__types_8h.html',1,'']]] +]; diff --git a/search/files_2.html b/search/files_2.html new file mode 100644 index 00000000..497cdf5c --- /dev/null +++ b/search/files_2.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/files_2.js b/search/files_2.js new file mode 100644 index 00000000..26012f85 --- /dev/null +++ b/search/files_2.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['duration_2eh_316',['duration.h',['../duration_8h.html',1,'']]] +]; diff --git a/search/files_3.html b/search/files_3.html new file mode 100644 index 00000000..1ba106b2 --- /dev/null +++ b/search/files_3.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/files_3.js b/search/files_3.js new file mode 100644 index 00000000..a162bacf --- /dev/null +++ b/search/files_3.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['errors_2eh_317',['errors.h',['../errors_8h.html',1,'']]], + ['examples_5fcommon_2eh_318',['examples_common.h',['../examples__common_8h.html',1,'']]], + ['exception_2eh_319',['exception.h',['../exception_8h.html',1,'']]] +]; diff --git a/search/files_4.html b/search/files_4.html new file mode 100644 index 00000000..753b7b10 --- /dev/null +++ b/search/files_4.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/files_4.js b/search/files_4.js new file mode 100644 index 00000000..8da8f48c --- /dev/null +++ b/search/files_4.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['gripper_2eh_320',['gripper.h',['../gripper_8h.html',1,'']]], + ['gripper_5fstate_2eh_321',['gripper_state.h',['../gripper__state_8h.html',1,'']]] +]; diff --git a/search/files_5.html b/search/files_5.html new file mode 100644 index 00000000..7b6affd7 --- /dev/null +++ b/search/files_5.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/files_5.js b/search/files_5.js new file mode 100644 index 00000000..bf3bce39 --- /dev/null +++ b/search/files_5.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['log_2eh_322',['log.h',['../log_8h.html',1,'']]], + ['lowpass_5ffilter_2eh_323',['lowpass_filter.h',['../lowpass__filter_8h.html',1,'']]] +]; diff --git a/search/files_6.html b/search/files_6.html new file mode 100644 index 00000000..802ebf71 --- /dev/null +++ b/search/files_6.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/files_6.js b/search/files_6.js new file mode 100644 index 00000000..ea0377e9 --- /dev/null +++ b/search/files_6.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['model_2eh_324',['model.h',['../model_8h.html',1,'']]] +]; diff --git a/search/files_7.html b/search/files_7.html new file mode 100644 index 00000000..365e6484 --- /dev/null +++ b/search/files_7.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/files_7.js b/search/files_7.js new file mode 100644 index 00000000..28c75edb --- /dev/null +++ b/search/files_7.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['rate_5flimiting_2eh_325',['rate_limiting.h',['../rate__limiting_8h.html',1,'']]], + ['robot_2eh_326',['robot.h',['../robot_8h.html',1,'']]], + ['robot_5fstate_2eh_327',['robot_state.h',['../robot__state_8h.html',1,'']]] +]; diff --git a/search/files_8.html b/search/files_8.html new file mode 100644 index 00000000..3df0f2fa --- /dev/null +++ b/search/files_8.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/files_8.js b/search/files_8.js new file mode 100644 index 00000000..9596b6eb --- /dev/null +++ b/search/files_8.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['vacuum_5fgripper_2eh_328',['vacuum_gripper.h',['../vacuum__gripper_8h.html',1,'']]], + ['vacuum_5fgripper_5fstate_2eh_329',['vacuum_gripper_state.h',['../vacuum__gripper__state_8h.html',1,'']]] +]; diff --git a/search/functions_0.html b/search/functions_0.html new file mode 100644 index 00000000..eb4c5014 --- /dev/null +++ b/search/functions_0.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_0.js b/search/functions_0.js new file mode 100644 index 00000000..a1ac2609 --- /dev/null +++ b/search/functions_0.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['activecontrol_330',['ActiveControl',['../classfranka_1_1ActiveControl.html#a4aa09537fddbec6cf1eed05fdc147b30',1,'franka::ActiveControl']]], + ['automaticerrorrecovery_331',['automaticErrorRecovery',['../classfranka_1_1Robot.html#af682aa673415718715bd859116bc2fed',1,'franka::Robot']]] +]; diff --git a/search/functions_1.html b/search/functions_1.html new file mode 100644 index 00000000..ef4088b8 --- /dev/null +++ b/search/functions_1.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_1.js b/search/functions_1.js new file mode 100644 index 00000000..3ac3985f --- /dev/null +++ b/search/functions_1.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['bodyjacobian_332',['bodyJacobian',['../classfranka_1_1Model.html#a914a197a900a275799cf8d7461bb9d8a',1,'franka::Model::bodyJacobian(Frame frame, const franka::RobotState &robot_state) const'],['../classfranka_1_1Model.html#a9ceca00546fa221f15ddaa7c0d27c40e',1,'franka::Model::bodyJacobian(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const']]] +]; diff --git a/search/functions_10.html b/search/functions_10.html new file mode 100644 index 00000000..1bdc1257 --- /dev/null +++ b/search/functions_10.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_10.js b/search/functions_10.js new file mode 100644 index 00000000..768638f5 --- /dev/null +++ b/search/functions_10.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['vacuum_414',['vacuum',['../classfranka_1_1VacuumGripper.html#a517d95d9800990ca1a5892473c2def89',1,'franka::VacuumGripper']]], + ['vacuumgripper_415',['VacuumGripper',['../classfranka_1_1VacuumGripper.html#ab5d8483a0bb16136da684cfac721eae1',1,'franka::VacuumGripper::VacuumGripper(const std::string &franka_address)'],['../classfranka_1_1VacuumGripper.html#ab80730b14b5948eea37395e87800ce5f',1,'franka::VacuumGripper::VacuumGripper(VacuumGripper &&vacuum_gripper) noexcept']]] +]; diff --git a/search/functions_11.html b/search/functions_11.html new file mode 100644 index 00000000..188076ef --- /dev/null +++ b/search/functions_11.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_11.js b/search/functions_11.js new file mode 100644 index 00000000..f5db6d74 --- /dev/null +++ b/search/functions_11.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['writeonce_416',['writeOnce',['../classfranka_1_1ActiveControlBase.html#ab0b5421122071fa0d578dcd0f4cabc36',1,'franka::ActiveControlBase::writeOnce()'],['../classfranka_1_1ActiveTorqueControl.html#acc3b1d8c41cd191786e384887adf5da2',1,'franka::ActiveTorqueControl::writeOnce()'],['../classfranka_1_1ActiveMotionGenerator.html#aae24c0819a0bd0996657063832245d69',1,'franka::ActiveMotionGenerator::writeOnce()'],['../classfranka_1_1ActiveControlBase.html#a35ad38e4c512e34b0c82b081cefe4020',1,'franka::ActiveControlBase::writeOnce(const CartesianVelocities &motion_generator_input)=0'],['../classfranka_1_1ActiveControlBase.html#a9b05a521b8ab9d1af6c58b3d1fbcf12f',1,'franka::ActiveControlBase::writeOnce(const CartesianPose &motion_generator_input)=0'],['../classfranka_1_1ActiveControlBase.html#ae00c5b9387e21b76443ddfd173f7d01e',1,'franka::ActiveControlBase::writeOnce(const JointVelocities &motion_generator_input)=0'],['../classfranka_1_1ActiveControlBase.html#a800a13f3d6d12408dbff3afc8d072af2',1,'franka::ActiveControlBase::writeOnce(const JointPositions &motion_generator_input)=0'],['../classfranka_1_1ActiveControlBase.html#ac94d472225bbe8b6322b9f3cbf98bd3b',1,'franka::ActiveControlBase::writeOnce(const CartesianVelocities &, const std::optional< const Torques > &)=0'],['../classfranka_1_1ActiveControlBase.html#a61ffd2a40b082e275784175f7a38aa08',1,'franka::ActiveControlBase::writeOnce(const CartesianPose &, const std::optional< const Torques > &)=0'],['../classfranka_1_1ActiveControlBase.html#a46f54e3366ad083c9dedf62b9f4e1fea',1,'franka::ActiveControlBase::writeOnce(const JointVelocities &, const std::optional< const Torques > &)=0'],['../classfranka_1_1ActiveControl.html#a888b87832cd3def156c07a0b57d95663',1,'franka::ActiveControl::writeOnce()'],['../classfranka_1_1ActiveControlBase.html#a070846c3bd259aa703848d984a82e43d',1,'franka::ActiveControlBase::writeOnce()'],['../classfranka_1_1ActiveControl.html#ad4bf06b3e873fd95a2261d67d89a4d1f',1,'franka::ActiveControl::writeOnce(const CartesianVelocities &motion_generator_input) override'],['../classfranka_1_1ActiveControl.html#a6b6265ccad26dc2e32c7b6329b74fb80',1,'franka::ActiveControl::writeOnce(const CartesianPose &motion_generator_input) override'],['../classfranka_1_1ActiveControl.html#a7f54a6bc037fa63f14e1a3f1329d4bf5',1,'franka::ActiveControl::writeOnce(const JointVelocities &motion_generator_input) override'],['../classfranka_1_1ActiveControl.html#a8166a590c84c749cd90c874bd2f1aca4',1,'franka::ActiveControl::writeOnce(const JointPositions &motion_generator_input) override'],['../classfranka_1_1ActiveControl.html#a12c3c6916e26e66dae41eb624daabb4a',1,'franka::ActiveControl::writeOnce(const CartesianVelocities &, const std::optional< const Torques > &) override'],['../classfranka_1_1ActiveControl.html#a52f9ce19182359732bddee7b52a87419',1,'franka::ActiveControl::writeOnce(const CartesianPose &, const std::optional< const Torques > &) override'],['../classfranka_1_1ActiveControl.html#a2a27360ae8203fa8a413c47708e03ede',1,'franka::ActiveControl::writeOnce(const JointVelocities &, const std::optional< const Torques > &) override'],['../classfranka_1_1ActiveControl.html#a762615a1a3d5cf18064bfbd0b45effa6',1,'franka::ActiveControl::writeOnce(const JointPositions &, const std::optional< const Torques > &) override']]] +]; diff --git a/search/functions_12.html b/search/functions_12.html new file mode 100644 index 00000000..eb29d8f9 --- /dev/null +++ b/search/functions_12.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_12.js b/search/functions_12.js new file mode 100644 index 00000000..5ae03e35 --- /dev/null +++ b/search/functions_12.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['zerojacobian_417',['zeroJacobian',['../classfranka_1_1Model.html#a6fb6347b571a6759bad10b3a9e28a28f',1,'franka::Model::zeroJacobian(Frame frame, const franka::RobotState &robot_state) const'],['../classfranka_1_1Model.html#a6522f1079e1dc5f6799dde6197b45259',1,'franka::Model::zeroJacobian(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const']]] +]; diff --git a/search/functions_13.html b/search/functions_13.html new file mode 100644 index 00000000..3da2ea69 --- /dev/null +++ b/search/functions_13.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_13.js b/search/functions_13.js new file mode 100644 index 00000000..826ceff0 --- /dev/null +++ b/search/functions_13.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['_7egripper_418',['~Gripper',['../classfranka_1_1Gripper.html#ade253b8a35312d52c636c6aafb7b2e1d',1,'franka::Gripper']]], + ['_7emodel_419',['~Model',['../classfranka_1_1Model.html#a1d6ffa26afc6cfdff7e329d15b8bd65e',1,'franka::Model']]], + ['_7erobot_420',['~Robot',['../classfranka_1_1Robot.html#ac19400de0fd39852d5825b1f1ccc85e2',1,'franka::Robot']]], + ['_7evacuumgripper_421',['~VacuumGripper',['../classfranka_1_1VacuumGripper.html#af43f640f3cb9ca873b02bb464d3c279b',1,'franka::VacuumGripper']]] +]; diff --git a/search/functions_2.html b/search/functions_2.html new file mode 100644 index 00000000..ca5aa10e --- /dev/null +++ b/search/functions_2.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_2.js b/search/functions_2.js new file mode 100644 index 00000000..aa4d35e8 --- /dev/null +++ b/search/functions_2.js @@ -0,0 +1,14 @@ +var searchData= +[ + ['cartesianlowpassfilter_333',['cartesianLowpassFilter',['../lowpass__filter_8h.html#ac25e174345ea5e2ea9099287ad43cd2b',1,'franka']]], + ['cartesianpose_334',['CartesianPose',['../classfranka_1_1CartesianPose.html#a17272cb33af9aa4b726fa96b31cf0101',1,'franka::CartesianPose::CartesianPose(const std::array< double, 16 > &cartesian_pose, const std::array< double, 2 > &elbow) noexcept'],['../classfranka_1_1CartesianPose.html#a70b6460e98bc763a49c53accd48d54a2',1,'franka::CartesianPose::CartesianPose(std::initializer_list< double > cartesian_pose)'],['../classfranka_1_1CartesianPose.html#ab7fb1dfd7cdb89c0caebab95c669ba49',1,'franka::CartesianPose::CartesianPose(std::initializer_list< double > cartesian_pose, std::initializer_list< double > elbow)'],['../classfranka_1_1CartesianPose.html#a5559a53a898f9b369b1df9d51f9351b5',1,'franka::CartesianPose::CartesianPose(const std::array< double, 16 > &cartesian_pose) noexcept']]], + ['cartesianvelocities_335',['CartesianVelocities',['../classfranka_1_1CartesianVelocities.html#a713380954e1f10c1be3033b95ca00657',1,'franka::CartesianVelocities::CartesianVelocities(const std::array< double, 6 > &cartesian_velocities) noexcept'],['../classfranka_1_1CartesianVelocities.html#a95f6feec3539ed9f96d555447717eb72',1,'franka::CartesianVelocities::CartesianVelocities(const std::array< double, 6 > &cartesian_velocities, const std::array< double, 2 > &elbow) noexcept'],['../classfranka_1_1CartesianVelocities.html#a39c4b06c315c963460e24324de8ad079',1,'franka::CartesianVelocities::CartesianVelocities(std::initializer_list< double > cartesian_velocities)'],['../classfranka_1_1CartesianVelocities.html#aec434afa3f92e462ad3ab4766d3456a4',1,'franka::CartesianVelocities::CartesianVelocities(std::initializer_list< double > cartesian_velocities, std::initializer_list< double > elbow)']]], + ['checkelbow_336',['checkElbow',['../control__tools_8h.html#add0cd2cd1401ac0b2393a84ca1577cde',1,'franka']]], + ['checkfinite_337',['checkFinite',['../control__tools_8h.html#a80d02c11ba41e5973ee76624bf1d4466',1,'franka']]], + ['checkmatrix_338',['checkMatrix',['../control__tools_8h.html#ab38ee604eecfedfb591ddb8327805ea4',1,'franka']]], + ['computelowerlimitsjointvelocity_339',['computeLowerLimitsJointVelocity',['../rate__limiting_8h.html#a75fe6c28325d7631f7bdb6c2b388b268',1,'franka']]], + ['computeupperlimitsjointvelocity_340',['computeUpperLimitsJointVelocity',['../rate__limiting_8h.html#a3a025c3c8f71f59627fe4f7e801021ac',1,'franka']]], + ['control_341',['control',['../classfranka_1_1Robot.html#a6ba6193e52178899dc8c6a34aa4c537c',1,'franka::Robot::control(std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#adce4add23b47befadccd30e3dbe9f2f4',1,'franka::Robot::control(std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a2176c99664b83bb394f0b2dfd416a8ee',1,'franka::Robot::control(std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a7fef8f6418cff168f680ac7c61a6b5cd',1,'franka::Robot::control(std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#aeb276d0a0e55f032841976de7db86f5a',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a4ce9fd531f97c8cc943dd2479298a55f',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a76e8b7a9c7e2b874c3e300ba7cdeb8ca',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a4b625b781d388f3379e0961c724239d5',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)'],['../classfranka_1_1Robot.html#a0d5effba5daff2fee123802bbd5f95d1',1,'franka::Robot::control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)']]], + ['controlexception_342',['ControlException',['../structfranka_1_1ControlException.html#a2efb9628eef80a3819031dbf2e2cb518',1,'franka::ControlException']]], + ['coriolis_343',['coriolis',['../classfranka_1_1Model.html#a91424f181a93bb47bda6af2d3567c65c',1,'franka::Model::coriolis(const franka::RobotState &robot_state) const noexcept'],['../classfranka_1_1Model.html#a3445ad932ddda2e3540768af9b7b4852',1,'franka::Model::coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept'],['../classfranka_1_1RobotModel.html#ae8b6b42f32ffb0ca654e76080c8ee347',1,'franka::RobotModel::coriolis()'],['../classRobotModelBase.html#a45226fbc547a27d5e7cff8a78e9bd0b4',1,'RobotModelBase::coriolis()']]] +]; diff --git a/search/functions_3.html b/search/functions_3.html new file mode 100644 index 00000000..d79f55b8 --- /dev/null +++ b/search/functions_3.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_3.js b/search/functions_3.js new file mode 100644 index 00000000..374af330 --- /dev/null +++ b/search/functions_3.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['dropoff_344',['dropOff',['../classfranka_1_1VacuumGripper.html#a04645348e97b946a788205c8b1168cac',1,'franka::VacuumGripper']]], + ['duration_345',['Duration',['../classfranka_1_1Duration.html#af721da321423772b4ce7ff11280d38d5',1,'franka::Duration::Duration() noexcept'],['../classfranka_1_1Duration.html#a46f0cea3e05c27cdaaba5ff25e0e6cd6',1,'franka::Duration::Duration(uint64_t milliseconds) noexcept'],['../classfranka_1_1Duration.html#a389dfef50f34e9cc5be69838fbdafba7',1,'franka::Duration::Duration(std::chrono::duration< uint64_t, std::milli > duration) noexcept'],['../classfranka_1_1Duration.html#a886575e716b45e85de1bb78def2eb133',1,'franka::Duration::Duration(const Duration &)=default']]] +]; diff --git a/search/functions_4.html b/search/functions_4.html new file mode 100644 index 00000000..1657cad0 --- /dev/null +++ b/search/functions_4.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_4.js b/search/functions_4.js new file mode 100644 index 00000000..e1158818 --- /dev/null +++ b/search/functions_4.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['errors_346',['Errors',['../structfranka_1_1Errors.html#aedd6b6af230c01b6f106b5050b29d9ae',1,'franka::Errors::Errors()'],['../structfranka_1_1Errors.html#a4548a72089cc6d61c9249a1b8f4cc480',1,'franka::Errors::Errors(const Errors &other)'],['../structfranka_1_1Errors.html#adffc6f8b2235e566c4a43ce69a86634e',1,'franka::Errors::Errors(const std::array< bool, 41 > &errors)']]] +]; diff --git a/search/functions_5.html b/search/functions_5.html new file mode 100644 index 00000000..9301d6b9 --- /dev/null +++ b/search/functions_5.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_5.js b/search/functions_5.js new file mode 100644 index 00000000..bd735b32 --- /dev/null +++ b/search/functions_5.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['getrobotmodel_347',['getRobotModel',['../classfranka_1_1Robot.html#a54565ca0eb7b58727f88a8dcbf2f98ab',1,'franka::Robot']]], + ['grasp_348',['grasp',['../classfranka_1_1Gripper.html#abff6a03a6c75b9079bd4b9b5ca380254',1,'franka::Gripper']]], + ['gravity_349',['gravity',['../classfranka_1_1Model.html#a9b28a648cf413297d80f383e62363ab9',1,'franka::Model::gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexcept'],['../classfranka_1_1Model.html#a76a94e1ddb45cf1cdded25be4cf2dcae',1,'franka::Model::gravity(const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const noexcept'],['../classfranka_1_1Model.html#a983611785e894e1cd1f07a2df97ddbdd',1,'franka::Model::gravity(const franka::RobotState &robot_state) const noexcept'],['../classfranka_1_1RobotModel.html#a027d8e2e713b66cdbaf17201a30236f1',1,'franka::RobotModel::gravity()'],['../classRobotModelBase.html#ace835cdef4ae60d965c9faf57c3914e1',1,'RobotModelBase::gravity()']]], + ['gripper_350',['Gripper',['../classfranka_1_1Gripper.html#a02b30632b08001592c62d3563561afc5',1,'franka::Gripper::Gripper(const std::string &franka_address)'],['../classfranka_1_1Gripper.html#aa045ea81b36f22420f9bc6f2a256a4f0',1,'franka::Gripper::Gripper(Gripper &&gripper) noexcept']]] +]; diff --git a/search/functions_6.html b/search/functions_6.html new file mode 100644 index 00000000..9c4f5fc6 --- /dev/null +++ b/search/functions_6.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_6.js b/search/functions_6.js new file mode 100644 index 00000000..59a1a003 --- /dev/null +++ b/search/functions_6.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['haselbow_351',['hasElbow',['../classfranka_1_1CartesianPose.html#a5fa9f47dbf73ab45f671d89e11f89ccf',1,'franka::CartesianPose::hasElbow()'],['../classfranka_1_1CartesianVelocities.html#a51a41893b10250982597fe367abb2ca6',1,'franka::CartesianVelocities::hasElbow()']]], + ['hasrealtimekernel_352',['hasRealtimeKernel',['../control__tools_8h.html#ad165a74da105c78586c0cd4c1ed57bd2',1,'franka']]], + ['homing_353',['homing',['../classfranka_1_1Gripper.html#aef356f93a4c3b9d6b2532c29126d478c',1,'franka::Gripper']]] +]; diff --git a/search/functions_7.html b/search/functions_7.html new file mode 100644 index 00000000..46b5c0f6 --- /dev/null +++ b/search/functions_7.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_7.js b/search/functions_7.js new file mode 100644 index 00000000..03b3b77f --- /dev/null +++ b/search/functions_7.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['incompatibleversionexception_354',['IncompatibleVersionException',['../structfranka_1_1IncompatibleVersionException.html#a518f40d994ed7e970c6f7fdafb673239',1,'franka::IncompatibleVersionException']]], + ['ishomogeneoustransformation_355',['isHomogeneousTransformation',['../control__tools_8h.html#ad81c99e8af3f2536ae3c6ec1ce8dce1e',1,'franka']]], + ['isvalidelbow_356',['isValidElbow',['../control__tools_8h.html#a4eda3eda0514fabf6d630a6d8c0373a0',1,'franka']]] +]; diff --git a/search/functions_8.html b/search/functions_8.html new file mode 100644 index 00000000..31a1d950 --- /dev/null +++ b/search/functions_8.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_8.js b/search/functions_8.js new file mode 100644 index 00000000..af9b3d82 --- /dev/null +++ b/search/functions_8.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['jointpositions_357',['JointPositions',['../classfranka_1_1JointPositions.html#a57bc9d7e033493b1182333276af5ce84',1,'franka::JointPositions::JointPositions(const std::array< double, 7 > &joint_positions) noexcept'],['../classfranka_1_1JointPositions.html#a1e2006bccc9de89d8eb1a4d1c4da2fb8',1,'franka::JointPositions::JointPositions(std::initializer_list< double > joint_positions)']]], + ['jointvelocities_358',['JointVelocities',['../classfranka_1_1JointVelocities.html#a1130f851055de3b7ebe9e6fbac960826',1,'franka::JointVelocities::JointVelocities(const std::array< double, 7 > &joint_velocities) noexcept'],['../classfranka_1_1JointVelocities.html#aed384fad8e302638c2e5baea6378c2d2',1,'franka::JointVelocities::JointVelocities(std::initializer_list< double > joint_velocities)']]] +]; diff --git a/search/functions_9.html b/search/functions_9.html new file mode 100644 index 00000000..9a8e4290 --- /dev/null +++ b/search/functions_9.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_9.js b/search/functions_9.js new file mode 100644 index 00000000..e1803133 --- /dev/null +++ b/search/functions_9.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['limitrate_359',['limitRate',['../rate__limiting_8h.html#aea6895d6bf209a86319c6cd5180e4b60',1,'franka::limitRate(const std::array< double, 7 > &max_derivatives, const std::array< double, 7 > &commanded_values, const std::array< double, 7 > &last_commanded_values)'],['../rate__limiting_8h.html#ae425f551c62b289a93ad471f94f87b7c',1,'franka::limitRate(double upper_limits_velocity, double lower_limits_velocity, double max_acceleration, double max_jerk, double commanded_velocity, double last_commanded_velocity, double last_commanded_acceleration)'],['../rate__limiting_8h.html#afacb3c087c76dded71874eaa7862b05d',1,'franka::limitRate(double upper_limits_velocity, double lower_limits_velocity, double max_acceleration, double max_jerk, double commanded_position, double last_commanded_position, double last_commanded_velocity, double last_commanded_acceleration)'],['../rate__limiting_8h.html#a62ebac6ebbef784d44135855a899abef',1,'franka::limitRate(const std::array< double, 7 > &upper_limits_velocity, const std::array< double, 7 > &lower_limits_velocity, const std::array< double, 7 > &max_acceleration, const std::array< double, 7 > &max_jerk, const std::array< double, 7 > &commanded_velocities, const std::array< double, 7 > &last_commanded_velocities, const std::array< double, 7 > &last_commanded_accelerations)'],['../rate__limiting_8h.html#aaaa22e0873d0630465e506ddc877083f',1,'franka::limitRate(const std::array< double, 7 > &upper_limits_velocity, const std::array< double, 7 > &lower_limits_velocity, const std::array< double, 7 > &max_acceleration, const std::array< double, 7 > &max_jerk, const std::array< double, 7 > &commanded_positions, const std::array< double, 7 > &last_commanded_positions, const std::array< double, 7 > &last_commanded_velocities, const std::array< double, 7 > &last_commanded_accelerations)'],['../rate__limiting_8h.html#ad3e0243f9be5335ae3d04f87852dfccb',1,'franka::limitRate(double max_translational_velocity, double max_translational_acceleration, double max_translational_jerk, double max_rotational_velocity, double max_rotational_acceleration, double max_rotational_jerk, const std::array< double, 6 > &O_dP_EE_c, const std::array< double, 6 > &last_O_dP_EE_c, const std::array< double, 6 > &last_O_ddP_EE_c)'],['../rate__limiting_8h.html#a9288f438fcfc1aedf7e0b52aa95b23ba',1,'franka::limitRate(double max_translational_velocity, double max_translational_acceleration, double max_translational_jerk, double max_rotational_velocity, double max_rotational_acceleration, double max_rotational_jerk, const std::array< double, 16 > &O_T_EE_c, const std::array< double, 16 > &last_O_T_EE_c, const std::array< double, 6 > &last_O_dP_EE_c, const std::array< double, 6 > &last_O_ddP_EE_c)']]], + ['loadmodel_360',['loadModel',['../classfranka_1_1Robot.html#a2da598c539469827409ac7e3bb61d5da',1,'franka::Robot']]], + ['logtocsv_361',['logToCSV',['../log_8h.html#a01fbdb37b0e6beb04ba108d5f5024fd9',1,'franka']]], + ['lowpassfilter_362',['lowpassFilter',['../lowpass__filter_8h.html#a94c21b0e87afce0147a9cd6025c239ca',1,'franka']]] +]; diff --git a/search/functions_a.html b/search/functions_a.html new file mode 100644 index 00000000..5ecc152c --- /dev/null +++ b/search/functions_a.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_a.js b/search/functions_a.js new file mode 100644 index 00000000..470d97ae --- /dev/null +++ b/search/functions_a.js @@ -0,0 +1,8 @@ +var searchData= +[ + ['mass_363',['mass',['../classfranka_1_1Model.html#ad5f6156064bc18e42fc0b6d2f36b2006',1,'franka::Model::mass(const franka::RobotState &robot_state) const noexcept'],['../classfranka_1_1Model.html#a61c3a8968e927c8629f1d549d20aaf85',1,'franka::Model::mass(const std::array< double, 7 > &q, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept'],['../classfranka_1_1RobotModel.html#abbff56dc8a77bb3bead7efb7f891f8ed',1,'franka::RobotModel::mass()'],['../classRobotModelBase.html#ad6205b8405cc76be5b3e8fe3a3a2c1f9',1,'RobotModelBase::mass()']]], + ['model_364',['Model',['../classfranka_1_1Model.html#a8bf08984ec15c041ff1cbbe870945b82',1,'franka::Model::Model(franka::Network &network, const std::string &urdf_model)'],['../classfranka_1_1Model.html#a8148cf270e52ad9e967d4651fc37d690',1,'franka::Model::Model(franka::Network &network, std::unique_ptr< RobotModelBase > robot_model)'],['../classfranka_1_1Model.html#a8b58ff37f62512aecdcd0e6aabfd9548',1,'franka::Model::Model(Model &&model) noexcept']]], + ['motionfinished_365',['MotionFinished',['../control__types_8h.html#a20791f7142d78bbbe3c957cc66a23ade',1,'franka::MotionFinished(Torques command) noexcept'],['../control__types_8h.html#a7f505509951b6568b08b3aec8ffb9098',1,'franka::MotionFinished(JointPositions command) noexcept'],['../control__types_8h.html#ab478c128d691a46c0ab85bbf3b5caac5',1,'franka::MotionFinished(JointVelocities command) noexcept'],['../control__types_8h.html#ab0b308e2a9348fd3eb5fd1d08db12dcf',1,'franka::MotionFinished(CartesianPose command) noexcept'],['../control__types_8h.html#a5898ad5e3bbc2682c24c0415bf7e9a95',1,'franka::MotionFinished(CartesianVelocities command) noexcept']]], + ['motiongenerator_366',['MotionGenerator',['../classMotionGenerator.html#a23dd564a60401c539fb7f1bf63470894',1,'MotionGenerator']]], + ['move_367',['move',['../classfranka_1_1Gripper.html#a047bc39267d66d6fb26c4c70669d68c2',1,'franka::Gripper']]] +]; diff --git a/search/functions_b.html b/search/functions_b.html new file mode 100644 index 00000000..e301fedd --- /dev/null +++ b/search/functions_b.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_b.js b/search/functions_b.js new file mode 100644 index 00000000..5d0488d5 --- /dev/null +++ b/search/functions_b.js @@ -0,0 +1,26 @@ +var searchData= +[ + ['duration_3c_20uint64_5ft_2c_20std_3a_3amilli_20_3e_368',['duration< uint64_t, std::milli >',['../classfranka_1_1Duration.html#ae58e283f511f9de8ac7e145db5cac1cf',1,'franka::Duration']]], + ['operator_20bool_369',['operator bool',['../structfranka_1_1Errors.html#a50cb6e50c1ce2b5ec281dcad83f1779e',1,'franka::Errors']]], + ['operator_21_3d_370',['operator!=',['../classfranka_1_1Duration.html#a61603353e39361af2f405c1df7097e84',1,'franka::Duration']]], + ['operator_25_371',['operator%',['../classfranka_1_1Duration.html#a5e472345c1bec29b645bee938932fdb1',1,'franka::Duration::operator%(const Duration &rhs) const noexcept'],['../classfranka_1_1Duration.html#af06ff91f24d881c479768c1bcbf31a1e',1,'franka::Duration::operator%(uint64_t rhs) const noexcept']]], + ['operator_25_3d_372',['operator%=',['../classfranka_1_1Duration.html#a97a6ea669877875ffc54c801ac0b152d',1,'franka::Duration::operator%=(const Duration &rhs) noexcept'],['../classfranka_1_1Duration.html#acd85bab22062a2258af83ac5b3b7a647',1,'franka::Duration::operator%=(uint64_t rhs) noexcept']]], + ['operator_28_29_373',['operator()',['../classMotionGenerator.html#aefd763e7c31c54b56404f33d2295fda9',1,'MotionGenerator']]], + ['operator_2a_374',['operator*',['../duration_8h.html#ab3a36a47682756845ef855994aadd7b6',1,'franka::operator*()'],['../classfranka_1_1Duration.html#a3eebc39550880fb2d23d45ba34d8acc5',1,'franka::Duration::operator*(uint64_t rhs) const noexcept']]], + ['operator_2a_3d_375',['operator*=',['../classfranka_1_1Duration.html#a73f971b2efb29a8ce663e8675d1ec09a',1,'franka::Duration']]], + ['operator_2b_376',['operator+',['../classfranka_1_1Duration.html#adb459e7bf5c6b02f9e72c808f5f30237',1,'franka::Duration']]], + ['operator_2b_2b_377',['operator++',['../model_8h.html#ae39c3a098fdb1bc9a097a262312454d0',1,'franka']]], + ['operator_2b_3d_378',['operator+=',['../classfranka_1_1Duration.html#ac55eb81937a12e736560bd856a8f23ae',1,'franka::Duration']]], + ['operator_2d_379',['operator-',['../classfranka_1_1Duration.html#a2a3bc1a8278b91bebe88d7498d410de9',1,'franka::Duration']]], + ['operator_2d_3d_380',['operator-=',['../classfranka_1_1Duration.html#acb24af377db86646918bcfb3e1e2ebe6',1,'franka::Duration']]], + ['operator_2f_381',['operator/',['../classfranka_1_1Duration.html#a90c76be31b53e11f5761416a05d990be',1,'franka::Duration::operator/(const Duration &rhs) const noexcept'],['../classfranka_1_1Duration.html#a15b7299198f36734b62ac98da1ef8c9c',1,'franka::Duration::operator/(uint64_t rhs) const noexcept']]], + ['operator_2f_3d_382',['operator/=',['../classfranka_1_1Duration.html#ac866dd8d0e8f2dbb92089dbd78418571',1,'franka::Duration']]], + ['operator_3c_383',['operator<',['../classfranka_1_1Duration.html#af1650b31c1226a447406fc243f4a2ac1',1,'franka::Duration']]], + ['operator_3c_3c_384',['operator<<',['../errors_8h.html#ad1027058086c3c154f4bbc9cade1f197',1,'franka::operator<<(std::ostream &ostream, const Errors &errors)'],['../gripper__state_8h.html#ab66181a74d1d3b7e90ae3b424ee85f4f',1,'franka::operator<<(std::ostream &ostream, const franka::GripperState &gripper_state)'],['../robot__state_8h.html#aee38e87180cc96476d0f11335da29e20',1,'franka::operator<<(std::ostream &ostream, const franka::RobotState &robot_state)'],['../robot__state_8h.html#a7d75ab63150979690a639f432c166755',1,'franka::operator<<(std::ostream &ostream, RobotMode robot_mode)'],['../vacuum__gripper__state_8h.html#aa2caece6baf774e998b6dec6e803cf24',1,'franka::operator<<(std::ostream &ostream, const franka::VacuumGripperState &vacuum_gripper_state)']]], + ['operator_3c_3d_385',['operator<=',['../classfranka_1_1Duration.html#ae4b9c8646fd50a2105d36f3848a5b949',1,'franka::Duration']]], + ['operator_3d_386',['operator=',['../classfranka_1_1Duration.html#adf2fec0c87fe1668e42f217ab029df19',1,'franka::Duration::operator=()'],['../structfranka_1_1Errors.html#a6fefa4083d79362080b79f3492fd4cb6',1,'franka::Errors::operator=()'],['../classfranka_1_1Gripper.html#a3c99c6973f8951ca489c4177cfacb069',1,'franka::Gripper::operator=()'],['../classfranka_1_1Model.html#a625529a4c9aed7783c9c6e150dbba793',1,'franka::Model::operator=()'],['../classfranka_1_1Robot.html#a35465b8497a7adbd277e70e98b7d97a7',1,'franka::Robot::operator=()'],['../classfranka_1_1VacuumGripper.html#a21d59603ac4deb8d9de5e074a57d080d',1,'franka::VacuumGripper::operator=()']]], + ['operator_3d_3d_387',['operator==',['../classfranka_1_1Duration.html#add0c7bcdfe51b563016236b223d74eae',1,'franka::Duration']]], + ['operator_3e_388',['operator>',['../classfranka_1_1Duration.html#a1702ec9121fe6cff1de533d116edcce0',1,'franka::Duration']]], + ['operator_3e_3d_389',['operator>=',['../classfranka_1_1Duration.html#a5bc498cf96d96f5908d6bd93eea491aa',1,'franka::Duration']]], + ['string_390',['string',['../structfranka_1_1Errors.html#a63ed1948f69db5be95a9c70107955d68',1,'franka::Errors']]] +]; diff --git a/search/functions_c.html b/search/functions_c.html new file mode 100644 index 00000000..c4f32687 --- /dev/null +++ b/search/functions_c.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_c.js b/search/functions_c.js new file mode 100644 index 00000000..f02b36d2 --- /dev/null +++ b/search/functions_c.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['pose_391',['pose',['../classfranka_1_1Model.html#a593c39dae76a6801cdd2402c2a783157',1,'franka::Model::pose(Frame frame, const franka::RobotState &robot_state) const'],['../classfranka_1_1Model.html#adf4fdf0404c2acf783493f7e646a6281',1,'franka::Model::pose(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const']]] +]; diff --git a/search/functions_d.html b/search/functions_d.html new file mode 100644 index 00000000..7a1ed065 --- /dev/null +++ b/search/functions_d.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_d.js b/search/functions_d.js new file mode 100644 index 00000000..b2f8c5e6 --- /dev/null +++ b/search/functions_d.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['read_392',['read',['../classfranka_1_1Robot.html#a82f85eed20426901a7e77b66c041664b',1,'franka::Robot']]], + ['readonce_393',['readOnce',['../classfranka_1_1ActiveControl.html#a55f5b94e5ac491e5b2ccc1782a873582',1,'franka::ActiveControl::readOnce()'],['../classfranka_1_1ActiveControlBase.html#ae99dac6dae3b0dcd79104a1a404e42d0',1,'franka::ActiveControlBase::readOnce()'],['../classfranka_1_1Gripper.html#ab0afc8a41c9c5fff808e76851dcf23ce',1,'franka::Gripper::readOnce()'],['../classfranka_1_1Robot.html#ae3c3d7c5c4491a1e96a0a543931e899a',1,'franka::Robot::readOnce()'],['../classfranka_1_1VacuumGripper.html#aaa61bfd1027cf5dc2eb9e96536a9fabf',1,'franka::VacuumGripper::readOnce()']]], + ['robot_394',['Robot',['../classfranka_1_1Robot.html#ae63bc19390df3d54f3a270814df35eb6',1,'franka::Robot::Robot(const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50)'],['../classfranka_1_1Robot.html#a378d415475336082e81a35b9811dc6c2',1,'franka::Robot::Robot(Robot &&other) noexcept'],['../classfranka_1_1Robot.html#a7cb49336d7e8b261b590a364daff2913',1,'franka::Robot::Robot(std::shared_ptr< Impl > robot_impl)'],['../classfranka_1_1Robot.html#abf60ce0434f4dc262f04fcab0beff5ac',1,'franka::Robot::Robot()=default']]] +]; diff --git a/search/functions_e.html b/search/functions_e.html new file mode 100644 index 00000000..22d2a6bf --- /dev/null +++ b/search/functions_e.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_e.js b/search/functions_e.js new file mode 100644 index 00000000..68985192 --- /dev/null +++ b/search/functions_e.js @@ -0,0 +1,19 @@ +var searchData= +[ + ['serverversion_395',['serverVersion',['../classfranka_1_1Robot.html#a3b864e16b7accafdf1a755dc21765701',1,'franka::Robot::serverVersion()'],['../classfranka_1_1VacuumGripper.html#a19abac44be2fc6df7f54fa11078a13ca',1,'franka::VacuumGripper::serverVersion()'],['../classfranka_1_1Gripper.html#a8b0b4246c042465fb00871b31efdbd8b',1,'franka::Gripper::serverVersion()']]], + ['setcartesianimpedance_396',['setCartesianImpedance',['../classfranka_1_1Robot.html#ac2678c5c31cc8c0627ecda7485f81f6d',1,'franka::Robot']]], + ['setcollisionbehavior_397',['setCollisionBehavior',['../classfranka_1_1Robot.html#a168e1214ac36d74ac64f894332b84534',1,'franka::Robot::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)'],['../classfranka_1_1Robot.html#aa188f58c9025594be4d1700da744a962',1,'franka::Robot::setCollisionBehavior(const std::array< double, 7 > &lower_torque_thresholds, const std::array< double, 7 > &upper_torque_thresholds, const std::array< double, 6 > &lower_force_thresholds, const std::array< double, 6 > &upper_force_thresholds)']]], + ['setcurrentthreadtohighestschedulerpriority_398',['setCurrentThreadToHighestSchedulerPriority',['../control__tools_8h.html#a5c090196bc50ead82194d3e594e61e65',1,'franka']]], + ['setdefaultbehavior_399',['setDefaultBehavior',['../examples__common_8h.html#ad0c6e1cb044845ee8a01b5aa1e801a45',1,'examples_common.cpp']]], + ['setee_400',['setEE',['../classfranka_1_1Robot.html#aec4abdefbc0f9a7400a36bfa0a6068af',1,'franka::Robot']]], + ['setguidingmode_401',['setGuidingMode',['../classfranka_1_1Robot.html#a7992cee203e66f9a61fe2f318ef88a26',1,'franka::Robot']]], + ['setjointimpedance_402',['setJointImpedance',['../classfranka_1_1Robot.html#aa18a28697cf6e3be16c6cff2dd839560',1,'franka::Robot']]], + ['setk_403',['setK',['../classfranka_1_1Robot.html#ad1cf59d1b11306d80cd3c7144a989c56',1,'franka::Robot']]], + ['setload_404',['setLoad',['../classfranka_1_1Robot.html#afcb708df10f24563dbcf7d5b907b4a15',1,'franka::Robot']]], + ['startcartesianposecontrol_405',['startCartesianPoseControl',['../classfranka_1_1Robot.html#a3822866cf931fab955d3dcfc6cf746e5',1,'franka::Robot']]], + ['startcartesianvelocitycontrol_406',['startCartesianVelocityControl',['../classfranka_1_1Robot.html#a838e2cfba6b08dd87742bbcfe62f15bf',1,'franka::Robot']]], + ['startjointpositioncontrol_407',['startJointPositionControl',['../classfranka_1_1Robot.html#aca7ecf76cf9c5af49cc5a878c91e19a9',1,'franka::Robot']]], + ['startjointvelocitycontrol_408',['startJointVelocityControl',['../classfranka_1_1Robot.html#ae9c867d10817b2485e306450f389a009',1,'franka::Robot']]], + ['starttorquecontrol_409',['startTorqueControl',['../classfranka_1_1Robot.html#a8146de9e50217068672b6f726a91de91',1,'franka::Robot']]], + ['stop_410',['stop',['../classfranka_1_1Gripper.html#add7397fb6c5631650c139d26a85c8e1d',1,'franka::Gripper::stop()'],['../classfranka_1_1Robot.html#a69cb08e075a81ecf3f26e94d26a06296',1,'franka::Robot::stop()'],['../classfranka_1_1VacuumGripper.html#a3722fe5488c516b4082c878a083cc865',1,'franka::VacuumGripper::stop()']]] +]; diff --git a/search/functions_f.html b/search/functions_f.html new file mode 100644 index 00000000..54b7dee0 --- /dev/null +++ b/search/functions_f.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/functions_f.js b/search/functions_f.js new file mode 100644 index 00000000..b023e3a7 --- /dev/null +++ b/search/functions_f.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['tomsec_411',['toMSec',['../classfranka_1_1Duration.html#a2a25ae33c8739b8f705f13798aa9e162',1,'franka::Duration']]], + ['torques_412',['Torques',['../classfranka_1_1Torques.html#a509d63195827289ffc645e4b62a9750d',1,'franka::Torques::Torques(const std::array< double, 7 > &torques) noexcept'],['../classfranka_1_1Torques.html#a744a08e16dcfc40b3a90ab6a85bac0d8',1,'franka::Torques::Torques(std::initializer_list< double > torques)']]], + ['tosec_413',['toSec',['../classfranka_1_1Duration.html#a497af77a3280159547f231f0374e9ac1',1,'franka::Duration']]] +]; diff --git a/search/mag_sel.svg b/search/mag_sel.svg new file mode 100644 index 00000000..03626f64 --- /dev/null +++ b/search/mag_sel.svg @@ -0,0 +1,74 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + diff --git a/search/nomatches.html b/search/nomatches.html new file mode 100644 index 00000000..2b9360b6 --- /dev/null +++ b/search/nomatches.html @@ -0,0 +1,13 @@ + + + + + + + + +
    +
    No Matches
    +
    + + diff --git a/search/pages_0.html b/search/pages_0.html new file mode 100644 index 00000000..8517b48f --- /dev/null +++ b/search/pages_0.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/pages_0.js b/search/pages_0.js new file mode 100644 index 00000000..b8ba1690 --- /dev/null +++ b/search/pages_0.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['libfranka_3a_20c_2b_2b_20library_20for_20franka_20robotics_20research_20robots_569',['libfranka: C++ library for Franka Robotics research robots',['../index.html',1,'']]] +]; diff --git a/search/related_0.html b/search/related_0.html new file mode 100644 index 00000000..506aaecc --- /dev/null +++ b/search/related_0.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/related_0.js b/search/related_0.js new file mode 100644 index 00000000..a61632ba --- /dev/null +++ b/search/related_0.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['robot_568',['Robot',['../classfranka_1_1ActiveMotionGenerator.html#a9f34d4a840b0d3e73fc3185af5fed175',1,'franka::ActiveMotionGenerator::Robot()'],['../classfranka_1_1ActiveTorqueControl.html#a9f34d4a840b0d3e73fc3185af5fed175',1,'franka::ActiveTorqueControl::Robot()']]] +]; diff --git a/search/search.css b/search/search.css new file mode 100644 index 00000000..9074198f --- /dev/null +++ b/search/search.css @@ -0,0 +1,257 @@ +/*---------------- Search Box */ + +#MSearchBox { + white-space : nowrap; + background: white; + border-radius: 0.65em; + box-shadow: inset 0.5px 0.5px 3px 0px #555; + z-index: 102; +} + +#MSearchBox .left { + display: inline-block; + vertical-align: middle; + height: 1.4em; +} + +#MSearchSelect { + display: inline-block; + vertical-align: middle; + height: 1.4em; + padding: 0 0 0 0.3em; + margin: 0; +} + +#MSearchField { + display: inline-block; + vertical-align: middle; + width: 7.5em; + height: 1.1em; + margin: 0 0.15em; + padding: 0; + line-height: 1em; + border:none; + color: #909090; + outline: none; + font-family: Arial, Verdana, sans-serif; + -webkit-border-radius: 0px; + border-radius: 0px; + background: none; +} + + +#MSearchBox .right { + display: inline-block; + vertical-align: middle; + width: 1.4em; + height: 1.4em; +} + +#MSearchClose { + display: none; + font-size: inherit; + background : none; + border: none; + margin: 0; + padding: 0; + outline: none; + +} + +#MSearchCloseImg { + height: 1.4em; + padding: 0.3em; + margin: 0; +} + +.MSearchBoxActive #MSearchField { + color: #000000; +} + +#main-menu > li:last-child { + /* This
  • object is the parent of the search bar */ + display: flex; + justify-content: center; + align-items: center; + height: 36px; + margin-right: 1em; +} + +/*---------------- Search filter selection */ + +#MSearchSelectWindow { + display: none; + position: absolute; + left: 0; top: 0; + border: 1px solid #90A5CE; + background-color: #F9FAFC; + z-index: 10001; + padding-top: 4px; + padding-bottom: 4px; + -moz-border-radius: 4px; + -webkit-border-top-left-radius: 4px; + -webkit-border-top-right-radius: 4px; + -webkit-border-bottom-left-radius: 4px; + -webkit-border-bottom-right-radius: 4px; + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); +} + +.SelectItem { + font: 8pt Arial, Verdana, sans-serif; + padding-left: 2px; + padding-right: 12px; + border: 0px; +} + +span.SelectionMark { + margin-right: 4px; + font-family: monospace; + outline-style: none; + text-decoration: none; +} + +a.SelectItem { + display: block; + outline-style: none; + color: #000000; + text-decoration: none; + padding-left: 6px; + padding-right: 12px; +} + +a.SelectItem:focus, +a.SelectItem:active { + color: #000000; + outline-style: none; + text-decoration: none; +} + +a.SelectItem:hover { + color: #FFFFFF; + background-color: #3D578C; + outline-style: none; + text-decoration: none; + cursor: pointer; + display: block; +} + +/*---------------- Search results window */ + +iframe#MSearchResults { + width: 60ex; + height: 15em; +} + +#MSearchResultsWindow { + display: none; + position: absolute; + left: 0; top: 0; + border: 1px solid #000; + background-color: #EEF1F7; + z-index:10000; +} + +/* ----------------------------------- */ + + +#SRIndex { + clear:both; + padding-bottom: 15px; +} + +.SREntry { + font-size: 10pt; + padding-left: 1ex; +} + +.SRPage .SREntry { + font-size: 8pt; + padding: 1px 5px; +} + +body.SRPage { + margin: 5px 2px; +} + +.SRChildren { + padding-left: 3ex; padding-bottom: .5em +} + +.SRPage .SRChildren { + display: none; +} + +.SRSymbol { + font-weight: bold; + color: #425E97; + font-family: Arial, Verdana, sans-serif; + text-decoration: none; + outline: none; +} + +a.SRScope { + display: block; + color: #425E97; + font-family: Arial, Verdana, sans-serif; + text-decoration: none; + outline: none; +} + +a.SRSymbol:focus, a.SRSymbol:active, +a.SRScope:focus, a.SRScope:active { + text-decoration: underline; +} + +span.SRScope { + padding-left: 4px; + font-family: Arial, Verdana, sans-serif; +} + +.SRPage .SRStatus { + padding: 2px 5px; + font-size: 8pt; + font-style: italic; + font-family: Arial, Verdana, sans-serif; +} + +.SRResult { + display: none; +} + +div.searchresults { + margin-left: 10px; + margin-right: 10px; +} + +/*---------------- External search page results */ + +.searchresult { + background-color: #F0F3F8; +} + +.pages b { + color: white; + padding: 5px 5px 3px 5px; + background-image: url("../tab_a.png"); + background-repeat: repeat-x; + text-shadow: 0 1px 1px #000000; +} + +.pages { + line-height: 17px; + margin-left: 4px; + text-decoration: none; +} + +.hl { + font-weight: bold; +} + +#searchresults { + margin-bottom: 20px; +} + +.searchpages { + margin-top: 10px; +} + diff --git a/search/search.js b/search/search.js new file mode 100644 index 00000000..fb226f73 --- /dev/null +++ b/search/search.js @@ -0,0 +1,816 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file + */ +function convertToId(search) +{ + var result = ''; + for (i=0;i do a search + { + this.Search(); + } + } + + this.OnSearchSelectKey = function(evt) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==40 && this.searchIndex0) // Up + { + this.searchIndex--; + this.OnSelectItem(this.searchIndex); + } + else if (e.keyCode==13 || e.keyCode==27) + { + this.OnSelectItem(this.searchIndex); + this.CloseSelectionWindow(); + this.DOMSearchField().focus(); + } + return false; + } + + // --------- Actions + + // Closes the results window. + this.CloseResultsWindow = function() + { + this.DOMPopupSearchResultsWindow().style.display = 'none'; + this.DOMSearchClose().style.display = 'none'; + this.Activate(false); + } + + this.CloseSelectionWindow = function() + { + this.DOMSearchSelectWindow().style.display = 'none'; + } + + // Performs a search. + this.Search = function() + { + this.keyTimeout = 0; + + // strip leading whitespace + var searchValue = this.DOMSearchField().value.replace(/^ +/, ""); + + var code = searchValue.toLowerCase().charCodeAt(0); + var idxChar = searchValue.substr(0, 1).toLowerCase(); + if ( 0xD800 <= code && code <= 0xDBFF && searchValue > 1) // surrogate pair + { + idxChar = searchValue.substr(0, 2); + } + + var resultsPage; + var resultsPageWithSearch; + var hasResultsPage; + + var idx = indexSectionsWithContent[this.searchIndex].indexOf(idxChar); + if (idx!=-1) + { + var hexCode=idx.toString(16); + resultsPage = this.resultsPath + '/' + indexSectionNames[this.searchIndex] + '_' + hexCode + this.extension; + resultsPageWithSearch = resultsPage+'?'+escape(searchValue); + hasResultsPage = true; + } + else // nothing available for this search term + { + resultsPage = this.resultsPath + '/nomatches' + this.extension; + resultsPageWithSearch = resultsPage; + hasResultsPage = false; + } + + window.frames.MSearchResults.location = resultsPageWithSearch; + var domPopupSearchResultsWindow = this.DOMPopupSearchResultsWindow(); + + if (domPopupSearchResultsWindow.style.display!='block') + { + var domSearchBox = this.DOMSearchBox(); + this.DOMSearchClose().style.display = 'inline-block'; + if (this.insideFrame) + { + var domPopupSearchResults = this.DOMPopupSearchResults(); + domPopupSearchResultsWindow.style.position = 'relative'; + domPopupSearchResultsWindow.style.display = 'block'; + var width = document.body.clientWidth - 8; // the -8 is for IE :-( + domPopupSearchResultsWindow.style.width = width + 'px'; + domPopupSearchResults.style.width = width + 'px'; + } + else + { + var domPopupSearchResults = this.DOMPopupSearchResults(); + var left = getXPos(domSearchBox) + 150; // domSearchBox.offsetWidth; + var top = getYPos(domSearchBox) + 20; // domSearchBox.offsetHeight + 1; + domPopupSearchResultsWindow.style.display = 'block'; + left -= domPopupSearchResults.offsetWidth; + domPopupSearchResultsWindow.style.top = top + 'px'; + domPopupSearchResultsWindow.style.left = left + 'px'; + } + } + + this.lastSearchValue = searchValue; + this.lastResultsPage = resultsPage; + } + + // -------- Activation Functions + + // Activates or deactivates the search panel, resetting things to + // their default values if necessary. + this.Activate = function(isActive) + { + if (isActive || // open it + this.DOMPopupSearchResultsWindow().style.display == 'block' + ) + { + this.DOMSearchBox().className = 'MSearchBoxActive'; + + var searchField = this.DOMSearchField(); + + if (searchField.value == this.searchLabel) // clear "Search" term upon entry + { + searchField.value = ''; + this.searchActive = true; + } + } + else if (!isActive) // directly remove the panel + { + this.DOMSearchBox().className = 'MSearchBoxInactive'; + this.DOMSearchField().value = this.searchLabel; + this.searchActive = false; + this.lastSearchValue = '' + this.lastResultsPage = ''; + } + } +} + +// ----------------------------------------------------------------------- + +// The class that handles everything on the search results page. +function SearchResults(name) +{ + // The number of matches from the last run of . + this.lastMatchCount = 0; + this.lastKey = 0; + this.repeatOn = false; + + // Toggles the visibility of the passed element ID. + this.FindChildElement = function(id) + { + var parentElement = document.getElementById(id); + var element = parentElement.firstChild; + + while (element && element!=parentElement) + { + if (element.nodeName.toLowerCase() == 'div' && element.className == 'SRChildren') + { + return element; + } + + if (element.nodeName.toLowerCase() == 'div' && element.hasChildNodes()) + { + element = element.firstChild; + } + else if (element.nextSibling) + { + element = element.nextSibling; + } + else + { + do + { + element = element.parentNode; + } + while (element && element!=parentElement && !element.nextSibling); + + if (element && element!=parentElement) + { + element = element.nextSibling; + } + } + } + } + + this.Toggle = function(id) + { + var element = this.FindChildElement(id); + if (element) + { + if (element.style.display == 'block') + { + element.style.display = 'none'; + } + else + { + element.style.display = 'block'; + } + } + } + + // Searches for the passed string. If there is no parameter, + // it takes it from the URL query. + // + // Always returns true, since other documents may try to call it + // and that may or may not be possible. + this.Search = function(search) + { + if (!search) // get search word from URL + { + search = window.location.search; + search = search.substring(1); // Remove the leading '?' + search = unescape(search); + } + + search = search.replace(/^ +/, ""); // strip leading spaces + search = search.replace(/ +$/, ""); // strip trailing spaces + search = search.toLowerCase(); + search = convertToId(search); + + var resultRows = document.getElementsByTagName("div"); + var matches = 0; + + var i = 0; + while (i < resultRows.length) + { + var row = resultRows.item(i); + if (row.className == "SRResult") + { + var rowMatchName = row.id.toLowerCase(); + rowMatchName = rowMatchName.replace(/^sr\d*_/, ''); // strip 'sr123_' + + if (search.length<=rowMatchName.length && + rowMatchName.substr(0, search.length)==search) + { + row.style.display = 'block'; + matches++; + } + else + { + row.style.display = 'none'; + } + } + i++; + } + document.getElementById("Searching").style.display='none'; + if (matches == 0) // no results + { + document.getElementById("NoMatches").style.display='block'; + } + else // at least one result + { + document.getElementById("NoMatches").style.display='none'; + } + this.lastMatchCount = matches; + return true; + } + + // return the first item with index index or higher that is visible + this.NavNext = function(index) + { + var focusItem; + while (1) + { + var focusName = 'Item'+index; + focusItem = document.getElementById(focusName); + if (focusItem && focusItem.parentNode.parentNode.style.display=='block') + { + break; + } + else if (!focusItem) // last element + { + break; + } + focusItem=null; + index++; + } + return focusItem; + } + + this.NavPrev = function(index) + { + var focusItem; + while (1) + { + var focusName = 'Item'+index; + focusItem = document.getElementById(focusName); + if (focusItem && focusItem.parentNode.parentNode.style.display=='block') + { + break; + } + else if (!focusItem) // last element + { + break; + } + focusItem=null; + index--; + } + return focusItem; + } + + this.ProcessKeys = function(e) + { + if (e.type == "keydown") + { + this.repeatOn = false; + this.lastKey = e.keyCode; + } + else if (e.type == "keypress") + { + if (!this.repeatOn) + { + if (this.lastKey) this.repeatOn = true; + return false; // ignore first keypress after keydown + } + } + else if (e.type == "keyup") + { + this.lastKey = 0; + this.repeatOn = false; + } + return this.lastKey!=0; + } + + this.Nav = function(evt,itemIndex) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==13) return true; + if (!this.ProcessKeys(e)) return false; + + if (this.lastKey==38) // Up + { + var newIndex = itemIndex-1; + var focusItem = this.NavPrev(newIndex); + if (focusItem) + { + var child = this.FindChildElement(focusItem.parentNode.parentNode.id); + if (child && child.style.display == 'block') // children visible + { + var n=0; + var tmpElem; + while (1) // search for last child + { + tmpElem = document.getElementById('Item'+newIndex+'_c'+n); + if (tmpElem) + { + focusItem = tmpElem; + } + else // found it! + { + break; + } + n++; + } + } + } + if (focusItem) + { + focusItem.focus(); + } + else // return focus to search field + { + parent.document.getElementById("MSearchField").focus(); + } + } + else if (this.lastKey==40) // Down + { + var newIndex = itemIndex+1; + var focusItem; + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem && elem.style.display == 'block') // children visible + { + focusItem = document.getElementById('Item'+itemIndex+'_c0'); + } + if (!focusItem) focusItem = this.NavNext(newIndex); + if (focusItem) focusItem.focus(); + } + else if (this.lastKey==39) // Right + { + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem) elem.style.display = 'block'; + } + else if (this.lastKey==37) // Left + { + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem) elem.style.display = 'none'; + } + else if (this.lastKey==27) // Escape + { + parent.searchBox.CloseResultsWindow(); + parent.document.getElementById("MSearchField").focus(); + } + else if (this.lastKey==13) // Enter + { + return true; + } + return false; + } + + this.NavChild = function(evt,itemIndex,childIndex) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==13) return true; + if (!this.ProcessKeys(e)) return false; + + if (this.lastKey==38) // Up + { + if (childIndex>0) + { + var newIndex = childIndex-1; + document.getElementById('Item'+itemIndex+'_c'+newIndex).focus(); + } + else // already at first child, jump to parent + { + document.getElementById('Item'+itemIndex).focus(); + } + } + else if (this.lastKey==40) // Down + { + var newIndex = childIndex+1; + var elem = document.getElementById('Item'+itemIndex+'_c'+newIndex); + if (!elem) // last child, jump to parent next parent + { + elem = this.NavNext(itemIndex+1); + } + if (elem) + { + elem.focus(); + } + } + else if (this.lastKey==27) // Escape + { + parent.searchBox.CloseResultsWindow(); + parent.document.getElementById("MSearchField").focus(); + } + else if (this.lastKey==13) // Enter + { + return true; + } + return false; + } +} + +function setKeyActions(elem,action) +{ + elem.setAttribute('onkeydown',action); + elem.setAttribute('onkeypress',action); + elem.setAttribute('onkeyup',action); +} + +function setClassAttr(elem,attr) +{ + elem.setAttribute('class',attr); + elem.setAttribute('className',attr); +} + +function createResults() +{ + var results = document.getElementById("SRResults"); + for (var e=0; e + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/typedefs_0.js b/search/typedefs_0.js new file mode 100644 index 00000000..22a8edf7 --- /dev/null +++ b/search/typedefs_0.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['serverversion_557',['ServerVersion',['../classfranka_1_1Gripper.html#a613bf52d9433b733685d0fb9ea71602e',1,'franka::Gripper::ServerVersion()'],['../classfranka_1_1Robot.html#ad1dd3dccff6f33691d2c66eaa5ac5a10',1,'franka::Robot::ServerVersion()'],['../classfranka_1_1VacuumGripper.html#a7b1d752680134e2a9df347002c6ace61',1,'franka::VacuumGripper::ServerVersion()']]] +]; diff --git a/search/variables_0.html b/search/variables_0.html new file mode 100644 index 00000000..1e477c08 --- /dev/null +++ b/search/variables_0.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_0.js b/search/variables_0.js new file mode 100644 index 00000000..ec113fae --- /dev/null +++ b/search/variables_0.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['actual_5fpower_422',['actual_power',['../structfranka_1_1VacuumGripperState.html#a4230c68698cdbf6c1c560e181133bdc3',1,'franka::VacuumGripperState']]] +]; diff --git a/search/variables_1.html b/search/variables_1.html new file mode 100644 index 00000000..ea73d9a4 --- /dev/null +++ b/search/variables_1.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_1.js b/search/variables_1.js new file mode 100644 index 00000000..c115ff9a --- /dev/null +++ b/search/variables_1.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['base_5facceleration_5finitialization_5ftimeout_423',['base_acceleration_initialization_timeout',['../structfranka_1_1Errors.html#a4dc331a7ae3242ea43e6fbf7e21c695a',1,'franka::Errors']]], + ['base_5facceleration_5finvalid_5freading_424',['base_acceleration_invalid_reading',['../structfranka_1_1Errors.html#a8467b7b8a3a68c3e0be7adc39933cb0e',1,'franka::Errors']]] +]; diff --git a/search/variables_10.html b/search/variables_10.html new file mode 100644 index 00000000..dc9920b6 --- /dev/null +++ b/search/variables_10.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_10.js b/search/variables_10.js new file mode 100644 index 00000000..52be8b46 --- /dev/null +++ b/search/variables_10.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['self_5fcollision_5favoidance_5fviolation_543',['self_collision_avoidance_violation',['../structfranka_1_1Errors.html#adf68f6333624cb5558864441a991de8c',1,'franka::Errors']]], + ['server_5fversion_544',['server_version',['../structfranka_1_1IncompatibleVersionException.html#a0928098d8c32f405d17b65a0f004b5ab',1,'franka::IncompatibleVersionException']]], + ['start_5felbow_5fsign_5finconsistent_545',['start_elbow_sign_inconsistent',['../structfranka_1_1Errors.html#aa6de1956ac056792a1dea6b9ddd52a50',1,'franka::Errors']]], + ['state_546',['state',['../structfranka_1_1Record.html#a58249658c9549fbc792eea90e7b6a7cc',1,'franka::Record']]] +]; diff --git a/search/variables_11.html b/search/variables_11.html new file mode 100644 index 00000000..704bcb18 --- /dev/null +++ b/search/variables_11.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_11.js b/search/variables_11.js new file mode 100644 index 00000000..3250cf19 --- /dev/null +++ b/search/variables_11.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['tau_5fext_5fhat_5ffiltered_547',['tau_ext_hat_filtered',['../structfranka_1_1RobotState.html#acdef8005828d193e45b128085a9e363b',1,'franka::RobotState']]], + ['tau_5fj_548',['tau_J',['../classfranka_1_1Torques.html#ac2a266cc2d3b7e0fb4f8eff045dbaed8',1,'franka::Torques::tau_J()'],['../structfranka_1_1RobotState.html#ad90e2518d661da0d8fa4c864bae210e5',1,'franka::RobotState::tau_J()']]], + ['tau_5fj_5fd_549',['tau_J_d',['../structfranka_1_1RobotState.html#a7086a89a2705810f93a3a95d43df2d9d',1,'franka::RobotState']]], + ['tau_5fj_5frange_5fviolation_550',['tau_j_range_violation',['../structfranka_1_1Errors.html#a1491f8428341649befa3d088aebb317e',1,'franka::Errors']]], + ['temperature_551',['temperature',['../structfranka_1_1GripperState.html#aa6733fa786dbf3b073acbaf3779e34b3',1,'franka::GripperState']]], + ['theta_552',['theta',['../structfranka_1_1RobotState.html#aa34145d77dd411d7ca578c355f0ba2b4',1,'franka::RobotState']]], + ['time_553',['time',['../structfranka_1_1GripperState.html#a80bf474b0e4351e2eefab62d1bd10c07',1,'franka::GripperState::time()'],['../structfranka_1_1RobotState.html#aabfdabeaef8c1858c52dd32344bdd039',1,'franka::RobotState::time()'],['../structfranka_1_1VacuumGripperState.html#aaa98eb6e1888094aace2014121a468ab',1,'franka::VacuumGripperState::time()']]], + ['torques_554',['torques',['../structfranka_1_1RobotCommand.html#a8b23e8b669b1fd594988ecdbf54bfbce',1,'franka::RobotCommand']]] +]; diff --git a/search/variables_12.html b/search/variables_12.html new file mode 100644 index 00000000..a3a32eb8 --- /dev/null +++ b/search/variables_12.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_12.js b/search/variables_12.js new file mode 100644 index 00000000..fd631ed3 --- /dev/null +++ b/search/variables_12.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['vacuum_555',['vacuum',['../structfranka_1_1VacuumGripperState.html#ae94720737193caa696a47563a8efe6a8',1,'franka::VacuumGripperState']]] +]; diff --git a/search/variables_13.html b/search/variables_13.html new file mode 100644 index 00000000..7d05bd86 --- /dev/null +++ b/search/variables_13.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_13.js b/search/variables_13.js new file mode 100644 index 00000000..87bcc4fa --- /dev/null +++ b/search/variables_13.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['width_556',['width',['../structfranka_1_1GripperState.html#adf095f446ec39a9a48e120b209dcd6e9',1,'franka::GripperState']]] +]; diff --git a/search/variables_2.html b/search/variables_2.html new file mode 100644 index 00000000..0580462e --- /dev/null +++ b/search/variables_2.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_2.js b/search/variables_2.js new file mode 100644 index 00000000..793534a5 --- /dev/null +++ b/search/variables_2.js @@ -0,0 +1,31 @@ +var searchData= +[ + ['cartesian_5fcollision_425',['cartesian_collision',['../structfranka_1_1RobotState.html#a52c20478f4c1e162df38582ea9bda044',1,'franka::RobotState']]], + ['cartesian_5fcontact_426',['cartesian_contact',['../structfranka_1_1RobotState.html#a7fc1f0358d2104d39d301d70544fa6c1',1,'franka::RobotState']]], + ['cartesian_5fmotion_5fgenerator_5facceleration_5fdiscontinuity_427',['cartesian_motion_generator_acceleration_discontinuity',['../structfranka_1_1Errors.html#a10c6ac36bf48b4a9edf91e74d9bc4837',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5felbow_5flimit_5fviolation_428',['cartesian_motion_generator_elbow_limit_violation',['../structfranka_1_1Errors.html#ac21ebdc1e0e8fb3099a7dce284550c4c',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5felbow_5fsign_5finconsistent_429',['cartesian_motion_generator_elbow_sign_inconsistent',['../structfranka_1_1Errors.html#a58b0e1199c9dded5a32bfeb110e63037',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fjoint_5facceleration_5fdiscontinuity_430',['cartesian_motion_generator_joint_acceleration_discontinuity',['../structfranka_1_1Errors.html#a2e223ef3c771709a6a3f094adf12f9cb',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fjoint_5fposition_5flimits_5fviolation_431',['cartesian_motion_generator_joint_position_limits_violation',['../structfranka_1_1Errors.html#a73aef7473fd6d1d5b207e68fa35948c5',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fjoint_5fvelocity_5fdiscontinuity_432',['cartesian_motion_generator_joint_velocity_discontinuity',['../structfranka_1_1Errors.html#a1c8c56766fefc19fda5d5de909ca5b37',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fjoint_5fvelocity_5flimits_5fviolation_433',['cartesian_motion_generator_joint_velocity_limits_violation',['../structfranka_1_1Errors.html#a435d16d62a123bfbf578bc76e3780605',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fstart_5felbow_5finvalid_434',['cartesian_motion_generator_start_elbow_invalid',['../structfranka_1_1Errors.html#a6d905b803bbe8a7be8490f2a94ba524a',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fvelocity_5fdiscontinuity_435',['cartesian_motion_generator_velocity_discontinuity',['../structfranka_1_1Errors.html#a17e4a9b6b7dc4cc12c1328d36cac3eaf',1,'franka::Errors']]], + ['cartesian_5fmotion_5fgenerator_5fvelocity_5flimits_5fviolation_436',['cartesian_motion_generator_velocity_limits_violation',['../structfranka_1_1Errors.html#a91437c081452ef708563346b102ba894',1,'franka::Errors']]], + ['cartesian_5fpose_437',['cartesian_pose',['../structfranka_1_1RobotCommand.html#acce2090d696ebb9759fd0f37fd35a298',1,'franka::RobotCommand']]], + ['cartesian_5fposition_5flimits_5fviolation_438',['cartesian_position_limits_violation',['../structfranka_1_1Errors.html#a41c8b50ecbb015a2dba1a3dbbff694b6',1,'franka::Errors']]], + ['cartesian_5fposition_5fmotion_5fgenerator_5finvalid_5fframe_439',['cartesian_position_motion_generator_invalid_frame',['../structfranka_1_1Errors.html#aa1952c6da2f81578861a19b947c97b85',1,'franka::Errors']]], + ['cartesian_5fposition_5fmotion_5fgenerator_5fstart_5fpose_5finvalid_440',['cartesian_position_motion_generator_start_pose_invalid',['../structfranka_1_1Errors.html#aa910fad4992b91be1ea1c321ee9b7a1e',1,'franka::Errors']]], + ['cartesian_5freflex_441',['cartesian_reflex',['../structfranka_1_1Errors.html#a47bd58b0ab2198e4d038e0a24eafb310',1,'franka::Errors']]], + ['cartesian_5fspline_5fmotion_5fgenerator_5fviolation_442',['cartesian_spline_motion_generator_violation',['../structfranka_1_1Errors.html#a5617689cd7e875baebcecf054513f0c4',1,'franka::Errors']]], + ['cartesian_5fvelocities_443',['cartesian_velocities',['../structfranka_1_1RobotCommand.html#a04b4841130fab920936190be1bc5dba3',1,'franka::RobotCommand']]], + ['cartesian_5fvelocity_5fprofile_5fsafety_5fviolation_444',['cartesian_velocity_profile_safety_violation',['../structfranka_1_1Errors.html#afc093fc5f99e1f6cab6de4fa9bc32692',1,'franka::Errors']]], + ['cartesian_5fvelocity_5fviolation_445',['cartesian_velocity_violation',['../structfranka_1_1Errors.html#a382fbec6b463ddcc2cbfd90340021ff1',1,'franka::Errors']]], + ['command_446',['command',['../structfranka_1_1Record.html#a8106f2ba9c2cf5ec7cbcf914c4c99e9c',1,'franka::Record']]], + ['communication_5fconstraints_5fviolation_447',['communication_constraints_violation',['../structfranka_1_1Errors.html#a4d17af86c1ebb698c218796fa15f9bd7',1,'franka::Errors']]], + ['control_5fcommand_5fsuccess_5frate_448',['control_command_success_rate',['../structfranka_1_1RobotState.html#af208572613a6afcdc61a24970c71fa28',1,'franka::RobotState']]], + ['control_5ffinished_449',['control_finished',['../classfranka_1_1ActiveControl.html#afa521707548926e9d1e38e4b83496db2',1,'franka::ActiveControl']]], + ['control_5flock_450',['control_lock',['../classfranka_1_1ActiveControl.html#aed53605877b237435581e36f4c0b34a4',1,'franka::ActiveControl']]], + ['controller_5ftorque_5fdiscontinuity_451',['controller_torque_discontinuity',['../structfranka_1_1Errors.html#af40d93759ace9ee6026208110692a732',1,'franka::Errors']]], + ['current_5ferrors_452',['current_errors',['../structfranka_1_1RobotState.html#abc5515f7a27f5de82396ea792a5ecb48',1,'franka::RobotState']]] +]; diff --git a/search/variables_3.html b/search/variables_3.html new file mode 100644 index 00000000..0d69e761 --- /dev/null +++ b/search/variables_3.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_3.js b/search/variables_3.js new file mode 100644 index 00000000..ef2a3234 --- /dev/null +++ b/search/variables_3.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['ddelbow_5fc_453',['ddelbow_c',['../structfranka_1_1RobotState.html#a1e5b6caf84249b1129491dbbcb1fc2e6',1,'franka::RobotState']]], + ['ddq_5fd_454',['ddq_d',['../structfranka_1_1RobotState.html#a6251e748cf72f4b86bcfdcb97d77ace2',1,'franka::RobotState']]], + ['delbow_5fc_455',['delbow_c',['../structfranka_1_1RobotState.html#a57c2c145e9f79010adf23085b8a9c5ad',1,'franka::RobotState']]], + ['device_5fstatus_456',['device_status',['../structfranka_1_1VacuumGripperState.html#ab44560b09c4a959c06ddafbd7f21da02',1,'franka::VacuumGripperState']]], + ['dq_457',['dq',['../classfranka_1_1JointVelocities.html#a14fddb6fe7a7c4034dc82c283de8c2d3',1,'franka::JointVelocities::dq()'],['../structfranka_1_1RobotState.html#af372a0081d72bc7b4fe873f99c7b2d8c',1,'franka::RobotState::dq()']]], + ['dq_5fd_458',['dq_d',['../structfranka_1_1RobotState.html#aed294a088be27b927be9575a18bec949',1,'franka::RobotState']]], + ['dtau_5fj_459',['dtau_J',['../structfranka_1_1RobotState.html#ae6b0d4ee0d7b36240a2165e6ded6f4b9',1,'franka::RobotState']]], + ['dtheta_460',['dtheta',['../structfranka_1_1RobotState.html#a271db0a55dd346715ed8a0daf3f8887c',1,'franka::RobotState']]] +]; diff --git a/search/variables_4.html b/search/variables_4.html new file mode 100644 index 00000000..a4b6506b --- /dev/null +++ b/search/variables_4.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_4.js b/search/variables_4.js new file mode 100644 index 00000000..1c140d56 --- /dev/null +++ b/search/variables_4.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['ee_5ft_5fk_461',['EE_T_K',['../structfranka_1_1RobotState.html#aeb78a3b4b76d4f57b9898cbea3a0f7aa',1,'franka::RobotState']]], + ['elbow_462',['elbow',['../classfranka_1_1CartesianPose.html#abef660743df9cf94d11c556d9c3d25be',1,'franka::CartesianPose::elbow()'],['../classfranka_1_1CartesianVelocities.html#a6419df1399d3dfab79b1654b94ced344',1,'franka::CartesianVelocities::elbow()'],['../structfranka_1_1RobotState.html#a43485841c427d70e7f36a912cc3116d1',1,'franka::RobotState::elbow()']]], + ['elbow_5fc_463',['elbow_c',['../structfranka_1_1RobotState.html#a16cfc844894e8b5b1ad829be529962f0',1,'franka::RobotState']]], + ['elbow_5fd_464',['elbow_d',['../structfranka_1_1RobotState.html#a295dada05d8588fc3c19a74fd427dcc0',1,'franka::RobotState']]] +]; diff --git a/search/variables_5.html b/search/variables_5.html new file mode 100644 index 00000000..7e345d16 --- /dev/null +++ b/search/variables_5.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_5.js b/search/variables_5.js new file mode 100644 index 00000000..426b2bcc --- /dev/null +++ b/search/variables_5.js @@ -0,0 +1,10 @@ +var searchData= +[ + ['f_5ft_5fee_465',['F_T_EE',['../structfranka_1_1RobotState.html#a705b85049fef747008b0eba8284c8057',1,'franka::RobotState']]], + ['f_5ft_5fne_466',['F_T_NE',['../structfranka_1_1RobotState.html#a88142795c453775c360e18d8a6570d15',1,'franka::RobotState']]], + ['f_5fx_5fcee_467',['F_x_Cee',['../structfranka_1_1RobotState.html#a907c4561d8f1c1a2af7980cf58ceb112',1,'franka::RobotState']]], + ['f_5fx_5fcload_468',['F_x_Cload',['../structfranka_1_1RobotState.html#a48e921e6215ad32f36e424b4d7b66a89',1,'franka::RobotState']]], + ['f_5fx_5fctotal_469',['F_x_Ctotal',['../structfranka_1_1RobotState.html#a72ee7362018e3c9e95e3c41e857bfd8d',1,'franka::RobotState']]], + ['force_5fcontrol_5fsafety_5fviolation_470',['force_control_safety_violation',['../structfranka_1_1Errors.html#ae7b19674da28b11ba970c30c7d800923',1,'franka::Errors']]], + ['force_5fcontroller_5fdesired_5fforce_5ftolerance_5fviolation_471',['force_controller_desired_force_tolerance_violation',['../structfranka_1_1Errors.html#ae474f20a64b2585dbe6496966dddff0a',1,'franka::Errors']]] +]; diff --git a/search/variables_6.html b/search/variables_6.html new file mode 100644 index 00000000..7d48e75e --- /dev/null +++ b/search/variables_6.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_6.js b/search/variables_6.js new file mode 100644 index 00000000..d917842f --- /dev/null +++ b/search/variables_6.js @@ -0,0 +1,9 @@ +var searchData= +[ + ['i_5fee_472',['I_ee',['../structfranka_1_1RobotState.html#a74cee1beb5d400694133deea2846e611',1,'franka::RobotState']]], + ['i_5fload_473',['I_load',['../structfranka_1_1RobotState.html#a5b194153497eff98049681f852118f82',1,'franka::RobotState']]], + ['i_5ftotal_474',['I_total',['../structfranka_1_1RobotState.html#ad9120ae7b7613e77df8c1c3eba8fb033',1,'franka::RobotState']]], + ['in_5fcontrol_5frange_475',['in_control_range',['../structfranka_1_1VacuumGripperState.html#a70c1b14b10c2a79511fcada258c7e0ba',1,'franka::VacuumGripperState']]], + ['instability_5fdetected_476',['instability_detected',['../structfranka_1_1Errors.html#aebb701987262097687d21b3cf1bc8930',1,'franka::Errors']]], + ['is_5fgrasped_477',['is_grasped',['../structfranka_1_1GripperState.html#aa65b46313e740454ead9c9ea27e7bf8d',1,'franka::GripperState']]] +]; diff --git a/search/variables_7.html b/search/variables_7.html new file mode 100644 index 00000000..5c263409 --- /dev/null +++ b/search/variables_7.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_7.js b/search/variables_7.js new file mode 100644 index 00000000..d01d1ae0 --- /dev/null +++ b/search/variables_7.js @@ -0,0 +1,18 @@ +var searchData= +[ + ['joint_5fcollision_478',['joint_collision',['../structfranka_1_1RobotState.html#a38757bafd4dd8e138410de1dca0c36f8',1,'franka::RobotState']]], + ['joint_5fcontact_479',['joint_contact',['../structfranka_1_1RobotState.html#a7243c652a8efe58c343a0d1252302fa4',1,'franka::RobotState']]], + ['joint_5fmotion_5fgenerator_5facceleration_5fdiscontinuity_480',['joint_motion_generator_acceleration_discontinuity',['../structfranka_1_1Errors.html#a633195adca91f5ecaf1506da12f3311f',1,'franka::Errors']]], + ['joint_5fmotion_5fgenerator_5fposition_5flimits_5fviolation_481',['joint_motion_generator_position_limits_violation',['../structfranka_1_1Errors.html#a9536ad072868b90525c56143cbb956ef',1,'franka::Errors']]], + ['joint_5fmotion_5fgenerator_5fvelocity_5fdiscontinuity_482',['joint_motion_generator_velocity_discontinuity',['../structfranka_1_1Errors.html#abd6da8e6a32d817a7b4848a24efd9379',1,'franka::Errors']]], + ['joint_5fmotion_5fgenerator_5fvelocity_5flimits_5fviolation_483',['joint_motion_generator_velocity_limits_violation',['../structfranka_1_1Errors.html#ae211638df9b0e23905c8a9d36e249207',1,'franka::Errors']]], + ['joint_5fmove_5fin_5fwrong_5fdirection_484',['joint_move_in_wrong_direction',['../structfranka_1_1Errors.html#a7d3a6480cbe572fd46e579b43732edc9',1,'franka::Errors']]], + ['joint_5fp2p_5finsufficient_5ftorque_5ffor_5fplanning_485',['joint_p2p_insufficient_torque_for_planning',['../structfranka_1_1Errors.html#a1c78be870253b510a4516acf14c2d3e3',1,'franka::Errors']]], + ['joint_5fposition_5flimits_5fviolation_486',['joint_position_limits_violation',['../structfranka_1_1Errors.html#a44ba0d45e52639280d32cf447f967e29',1,'franka::Errors']]], + ['joint_5fposition_5fmotion_5fgenerator_5fstart_5fpose_5finvalid_487',['joint_position_motion_generator_start_pose_invalid',['../structfranka_1_1Errors.html#a7af91cbf61dc79304bff3ffadc51ea86',1,'franka::Errors']]], + ['joint_5fpositions_488',['joint_positions',['../structfranka_1_1RobotCommand.html#a086afcec596eae5284b6c39dc1452280',1,'franka::RobotCommand']]], + ['joint_5freflex_489',['joint_reflex',['../structfranka_1_1Errors.html#afb0928680c586e73d4e2cd4b42c7fe48',1,'franka::Errors']]], + ['joint_5fvelocities_490',['joint_velocities',['../structfranka_1_1RobotCommand.html#a049657cf2bbbb53d6ffa5581721e7b71',1,'franka::RobotCommand']]], + ['joint_5fvelocity_5fviolation_491',['joint_velocity_violation',['../structfranka_1_1Errors.html#a803ac4acbc26350602ea2eb02b7b30c4',1,'franka::Errors']]], + ['joint_5fvia_5fmotion_5fgenerator_5fplanning_5fjoint_5flimit_5fviolation_492',['joint_via_motion_generator_planning_joint_limit_violation',['../structfranka_1_1Errors.html#aef3c74f48978545187ee2dc3a96db1c8',1,'franka::Errors']]] +]; diff --git a/search/variables_8.html b/search/variables_8.html new file mode 100644 index 00000000..dc9ec54a --- /dev/null +++ b/search/variables_8.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_8.js b/search/variables_8.js new file mode 100644 index 00000000..7f6763b5 --- /dev/null +++ b/search/variables_8.js @@ -0,0 +1,24 @@ +var searchData= +[ + ['k_5ff_5fext_5fhat_5fk_493',['K_F_ext_hat_K',['../structfranka_1_1RobotState.html#a96267d443c05fcc58d7ac32f63912649',1,'franka::RobotState']]], + ['kdefaultcutofffrequency_494',['kDefaultCutoffFrequency',['../lowpass__filter_8h.html#ad8e3b7da346e03181ab5ac138a4171d4',1,'franka']]], + ['kdeltat_495',['kDeltaT',['../rate__limiting_8h.html#a1e207a0d5a6e90c1e1a78e6e1057120a',1,'franka']]], + ['kfactorcartesianrotationposeinterface_496',['kFactorCartesianRotationPoseInterface',['../rate__limiting_8h.html#a19166d1a64c5a84f80b4ed3aa0bfb3a0',1,'franka']]], + ['kjointvelocitylimitstolerance_497',['kJointVelocityLimitsTolerance',['../rate__limiting_8h.html#a39b6d9504e2844d289f834471994d889',1,'franka']]], + ['klimiteps_498',['kLimitEps',['../rate__limiting_8h.html#aad1f9b575274830b8da9e638559d424b',1,'franka']]], + ['kmaxcutofffrequency_499',['kMaxCutoffFrequency',['../lowpass__filter_8h.html#adb10b364af8deb9e17d9bcc1ff2695be',1,'franka']]], + ['kmaxelbowacceleration_500',['kMaxElbowAcceleration',['../rate__limiting_8h.html#af365e574ad7b1580ce15e30dd909b3ba',1,'franka']]], + ['kmaxelbowjerk_501',['kMaxElbowJerk',['../rate__limiting_8h.html#adc70178204d4da073c78de777a2dff74',1,'franka']]], + ['kmaxelbowvelocity_502',['kMaxElbowVelocity',['../rate__limiting_8h.html#a2896b2e0c8bd96f9ee242c1203ac3483',1,'franka']]], + ['kmaxjointacceleration_503',['kMaxJointAcceleration',['../rate__limiting_8h.html#a826ecf0b7d214df69c1ee416d3e66b93',1,'franka']]], + ['kmaxjointjerk_504',['kMaxJointJerk',['../rate__limiting_8h.html#a600a21a6151ff2eee38294293dd8aeec',1,'franka']]], + ['kmaxrotationalacceleration_505',['kMaxRotationalAcceleration',['../rate__limiting_8h.html#a5e3d5c95ba72f9660f17f8ebf1e0aa2e',1,'franka']]], + ['kmaxrotationaljerk_506',['kMaxRotationalJerk',['../rate__limiting_8h.html#a259520ce1b6b5b85a88d05262286820d',1,'franka']]], + ['kmaxrotationalvelocity_507',['kMaxRotationalVelocity',['../rate__limiting_8h.html#aafb1f5ef8f8a7abd546edea498c18b45',1,'franka']]], + ['kmaxtorquerate_508',['kMaxTorqueRate',['../rate__limiting_8h.html#a6c1a0e9a5e1f375d2aad61edac907d4e',1,'franka']]], + ['kmaxtranslationalacceleration_509',['kMaxTranslationalAcceleration',['../rate__limiting_8h.html#a3803b1a54ba526ccaa4fa0d15446f3db',1,'franka']]], + ['kmaxtranslationaljerk_510',['kMaxTranslationalJerk',['../rate__limiting_8h.html#a46b8f11959ed3f731a0914f524af8e69',1,'franka']]], + ['kmaxtranslationalvelocity_511',['kMaxTranslationalVelocity',['../rate__limiting_8h.html#a857e1e5e18d688ec7095264a629bf474',1,'franka']]], + ['knormeps_512',['kNormEps',['../rate__limiting_8h.html#a420d72830a872ef375d9d6cbb1c439b5',1,'franka']]], + ['ktolnumberpacketslost_513',['kTolNumberPacketsLost',['../rate__limiting_8h.html#a664b546834ceecd4e3220ffa92f1172c',1,'franka']]] +]; diff --git a/search/variables_9.html b/search/variables_9.html new file mode 100644 index 00000000..7b014750 --- /dev/null +++ b/search/variables_9.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_9.js b/search/variables_9.js new file mode 100644 index 00000000..868126b3 --- /dev/null +++ b/search/variables_9.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['last_5fmotion_5ferrors_514',['last_motion_errors',['../structfranka_1_1RobotState.html#a06d7019f85339409e932dc086b7a260b',1,'franka::RobotState']]], + ['last_5fread_5faccess_515',['last_read_access',['../classfranka_1_1ActiveControl.html#a226304deac8032ed6c8428caa60c9fb4',1,'franka::ActiveControl']]], + ['library_5fversion_516',['library_version',['../structfranka_1_1IncompatibleVersionException.html#a81e6d7f01965ed7ee34f83dc3883ad01',1,'franka::IncompatibleVersionException']]], + ['log_517',['log',['../structfranka_1_1ControlException.html#ae57f0ac0a9aa195057af1f1cc712b41e',1,'franka::ControlException']]] +]; diff --git a/search/variables_a.html b/search/variables_a.html new file mode 100644 index 00000000..52a724d1 --- /dev/null +++ b/search/variables_a.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_a.js b/search/variables_a.js new file mode 100644 index 00000000..c7111afd --- /dev/null +++ b/search/variables_a.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['m_5fee_518',['m_ee',['../structfranka_1_1RobotState.html#af982a16246e33c1495ec02972a36bce3',1,'franka::RobotState']]], + ['m_5fload_519',['m_load',['../structfranka_1_1RobotState.html#a99ea4ab9c5a42a5c17365ed8fd730cd1',1,'franka::RobotState']]], + ['m_5ftotal_520',['m_total',['../structfranka_1_1RobotState.html#a87880d4693c8f576ebdabf00f4d4f981',1,'franka::RobotState']]], + ['max_5fgoal_5fpose_5fdeviation_5fviolation_521',['max_goal_pose_deviation_violation',['../structfranka_1_1Errors.html#ac55d3624087e606cb4ffab121869d580',1,'franka::Errors']]], + ['max_5fpath_5fpose_5fdeviation_5fviolation_522',['max_path_pose_deviation_violation',['../structfranka_1_1Errors.html#ad90cffe703ca1b782007f3ba49da587c',1,'franka::Errors']]], + ['max_5fwidth_523',['max_width',['../structfranka_1_1GripperState.html#ab71a26356c2898c49609bf991843e166',1,'franka::GripperState']]], + ['motion_5ffinished_524',['motion_finished',['../structfranka_1_1Finishable.html#a5d48028c0f912d4a089e6220d8715f7f',1,'franka::Finishable']]], + ['motion_5fid_525',['motion_id',['../classfranka_1_1ActiveControl.html#a0852a7d4b5a67df218440c2cc629f638',1,'franka::ActiveControl']]] +]; diff --git a/search/variables_b.html b/search/variables_b.html new file mode 100644 index 00000000..f376b27a --- /dev/null +++ b/search/variables_b.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_b.js b/search/variables_b.js new file mode 100644 index 00000000..a079cf83 --- /dev/null +++ b/search/variables_b.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['ne_5ft_5fee_526',['NE_T_EE',['../structfranka_1_1RobotState.html#ac53f1046fe758cfdda438a8e3ba08fff',1,'franka::RobotState']]] +]; diff --git a/search/variables_c.html b/search/variables_c.html new file mode 100644 index 00000000..6019eba9 --- /dev/null +++ b/search/variables_c.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_c.js b/search/variables_c.js new file mode 100644 index 00000000..ba90ff87 --- /dev/null +++ b/search/variables_c.js @@ -0,0 +1,12 @@ +var searchData= +[ + ['o_5fddp_5fee_5fc_527',['O_ddP_EE_c',['../structfranka_1_1RobotState.html#ac8dfcf78ddbb27852484e921d6d66ca1',1,'franka::RobotState']]], + ['o_5fddp_5fo_528',['O_ddP_O',['../structfranka_1_1RobotState.html#ab24d7982942d316459fc35337dc38ecd',1,'franka::RobotState']]], + ['o_5fdp_5fee_529',['O_dP_EE',['../classfranka_1_1CartesianVelocities.html#ab7a42c7c1ee7109025aff5c43a56b398',1,'franka::CartesianVelocities']]], + ['o_5fdp_5fee_5fc_530',['O_dP_EE_c',['../structfranka_1_1RobotState.html#a4be112bd1a9a7d777a67aea4a18a8dcc',1,'franka::RobotState']]], + ['o_5fdp_5fee_5fd_531',['O_dP_EE_d',['../structfranka_1_1RobotState.html#a1e0a82b98534929c3061295d5761d607',1,'franka::RobotState']]], + ['o_5ff_5fext_5fhat_5fk_532',['O_F_ext_hat_K',['../structfranka_1_1RobotState.html#a5a830b4f9d6a3c2dc92e4a9cc6050493',1,'franka::RobotState']]], + ['o_5ft_5fee_533',['O_T_EE',['../classfranka_1_1CartesianPose.html#a406e53e3d8fe594a11888f516eb4bf7d',1,'franka::CartesianPose::O_T_EE()'],['../structfranka_1_1RobotState.html#a193781d47722b32925e0ea7ac415f442',1,'franka::RobotState::O_T_EE()']]], + ['o_5ft_5fee_5fc_534',['O_T_EE_c',['../structfranka_1_1RobotState.html#a395c48eff099419ea5d42eaf0870fc18',1,'franka::RobotState']]], + ['o_5ft_5fee_5fd_535',['O_T_EE_d',['../structfranka_1_1RobotState.html#a3e5b4b7687856e92d826044be7d15733',1,'franka::RobotState']]] +]; diff --git a/search/variables_d.html b/search/variables_d.html new file mode 100644 index 00000000..f61ae751 --- /dev/null +++ b/search/variables_d.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_d.js b/search/variables_d.js new file mode 100644 index 00000000..58c4c373 --- /dev/null +++ b/search/variables_d.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['part_5fdetached_536',['part_detached',['../structfranka_1_1VacuumGripperState.html#aa27a2b4b9d19bdcb059995a8121ba309',1,'franka::VacuumGripperState']]], + ['part_5fpresent_537',['part_present',['../structfranka_1_1VacuumGripperState.html#aeb5664ab2a9784c9e31ce5f67c914107',1,'franka::VacuumGripperState']]], + ['power_5flimit_5fviolation_538',['power_limit_violation',['../structfranka_1_1Errors.html#a6c4d8cb1fb314567ebd07a6195b840f5',1,'franka::Errors']]] +]; diff --git a/search/variables_e.html b/search/variables_e.html new file mode 100644 index 00000000..7bfd3721 --- /dev/null +++ b/search/variables_e.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_e.js b/search/variables_e.js new file mode 100644 index 00000000..968c2434 --- /dev/null +++ b/search/variables_e.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['q_539',['q',['../classfranka_1_1JointPositions.html#a40e9098abe1c51cd48e17e41fbf78337',1,'franka::JointPositions::q()'],['../structfranka_1_1RobotState.html#ade3335d1ac2f6c44741a916d565f7091',1,'franka::RobotState::q()']]], + ['q_5fd_540',['q_d',['../structfranka_1_1RobotState.html#a706045af1b176049e9e56df755325bd2',1,'franka::RobotState']]] +]; diff --git a/search/variables_f.html b/search/variables_f.html new file mode 100644 index 00000000..d97920d0 --- /dev/null +++ b/search/variables_f.html @@ -0,0 +1,37 @@ + + + + + + + + + + +
    +
    Loading...
    +
    + +
    Searching...
    +
    No Matches
    + +
    + + diff --git a/search/variables_f.js b/search/variables_f.js new file mode 100644 index 00000000..d9c54022 --- /dev/null +++ b/search/variables_f.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['robot_5fimpl_541',['robot_impl',['../classfranka_1_1ActiveControl.html#a94e725adb409391547a260f204c74564',1,'franka::ActiveControl']]], + ['robot_5fmode_542',['robot_mode',['../structfranka_1_1RobotState.html#a4943ae75e0e2ec534e0afac31cbcc987',1,'franka::RobotState']]] +]; diff --git a/splitbar.png b/splitbar.png new file mode 100644 index 00000000..fe895f2c Binary files /dev/null and b/splitbar.png differ diff --git a/structfranka_1_1CommandException.html b/structfranka_1_1CommandException.html new file mode 100644 index 00000000..a5ca4424 --- /dev/null +++ b/structfranka_1_1CommandException.html @@ -0,0 +1,118 @@ + + + + + + + +libfranka: franka::CommandException Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::CommandException Struct Reference
    +
    +
    + +

    CommandException is thrown if an error occurs during command execution. + More...

    + +

    #include <exception.h>

    +
    +Inheritance diagram for franka::CommandException:
    +
    +
    Inheritance graph
    + + + + + +
    [legend]
    +
    +Collaboration diagram for franka::CommandException:
    +
    +
    Collaboration graph
    + + + + + +
    [legend]
    +

    Detailed Description

    +

    CommandException is thrown if an error occurs during command execution.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1CommandException__coll__graph.map b/structfranka_1_1CommandException__coll__graph.map new file mode 100644 index 00000000..73c58e3f --- /dev/null +++ b/structfranka_1_1CommandException__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1CommandException__coll__graph.md5 b/structfranka_1_1CommandException__coll__graph.md5 new file mode 100644 index 00000000..d76a1d46 --- /dev/null +++ b/structfranka_1_1CommandException__coll__graph.md5 @@ -0,0 +1 @@ +8f554c30479b664936d4c1cfc452d7af \ No newline at end of file diff --git a/structfranka_1_1CommandException__coll__graph.png b/structfranka_1_1CommandException__coll__graph.png new file mode 100644 index 00000000..1c2cc733 Binary files /dev/null and b/structfranka_1_1CommandException__coll__graph.png differ diff --git a/structfranka_1_1CommandException__inherit__graph.map b/structfranka_1_1CommandException__inherit__graph.map new file mode 100644 index 00000000..73c58e3f --- /dev/null +++ b/structfranka_1_1CommandException__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1CommandException__inherit__graph.md5 b/structfranka_1_1CommandException__inherit__graph.md5 new file mode 100644 index 00000000..d76a1d46 --- /dev/null +++ b/structfranka_1_1CommandException__inherit__graph.md5 @@ -0,0 +1 @@ +8f554c30479b664936d4c1cfc452d7af \ No newline at end of file diff --git a/structfranka_1_1CommandException__inherit__graph.png b/structfranka_1_1CommandException__inherit__graph.png new file mode 100644 index 00000000..1c2cc733 Binary files /dev/null and b/structfranka_1_1CommandException__inherit__graph.png differ diff --git a/structfranka_1_1ControlException-members.html b/structfranka_1_1ControlException-members.html new file mode 100644 index 00000000..d46cb341 --- /dev/null +++ b/structfranka_1_1ControlException-members.html @@ -0,0 +1,93 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::ControlException Member List
    +
    +
    + +

    This is the complete list of members for franka::ControlException, including all inherited members.

    + + + +
    ControlException(const std::string &what, std::vector< franka::Record > log={}) noexceptfranka::ControlExceptionexplicit
    logfranka::ControlException
    + + + + diff --git a/structfranka_1_1ControlException.html b/structfranka_1_1ControlException.html new file mode 100644 index 00000000..4c701343 --- /dev/null +++ b/structfranka_1_1ControlException.html @@ -0,0 +1,185 @@ + + + + + + + +libfranka: franka::ControlException Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    franka::ControlException Struct Reference
    +
    +
    + +

    ControlException is thrown if an error occurs during motion generation or torque control. + More...

    + +

    #include <exception.h>

    +
    +Inheritance diagram for franka::ControlException:
    +
    +
    Inheritance graph
    + + + + + +
    [legend]
    +
    +Collaboration diagram for franka::ControlException:
    +
    +
    Collaboration graph
    + + + + + +
    [legend]
    + + + + + +

    +Public Member Functions

     ControlException (const std::string &what, std::vector< franka::Record > log={}) noexcept
     Creates the exception with an explanatory string and a Log object. More...
     
    + + + + +

    +Public Attributes

    +const std::vector< franka::Recordlog
     Vector of states and commands logged just before the exception occurred.
     
    +

    Detailed Description

    +

    ControlException is thrown if an error occurs during motion generation or torque control.

    +

    The exception holds a vector with the last received robot states. The number of recorded states can be configured in the Robot constructor.

    +
    Examples
    generate_consecutive_motions.cpp, motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.
    +
    +

    Constructor & Destructor Documentation

    + +

    ◆ ControlException()

    + +
    +
    + + + + + +
    + + + + + + + + + + + + + + + + + + +
    franka::ControlException::ControlException (const std::string & what,
    std::vector< franka::Recordlog = {} 
    )
    +
    +explicitnoexcept
    +
    + +

    Creates the exception with an explanatory string and a Log object.

    +
    Parameters
    + + + +
    [in]whatExplanatory string.
    [in]logVector of last received states and commands.
    +
    +
    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1ControlException__coll__graph.map b/structfranka_1_1ControlException__coll__graph.map new file mode 100644 index 00000000..76e25ff0 --- /dev/null +++ b/structfranka_1_1ControlException__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1ControlException__coll__graph.md5 b/structfranka_1_1ControlException__coll__graph.md5 new file mode 100644 index 00000000..fe9c0ccd --- /dev/null +++ b/structfranka_1_1ControlException__coll__graph.md5 @@ -0,0 +1 @@ +4e553ffed42befde0592aa1e7f95bbac \ No newline at end of file diff --git a/structfranka_1_1ControlException__coll__graph.png b/structfranka_1_1ControlException__coll__graph.png new file mode 100644 index 00000000..59b599d0 Binary files /dev/null and b/structfranka_1_1ControlException__coll__graph.png differ diff --git a/structfranka_1_1ControlException__inherit__graph.map b/structfranka_1_1ControlException__inherit__graph.map new file mode 100644 index 00000000..76e25ff0 --- /dev/null +++ b/structfranka_1_1ControlException__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1ControlException__inherit__graph.md5 b/structfranka_1_1ControlException__inherit__graph.md5 new file mode 100644 index 00000000..fe9c0ccd --- /dev/null +++ b/structfranka_1_1ControlException__inherit__graph.md5 @@ -0,0 +1 @@ +4e553ffed42befde0592aa1e7f95bbac \ No newline at end of file diff --git a/structfranka_1_1ControlException__inherit__graph.png b/structfranka_1_1ControlException__inherit__graph.png new file mode 100644 index 00000000..59b599d0 Binary files /dev/null and b/structfranka_1_1ControlException__inherit__graph.png differ diff --git a/structfranka_1_1Errors-members.html b/structfranka_1_1Errors-members.html new file mode 100644 index 00000000..87cce84c --- /dev/null +++ b/structfranka_1_1Errors-members.html @@ -0,0 +1,138 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::Errors Member List
    +
    +
    + +

    This is the complete list of members for franka::Errors, including all inherited members.

    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    base_acceleration_initialization_timeoutfranka::Errors
    base_acceleration_invalid_readingfranka::Errors
    cartesian_motion_generator_acceleration_discontinuityfranka::Errors
    cartesian_motion_generator_elbow_limit_violationfranka::Errors
    cartesian_motion_generator_elbow_sign_inconsistentfranka::Errors
    cartesian_motion_generator_joint_acceleration_discontinuityfranka::Errors
    cartesian_motion_generator_joint_position_limits_violationfranka::Errors
    cartesian_motion_generator_joint_velocity_discontinuityfranka::Errors
    cartesian_motion_generator_joint_velocity_limits_violationfranka::Errors
    cartesian_motion_generator_start_elbow_invalidfranka::Errors
    cartesian_motion_generator_velocity_discontinuityfranka::Errors
    cartesian_motion_generator_velocity_limits_violationfranka::Errors
    cartesian_position_limits_violationfranka::Errors
    cartesian_position_motion_generator_invalid_framefranka::Errors
    cartesian_position_motion_generator_start_pose_invalidfranka::Errors
    cartesian_reflexfranka::Errors
    cartesian_spline_motion_generator_violationfranka::Errors
    cartesian_velocity_profile_safety_violationfranka::Errors
    cartesian_velocity_violationfranka::Errors
    communication_constraints_violationfranka::Errors
    controller_torque_discontinuityfranka::Errors
    Errors()franka::Errors
    Errors(const Errors &other)franka::Errors
    Errors(const std::array< bool, 41 > &errors)franka::Errors
    force_control_safety_violationfranka::Errors
    force_controller_desired_force_tolerance_violationfranka::Errors
    instability_detectedfranka::Errors
    joint_motion_generator_acceleration_discontinuityfranka::Errors
    joint_motion_generator_position_limits_violationfranka::Errors
    joint_motion_generator_velocity_discontinuityfranka::Errors
    joint_motion_generator_velocity_limits_violationfranka::Errors
    joint_move_in_wrong_directionfranka::Errors
    joint_p2p_insufficient_torque_for_planningfranka::Errors
    joint_position_limits_violationfranka::Errors
    joint_position_motion_generator_start_pose_invalidfranka::Errors
    joint_reflexfranka::Errors
    joint_velocity_violationfranka::Errors
    joint_via_motion_generator_planning_joint_limit_violationfranka::Errors
    max_goal_pose_deviation_violationfranka::Errors
    max_path_pose_deviation_violationfranka::Errors
    operator bool() const noexceptfranka::Errorsexplicit
    operator std::string() constfranka::Errorsexplicit
    operator=(Errors other)franka::Errors
    power_limit_violationfranka::Errors
    self_collision_avoidance_violationfranka::Errors
    start_elbow_sign_inconsistentfranka::Errors
    tau_j_range_violationfranka::Errors
    + + + + diff --git a/structfranka_1_1Errors.html b/structfranka_1_1Errors.html new file mode 100644 index 00000000..68069ce6 --- /dev/null +++ b/structfranka_1_1Errors.html @@ -0,0 +1,462 @@ + + + + + + + +libfranka: franka::Errors Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    franka::Errors Struct Reference
    +
    +
    + +

    Enumerates errors that can occur while controlling a franka::Robot. + More...

    + +

    #include <errors.h>

    + + + + + + + + + + + + + + + + + + + + +

    +Public Member Functions

    Errors ()
     Creates an empty Errors instance.
     
     Errors (const Errors &other)
     Copy constructs a new Errors instance. More...
     
    Errorsoperator= (Errors other)
     Assigns this Errors instance from another Errors value. More...
     
     Errors (const std::array< bool, 41 > &errors)
     Creates a new Errors instance from the given array. More...
     
     operator bool () const noexcept
     Check if any error flag is set to true. More...
     
     operator std::string () const
     Creates a string with names of active errors: "[active_error_name2, active_error_name_2, ... active_error_name_n]" If no errors are active, the string contains empty brackets: "[]". More...
     
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

    +Public Attributes

    +const bool & joint_position_limits_violation
     True if the robot moved past the joint limits.
     
    +const bool & cartesian_position_limits_violation
     True if the robot moved past any of the virtual walls.
     
    +const bool & self_collision_avoidance_violation
     True if the robot would have collided with itself.
     
    +const bool & joint_velocity_violation
     True if the robot exceeded joint velocity limits.
     
    +const bool & cartesian_velocity_violation
     True if the robot exceeded Cartesian velocity limits.
     
    +const bool & force_control_safety_violation
     True if the robot exceeded safety threshold during force control.
     
    +const bool & joint_reflex
     True if a collision was detected, i.e. the robot exceeded a torque threshold in a joint motion.
     
    +const bool & cartesian_reflex
     True if a collision was detected, i.e. the robot exceeded a torque threshold in a Cartesian motion.
     
    +const bool & max_goal_pose_deviation_violation
     True if internal motion generator did not reach the goal pose.
     
    +const bool & max_path_pose_deviation_violation
     True if internal motion generator deviated from the path.
     
    +const bool & cartesian_velocity_profile_safety_violation
     True if Cartesian velocity profile for internal motions was exceeded.
     
    +const bool & joint_position_motion_generator_start_pose_invalid
     True if an external joint position motion generator was started with a pose too far from the current pose.
     
    +const bool & joint_motion_generator_position_limits_violation
     True if an external joint motion generator would move into a joint limit.
     
    +const bool & joint_motion_generator_velocity_limits_violation
     True if an external joint motion generator exceeded velocity limits.
     
    +const bool & joint_motion_generator_velocity_discontinuity
     True if commanded velocity in joint motion generators is discontinuous (target values are too far apart).
     
    +const bool & joint_motion_generator_acceleration_discontinuity
     True if commanded acceleration in joint motion generators is discontinuous (target values are too far apart).
     
    +const bool & cartesian_position_motion_generator_start_pose_invalid
     True if an external Cartesian position motion generator was started with a pose too far from the current pose.
     
    +const bool & cartesian_motion_generator_elbow_limit_violation
     True if an external Cartesian motion generator would move into an elbow limit.
     
    +const bool & cartesian_motion_generator_velocity_limits_violation
     True if an external Cartesian motion generator would move with too high velocity.
     
    +const bool & cartesian_motion_generator_velocity_discontinuity
     True if commanded velocity in Cartesian motion generators is discontinuous (target values are too far apart).
     
    +const bool & cartesian_motion_generator_acceleration_discontinuity
     True if commanded acceleration in Cartesian motion generators is discontinuous (target values are too far apart).
     
    +const bool & cartesian_motion_generator_elbow_sign_inconsistent
     True if commanded elbow values in Cartesian motion generators are inconsistent.
     
    +const bool & cartesian_motion_generator_start_elbow_invalid
     True if the first elbow value in Cartesian motion generators is too far from initial one.
     
    +const bool & cartesian_motion_generator_joint_position_limits_violation
     True if the joint position limits would be exceeded after IK calculation.
     
    +const bool & cartesian_motion_generator_joint_velocity_limits_violation
     True if the joint velocity limits would be exceeded after IK calculation.
     
    +const bool & cartesian_motion_generator_joint_velocity_discontinuity
     True if the joint velocity in Cartesian motion generators is discontinuous after IK calculation.
     
    +const bool & cartesian_motion_generator_joint_acceleration_discontinuity
     True if the joint acceleration in Cartesian motion generators is discontinuous after IK calculation.
     
    +const bool & cartesian_position_motion_generator_invalid_frame
     True if the Cartesian pose is not a valid transformation matrix.
     
    +const bool & force_controller_desired_force_tolerance_violation
     True if desired force exceeds the safety thresholds.
     
    +const bool & controller_torque_discontinuity
     True if the torque set by the external controller is discontinuous.
     
    const bool & start_elbow_sign_inconsistent
     True if the start elbow sign was inconsistent. More...
     
    +const bool & communication_constraints_violation
     True if minimum network communication quality could not be held during a motion.
     
    +const bool & power_limit_violation
     True if commanded values would result in exceeding the power limit.
     
    const bool & joint_p2p_insufficient_torque_for_planning
     True if the robot is overloaded for the required motion. More...
     
    +const bool & tau_j_range_violation
     True if the measured torque signal is out of the safe range.
     
    +const bool & instability_detected
     True if an instability is detected.
     
    +const bool & joint_move_in_wrong_direction
     True if the robot is in joint position limits violation error and the user guides the robot further towards the limit.
     
    +const bool & cartesian_spline_motion_generator_violation
     True if the generated motion violates a joint limit.
     
    +const bool & joint_via_motion_generator_planning_joint_limit_violation
     True if the generated motion violates a joint limit.
     
    +const bool & base_acceleration_initialization_timeout
     True if the gravity vector could not be initialized by measureing the base acceleration.
     
    +const bool & base_acceleration_invalid_reading
     True if the base acceleration O_ddP_O cannot be determined.
     
    +

    Detailed Description

    +

    Enumerates errors that can occur while controlling a franka::Robot.

    +

    Constructor & Destructor Documentation

    + +

    ◆ Errors() [1/2]

    + +
    +
    + + + + + + + + +
    franka::Errors::Errors (const Errorsother)
    +
    + +

    Copy constructs a new Errors instance.

    +
    Parameters
    + + +
    [in]otherOther Errors instance.
    +
    +
    + +
    +
    + +

    ◆ Errors() [2/2]

    + +
    +
    + + + + + + + + +
    franka::Errors::Errors (const std::array< bool, 41 > & errors)
    +
    + +

    Creates a new Errors instance from the given array.

    +
    Parameters
    + + +
    errorsArray of error flags.
    +
    +
    + +
    +
    +

    Member Function Documentation

    + +

    ◆ operator bool()

    + +
    +
    + + + + + +
    + + + + + + + +
    franka::Errors::operator bool () const
    +
    +explicitnoexcept
    +
    + +

    Check if any error flag is set to true.

    +
    Returns
    True if any errors are set.
    + +
    +
    + +

    ◆ operator std::string()

    + +
    +
    + + + + + +
    + + + + + + + +
    franka::Errors::operator std::string () const
    +
    +explicit
    +
    + +

    Creates a string with names of active errors: "[active_error_name2, active_error_name_2, ... active_error_name_n]" If no errors are active, the string contains empty brackets: "[]".

    +
    Returns
    string with names of active errors
    + +
    +
    + +

    ◆ operator=()

    + +
    +
    + + + + + + + + +
    Errors& franka::Errors::operator= (Errors other)
    +
    + +

    Assigns this Errors instance from another Errors value.

    +
    Parameters
    + + +
    [in]otherOther Errors instance.
    +
    +
    +
    Returns
    Errors instance.
    + +
    +
    +

    Member Data Documentation

    + +

    ◆ joint_p2p_insufficient_torque_for_planning

    + +
    +
    + + + + +
    const bool& franka::Errors::joint_p2p_insufficient_torque_for_planning
    +
    + +

    True if the robot is overloaded for the required motion.

    +

    Applies only to motions started from Desk.

    + +
    +
    + +

    ◆ start_elbow_sign_inconsistent

    + +
    +
    + + + + +
    const bool& franka::Errors::start_elbow_sign_inconsistent
    +
    + +

    True if the start elbow sign was inconsistent.

    +

    Applies only to motions started from Desk.

    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1Exception.html b/structfranka_1_1Exception.html new file mode 100644 index 00000000..a30f8b0e --- /dev/null +++ b/structfranka_1_1Exception.html @@ -0,0 +1,126 @@ + + + + + + + +libfranka: franka::Exception Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::Exception Struct Reference
    +
    + + + + + diff --git a/structfranka_1_1Exception__coll__graph.map b/structfranka_1_1Exception__coll__graph.map new file mode 100644 index 00000000..a3586d81 --- /dev/null +++ b/structfranka_1_1Exception__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/structfranka_1_1Exception__coll__graph.md5 b/structfranka_1_1Exception__coll__graph.md5 new file mode 100644 index 00000000..9c424121 --- /dev/null +++ b/structfranka_1_1Exception__coll__graph.md5 @@ -0,0 +1 @@ +35ab8e8c51542517bb4903c73914631e \ No newline at end of file diff --git a/structfranka_1_1Exception__coll__graph.png b/structfranka_1_1Exception__coll__graph.png new file mode 100644 index 00000000..a3eaf33b Binary files /dev/null and b/structfranka_1_1Exception__coll__graph.png differ diff --git a/structfranka_1_1Exception__inherit__graph.map b/structfranka_1_1Exception__inherit__graph.map new file mode 100644 index 00000000..c6b44fd0 --- /dev/null +++ b/structfranka_1_1Exception__inherit__graph.map @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/structfranka_1_1Exception__inherit__graph.md5 b/structfranka_1_1Exception__inherit__graph.md5 new file mode 100644 index 00000000..697f6d12 --- /dev/null +++ b/structfranka_1_1Exception__inherit__graph.md5 @@ -0,0 +1 @@ +6faf038d3e55c6494cd13b5fbac07b70 \ No newline at end of file diff --git a/structfranka_1_1Exception__inherit__graph.png b/structfranka_1_1Exception__inherit__graph.png new file mode 100644 index 00000000..7707c6e3 Binary files /dev/null and b/structfranka_1_1Exception__inherit__graph.png differ diff --git a/structfranka_1_1Finishable-members.html b/structfranka_1_1Finishable-members.html new file mode 100644 index 00000000..6aada15c --- /dev/null +++ b/structfranka_1_1Finishable-members.html @@ -0,0 +1,92 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::Finishable Member List
    +
    +
    + +

    This is the complete list of members for franka::Finishable, including all inherited members.

    + + +
    motion_finishedfranka::Finishable
    + + + + diff --git a/structfranka_1_1Finishable.html b/structfranka_1_1Finishable.html new file mode 100644 index 00000000..1b224775 --- /dev/null +++ b/structfranka_1_1Finishable.html @@ -0,0 +1,124 @@ + + + + + + + +libfranka: franka::Finishable Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    franka::Finishable Struct Reference
    +
    +
    + +

    Helper type for control and motion generation loops. + More...

    + +

    #include <control_types.h>

    +
    +Inheritance diagram for franka::Finishable:
    +
    +
    Inheritance graph
    + + + + + + + + +
    [legend]
    + + + + + +

    +Public Attributes

    +bool motion_finished = false
     Determines whether to finish a currently running motion.
     
    +

    Detailed Description

    +

    Helper type for control and motion generation loops.

    +

    Used to determine whether to terminate a loop after the control callback has returned.

    +
    See also
    Documentation on callbacks
    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1Finishable__inherit__graph.map b/structfranka_1_1Finishable__inherit__graph.map new file mode 100644 index 00000000..b06c5d07 --- /dev/null +++ b/structfranka_1_1Finishable__inherit__graph.map @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/structfranka_1_1Finishable__inherit__graph.md5 b/structfranka_1_1Finishable__inherit__graph.md5 new file mode 100644 index 00000000..7b080573 --- /dev/null +++ b/structfranka_1_1Finishable__inherit__graph.md5 @@ -0,0 +1 @@ +761d61ee040c65aed80333cad3d1f1dc \ No newline at end of file diff --git a/structfranka_1_1Finishable__inherit__graph.png b/structfranka_1_1Finishable__inherit__graph.png new file mode 100644 index 00000000..60e1e0dc Binary files /dev/null and b/structfranka_1_1Finishable__inherit__graph.png differ diff --git a/structfranka_1_1GripperState-members.html b/structfranka_1_1GripperState-members.html new file mode 100644 index 00000000..89e3b81b --- /dev/null +++ b/structfranka_1_1GripperState-members.html @@ -0,0 +1,96 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::GripperState Member List
    +
    + + + + + diff --git a/structfranka_1_1GripperState.html b/structfranka_1_1GripperState.html new file mode 100644 index 00000000..c522b426 --- /dev/null +++ b/structfranka_1_1GripperState.html @@ -0,0 +1,188 @@ + + + + + + + +libfranka: franka::GripperState Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    franka::GripperState Struct Reference
    +
    +
    + +

    Describes the gripper state. + More...

    + +

    #include <gripper_state.h>

    +
    +Collaboration diagram for franka::GripperState:
    +
    +
    Collaboration graph
    + + + + +
    [legend]
    + + + + + + + + + + + + + + + + + +

    +Public Attributes

    double width {}
     Current gripper opening width. More...
     
    double max_width {}
     Maximum gripper opening width. More...
     
    +bool is_grasped {}
     Indicates whether an object is currently grasped.
     
    uint16_t temperature {}
     Current gripper temperature. More...
     
    +Duration time {}
     Strictly monotonically increasing timestamp since robot start.
     
    +

    Detailed Description

    +

    Describes the gripper state.

    +
    Examples
    grasp_object.cpp.
    +
    +

    Member Data Documentation

    + +

    ◆ max_width

    + +
    +
    + + + + +
    double franka::GripperState::max_width {}
    +
    + +

    Maximum gripper opening width.

    +

    This parameter is estimated by homing the gripper. After changing the gripper fingers, a homing needs to be done. Unit: \([m]\).

    +
    See also
    Gripper::homing.
    +
    Examples
    grasp_object.cpp.
    +
    + +
    +
    + +

    ◆ temperature

    + +
    +
    + + + + +
    uint16_t franka::GripperState::temperature {}
    +
    + +

    Current gripper temperature.

    +

    Unit: \([°C]\).

    + +
    +
    + +

    ◆ width

    + +
    +
    + + + + +
    double franka::GripperState::width {}
    +
    + +

    Current gripper opening width.

    +

    Unit: \([m]\).

    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1GripperState__coll__graph.map b/structfranka_1_1GripperState__coll__graph.map new file mode 100644 index 00000000..9cd39f67 --- /dev/null +++ b/structfranka_1_1GripperState__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/structfranka_1_1GripperState__coll__graph.md5 b/structfranka_1_1GripperState__coll__graph.md5 new file mode 100644 index 00000000..efc0d3cf --- /dev/null +++ b/structfranka_1_1GripperState__coll__graph.md5 @@ -0,0 +1 @@ +44936ba81b40a2d95800ad5ee62e8de6 \ No newline at end of file diff --git a/structfranka_1_1GripperState__coll__graph.png b/structfranka_1_1GripperState__coll__graph.png new file mode 100644 index 00000000..afc6689e Binary files /dev/null and b/structfranka_1_1GripperState__coll__graph.png differ diff --git a/structfranka_1_1IncompatibleVersionException-members.html b/structfranka_1_1IncompatibleVersionException-members.html new file mode 100644 index 00000000..23a416b3 --- /dev/null +++ b/structfranka_1_1IncompatibleVersionException-members.html @@ -0,0 +1,94 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::IncompatibleVersionException Member List
    +
    +
    + +

    This is the complete list of members for franka::IncompatibleVersionException, including all inherited members.

    + + + + +
    IncompatibleVersionException(uint16_t server_version, uint16_t library_version) noexceptfranka::IncompatibleVersionException
    library_versionfranka::IncompatibleVersionException
    server_versionfranka::IncompatibleVersionException
    + + + + diff --git a/structfranka_1_1IncompatibleVersionException.html b/structfranka_1_1IncompatibleVersionException.html new file mode 100644 index 00000000..9e9a0def --- /dev/null +++ b/structfranka_1_1IncompatibleVersionException.html @@ -0,0 +1,186 @@ + + + + + + + +libfranka: franka::IncompatibleVersionException Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    franka::IncompatibleVersionException Struct Reference
    +
    +
    + +

    IncompatibleVersionException is thrown if the robot does not support this version of libfranka. + More...

    + +

    #include <exception.h>

    +
    +Inheritance diagram for franka::IncompatibleVersionException:
    +
    +
    Inheritance graph
    + + + + + +
    [legend]
    +
    +Collaboration diagram for franka::IncompatibleVersionException:
    +
    +
    Collaboration graph
    + + + + + +
    [legend]
    + + + + + +

    +Public Member Functions

     IncompatibleVersionException (uint16_t server_version, uint16_t library_version) noexcept
     Creates the exception using the two different protocol versions. More...
     
    + + + + + + + +

    +Public Attributes

    +const uint16_t server_version
     Control's protocol version.
     
    +const uint16_t library_version
     libfranka protocol version.
     
    +

    Detailed Description

    +

    IncompatibleVersionException is thrown if the robot does not support this version of libfranka.

    +

    Constructor & Destructor Documentation

    + +

    ◆ IncompatibleVersionException()

    + +
    +
    + + + + + +
    + + + + + + + + + + + + + + + + + + +
    franka::IncompatibleVersionException::IncompatibleVersionException (uint16_t server_version,
    uint16_t library_version 
    )
    +
    +noexcept
    +
    + +

    Creates the exception using the two different protocol versions.

    +
    Parameters
    + + + +
    [in]server_versionProtocol version on the Control side.
    [in]library_versionProtocol version of libfranka.
    +
    +
    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1IncompatibleVersionException__coll__graph.map b/structfranka_1_1IncompatibleVersionException__coll__graph.map new file mode 100644 index 00000000..2461bd9d --- /dev/null +++ b/structfranka_1_1IncompatibleVersionException__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1IncompatibleVersionException__coll__graph.md5 b/structfranka_1_1IncompatibleVersionException__coll__graph.md5 new file mode 100644 index 00000000..e2854f08 --- /dev/null +++ b/structfranka_1_1IncompatibleVersionException__coll__graph.md5 @@ -0,0 +1 @@ +d8405e8f399f826091a2d7b535b2ec56 \ No newline at end of file diff --git a/structfranka_1_1IncompatibleVersionException__coll__graph.png b/structfranka_1_1IncompatibleVersionException__coll__graph.png new file mode 100644 index 00000000..2932e20b Binary files /dev/null and b/structfranka_1_1IncompatibleVersionException__coll__graph.png differ diff --git a/structfranka_1_1IncompatibleVersionException__inherit__graph.map b/structfranka_1_1IncompatibleVersionException__inherit__graph.map new file mode 100644 index 00000000..2461bd9d --- /dev/null +++ b/structfranka_1_1IncompatibleVersionException__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1IncompatibleVersionException__inherit__graph.md5 b/structfranka_1_1IncompatibleVersionException__inherit__graph.md5 new file mode 100644 index 00000000..e2854f08 --- /dev/null +++ b/structfranka_1_1IncompatibleVersionException__inherit__graph.md5 @@ -0,0 +1 @@ +d8405e8f399f826091a2d7b535b2ec56 \ No newline at end of file diff --git a/structfranka_1_1IncompatibleVersionException__inherit__graph.png b/structfranka_1_1IncompatibleVersionException__inherit__graph.png new file mode 100644 index 00000000..2932e20b Binary files /dev/null and b/structfranka_1_1IncompatibleVersionException__inherit__graph.png differ diff --git a/structfranka_1_1InvalidOperationException.html b/structfranka_1_1InvalidOperationException.html new file mode 100644 index 00000000..a2af1105 --- /dev/null +++ b/structfranka_1_1InvalidOperationException.html @@ -0,0 +1,118 @@ + + + + + + + +libfranka: franka::InvalidOperationException Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::InvalidOperationException Struct Reference
    +
    +
    + +

    InvalidOperationException is thrown if an operation cannot be performed. + More...

    + +

    #include <exception.h>

    +
    +Inheritance diagram for franka::InvalidOperationException:
    +
    +
    Inheritance graph
    + + + + + +
    [legend]
    +
    +Collaboration diagram for franka::InvalidOperationException:
    +
    +
    Collaboration graph
    + + + + + +
    [legend]
    +

    Detailed Description

    +

    InvalidOperationException is thrown if an operation cannot be performed.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1InvalidOperationException__coll__graph.map b/structfranka_1_1InvalidOperationException__coll__graph.map new file mode 100644 index 00000000..e95ed993 --- /dev/null +++ b/structfranka_1_1InvalidOperationException__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1InvalidOperationException__coll__graph.md5 b/structfranka_1_1InvalidOperationException__coll__graph.md5 new file mode 100644 index 00000000..498ce916 --- /dev/null +++ b/structfranka_1_1InvalidOperationException__coll__graph.md5 @@ -0,0 +1 @@ +378a4924d439a7e9d695dd50ea34922d \ No newline at end of file diff --git a/structfranka_1_1InvalidOperationException__coll__graph.png b/structfranka_1_1InvalidOperationException__coll__graph.png new file mode 100644 index 00000000..8cac2e28 Binary files /dev/null and b/structfranka_1_1InvalidOperationException__coll__graph.png differ diff --git a/structfranka_1_1InvalidOperationException__inherit__graph.map b/structfranka_1_1InvalidOperationException__inherit__graph.map new file mode 100644 index 00000000..e95ed993 --- /dev/null +++ b/structfranka_1_1InvalidOperationException__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1InvalidOperationException__inherit__graph.md5 b/structfranka_1_1InvalidOperationException__inherit__graph.md5 new file mode 100644 index 00000000..498ce916 --- /dev/null +++ b/structfranka_1_1InvalidOperationException__inherit__graph.md5 @@ -0,0 +1 @@ +378a4924d439a7e9d695dd50ea34922d \ No newline at end of file diff --git a/structfranka_1_1InvalidOperationException__inherit__graph.png b/structfranka_1_1InvalidOperationException__inherit__graph.png new file mode 100644 index 00000000..8cac2e28 Binary files /dev/null and b/structfranka_1_1InvalidOperationException__inherit__graph.png differ diff --git a/structfranka_1_1ModelException.html b/structfranka_1_1ModelException.html new file mode 100644 index 00000000..ae9249f6 --- /dev/null +++ b/structfranka_1_1ModelException.html @@ -0,0 +1,118 @@ + + + + + + + +libfranka: franka::ModelException Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::ModelException Struct Reference
    +
    +
    + +

    ModelException is thrown if an error occurs when loading the model library. + More...

    + +

    #include <exception.h>

    +
    +Inheritance diagram for franka::ModelException:
    +
    +
    Inheritance graph
    + + + + + +
    [legend]
    +
    +Collaboration diagram for franka::ModelException:
    +
    +
    Collaboration graph
    + + + + + +
    [legend]
    +

    Detailed Description

    +

    ModelException is thrown if an error occurs when loading the model library.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1ModelException__coll__graph.map b/structfranka_1_1ModelException__coll__graph.map new file mode 100644 index 00000000..eefb28fa --- /dev/null +++ b/structfranka_1_1ModelException__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1ModelException__coll__graph.md5 b/structfranka_1_1ModelException__coll__graph.md5 new file mode 100644 index 00000000..6d7532b4 --- /dev/null +++ b/structfranka_1_1ModelException__coll__graph.md5 @@ -0,0 +1 @@ +aef07e73e3e9ceee16637698387a0402 \ No newline at end of file diff --git a/structfranka_1_1ModelException__coll__graph.png b/structfranka_1_1ModelException__coll__graph.png new file mode 100644 index 00000000..0ffed1a5 Binary files /dev/null and b/structfranka_1_1ModelException__coll__graph.png differ diff --git a/structfranka_1_1ModelException__inherit__graph.map b/structfranka_1_1ModelException__inherit__graph.map new file mode 100644 index 00000000..eefb28fa --- /dev/null +++ b/structfranka_1_1ModelException__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1ModelException__inherit__graph.md5 b/structfranka_1_1ModelException__inherit__graph.md5 new file mode 100644 index 00000000..6d7532b4 --- /dev/null +++ b/structfranka_1_1ModelException__inherit__graph.md5 @@ -0,0 +1 @@ +aef07e73e3e9ceee16637698387a0402 \ No newline at end of file diff --git a/structfranka_1_1ModelException__inherit__graph.png b/structfranka_1_1ModelException__inherit__graph.png new file mode 100644 index 00000000..0ffed1a5 Binary files /dev/null and b/structfranka_1_1ModelException__inherit__graph.png differ diff --git a/structfranka_1_1NetworkException.html b/structfranka_1_1NetworkException.html new file mode 100644 index 00000000..648ad58a --- /dev/null +++ b/structfranka_1_1NetworkException.html @@ -0,0 +1,118 @@ + + + + + + + +libfranka: franka::NetworkException Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::NetworkException Struct Reference
    +
    +
    + +

    NetworkException is thrown if a connection to the robot cannot be established, or when a timeout occurs. + More...

    + +

    #include <exception.h>

    +
    +Inheritance diagram for franka::NetworkException:
    +
    +
    Inheritance graph
    + + + + + +
    [legend]
    +
    +Collaboration diagram for franka::NetworkException:
    +
    +
    Collaboration graph
    + + + + + +
    [legend]
    +

    Detailed Description

    +

    NetworkException is thrown if a connection to the robot cannot be established, or when a timeout occurs.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1NetworkException__coll__graph.map b/structfranka_1_1NetworkException__coll__graph.map new file mode 100644 index 00000000..1d2a3fb1 --- /dev/null +++ b/structfranka_1_1NetworkException__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1NetworkException__coll__graph.md5 b/structfranka_1_1NetworkException__coll__graph.md5 new file mode 100644 index 00000000..075dd123 --- /dev/null +++ b/structfranka_1_1NetworkException__coll__graph.md5 @@ -0,0 +1 @@ +d8561e044d91fa5f3077a8f6d620401b \ No newline at end of file diff --git a/structfranka_1_1NetworkException__coll__graph.png b/structfranka_1_1NetworkException__coll__graph.png new file mode 100644 index 00000000..a96102f4 Binary files /dev/null and b/structfranka_1_1NetworkException__coll__graph.png differ diff --git a/structfranka_1_1NetworkException__inherit__graph.map b/structfranka_1_1NetworkException__inherit__graph.map new file mode 100644 index 00000000..1d2a3fb1 --- /dev/null +++ b/structfranka_1_1NetworkException__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1NetworkException__inherit__graph.md5 b/structfranka_1_1NetworkException__inherit__graph.md5 new file mode 100644 index 00000000..075dd123 --- /dev/null +++ b/structfranka_1_1NetworkException__inherit__graph.md5 @@ -0,0 +1 @@ +d8561e044d91fa5f3077a8f6d620401b \ No newline at end of file diff --git a/structfranka_1_1NetworkException__inherit__graph.png b/structfranka_1_1NetworkException__inherit__graph.png new file mode 100644 index 00000000..a96102f4 Binary files /dev/null and b/structfranka_1_1NetworkException__inherit__graph.png differ diff --git a/structfranka_1_1ProtocolException.html b/structfranka_1_1ProtocolException.html new file mode 100644 index 00000000..ca96b332 --- /dev/null +++ b/structfranka_1_1ProtocolException.html @@ -0,0 +1,118 @@ + + + + + + + +libfranka: franka::ProtocolException Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::ProtocolException Struct Reference
    +
    +
    + +

    ProtocolException is thrown if the robot returns an incorrect message. + More...

    + +

    #include <exception.h>

    +
    +Inheritance diagram for franka::ProtocolException:
    +
    +
    Inheritance graph
    + + + + + +
    [legend]
    +
    +Collaboration diagram for franka::ProtocolException:
    +
    +
    Collaboration graph
    + + + + + +
    [legend]
    +

    Detailed Description

    +

    ProtocolException is thrown if the robot returns an incorrect message.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1ProtocolException__coll__graph.map b/structfranka_1_1ProtocolException__coll__graph.map new file mode 100644 index 00000000..a05191a0 --- /dev/null +++ b/structfranka_1_1ProtocolException__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1ProtocolException__coll__graph.md5 b/structfranka_1_1ProtocolException__coll__graph.md5 new file mode 100644 index 00000000..f7972396 --- /dev/null +++ b/structfranka_1_1ProtocolException__coll__graph.md5 @@ -0,0 +1 @@ +f4dff3c8ff5693e8c7a038439d383191 \ No newline at end of file diff --git a/structfranka_1_1ProtocolException__coll__graph.png b/structfranka_1_1ProtocolException__coll__graph.png new file mode 100644 index 00000000..8a9200c8 Binary files /dev/null and b/structfranka_1_1ProtocolException__coll__graph.png differ diff --git a/structfranka_1_1ProtocolException__inherit__graph.map b/structfranka_1_1ProtocolException__inherit__graph.map new file mode 100644 index 00000000..a05191a0 --- /dev/null +++ b/structfranka_1_1ProtocolException__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1ProtocolException__inherit__graph.md5 b/structfranka_1_1ProtocolException__inherit__graph.md5 new file mode 100644 index 00000000..f7972396 --- /dev/null +++ b/structfranka_1_1ProtocolException__inherit__graph.md5 @@ -0,0 +1 @@ +f4dff3c8ff5693e8c7a038439d383191 \ No newline at end of file diff --git a/structfranka_1_1ProtocolException__inherit__graph.png b/structfranka_1_1ProtocolException__inherit__graph.png new file mode 100644 index 00000000..8a9200c8 Binary files /dev/null and b/structfranka_1_1ProtocolException__inherit__graph.png differ diff --git a/structfranka_1_1RealtimeException.html b/structfranka_1_1RealtimeException.html new file mode 100644 index 00000000..7a9498e9 --- /dev/null +++ b/structfranka_1_1RealtimeException.html @@ -0,0 +1,118 @@ + + + + + + + +libfranka: franka::RealtimeException Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::RealtimeException Struct Reference
    +
    +
    + +

    RealtimeException is thrown if realtime priority cannot be set. + More...

    + +

    #include <exception.h>

    +
    +Inheritance diagram for franka::RealtimeException:
    +
    +
    Inheritance graph
    + + + + + +
    [legend]
    +
    +Collaboration diagram for franka::RealtimeException:
    +
    +
    Collaboration graph
    + + + + + +
    [legend]
    +

    Detailed Description

    +

    RealtimeException is thrown if realtime priority cannot be set.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1RealtimeException__coll__graph.map b/structfranka_1_1RealtimeException__coll__graph.map new file mode 100644 index 00000000..570fa5e2 --- /dev/null +++ b/structfranka_1_1RealtimeException__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1RealtimeException__coll__graph.md5 b/structfranka_1_1RealtimeException__coll__graph.md5 new file mode 100644 index 00000000..47b203b1 --- /dev/null +++ b/structfranka_1_1RealtimeException__coll__graph.md5 @@ -0,0 +1 @@ +c25253c62c5844c462e123c0cc70a84a \ No newline at end of file diff --git a/structfranka_1_1RealtimeException__coll__graph.png b/structfranka_1_1RealtimeException__coll__graph.png new file mode 100644 index 00000000..26a4e664 Binary files /dev/null and b/structfranka_1_1RealtimeException__coll__graph.png differ diff --git a/structfranka_1_1RealtimeException__inherit__graph.map b/structfranka_1_1RealtimeException__inherit__graph.map new file mode 100644 index 00000000..570fa5e2 --- /dev/null +++ b/structfranka_1_1RealtimeException__inherit__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1RealtimeException__inherit__graph.md5 b/structfranka_1_1RealtimeException__inherit__graph.md5 new file mode 100644 index 00000000..47b203b1 --- /dev/null +++ b/structfranka_1_1RealtimeException__inherit__graph.md5 @@ -0,0 +1 @@ +c25253c62c5844c462e123c0cc70a84a \ No newline at end of file diff --git a/structfranka_1_1RealtimeException__inherit__graph.png b/structfranka_1_1RealtimeException__inherit__graph.png new file mode 100644 index 00000000..26a4e664 Binary files /dev/null and b/structfranka_1_1RealtimeException__inherit__graph.png differ diff --git a/structfranka_1_1Record-members.html b/structfranka_1_1Record-members.html new file mode 100644 index 00000000..b39632ec --- /dev/null +++ b/structfranka_1_1Record-members.html @@ -0,0 +1,93 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::Record Member List
    +
    +
    + +

    This is the complete list of members for franka::Record, including all inherited members.

    + + + +
    commandfranka::Record
    statefranka::Record
    + + + + diff --git a/structfranka_1_1Record.html b/structfranka_1_1Record.html new file mode 100644 index 00000000..815682cf --- /dev/null +++ b/structfranka_1_1Record.html @@ -0,0 +1,132 @@ + + + + + + + +libfranka: franka::Record Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    franka::Record Struct Reference
    +
    +
    + +

    One row of the log contains a robot command of timestamp n and a corresponding robot state of timestamp n+1. + More...

    + +

    #include <log.h>

    +
    +Collaboration diagram for franka::Record:
    +
    +
    Collaboration graph
    + + + + + + + + + + + + + +
    [legend]
    + + + + + + + + +

    +Public Attributes

    +RobotState state
     Robot state of timestamp n+1.
     
    +RobotCommand command
     Robot command of timestamp n, after rate limiting (if activated).
     
    +

    Detailed Description

    +

    One row of the log contains a robot command of timestamp n and a corresponding robot state of timestamp n+1.

    +

    Provided by the ControlException.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1Record__coll__graph.map b/structfranka_1_1Record__coll__graph.map new file mode 100644 index 00000000..347dfd9a --- /dev/null +++ b/structfranka_1_1Record__coll__graph.map @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/structfranka_1_1Record__coll__graph.md5 b/structfranka_1_1Record__coll__graph.md5 new file mode 100644 index 00000000..1cc4d372 --- /dev/null +++ b/structfranka_1_1Record__coll__graph.md5 @@ -0,0 +1 @@ +8ba0cd54bd97ddfaaafb627adcb3ed04 \ No newline at end of file diff --git a/structfranka_1_1Record__coll__graph.png b/structfranka_1_1Record__coll__graph.png new file mode 100644 index 00000000..ed91de2a Binary files /dev/null and b/structfranka_1_1Record__coll__graph.png differ diff --git a/structfranka_1_1RobotCommand-members.html b/structfranka_1_1RobotCommand-members.html new file mode 100644 index 00000000..284e775c --- /dev/null +++ b/structfranka_1_1RobotCommand-members.html @@ -0,0 +1,96 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::RobotCommand Member List
    +
    + + + + + diff --git a/structfranka_1_1RobotCommand.html b/structfranka_1_1RobotCommand.html new file mode 100644 index 00000000..2be782da --- /dev/null +++ b/structfranka_1_1RobotCommand.html @@ -0,0 +1,140 @@ + + + + + + + +libfranka: franka::RobotCommand Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    franka::RobotCommand Struct Reference
    +
    +
    + +

    Command sent to the robot. + More...

    + +

    #include <log.h>

    +
    +Collaboration diagram for franka::RobotCommand:
    +
    +
    Collaboration graph
    + + + + + + + + + +
    [legend]
    + + + + + + + + + + + + + + + + + +

    +Public Attributes

    +JointPositions joint_positions {0, 0, 0, 0, 0, 0, 0}
     \(q_d\) sent to the robot.
     
    +JointVelocities joint_velocities {0, 0, 0, 0, 0, 0, 0}
     \(\dot{q}_d\) sent to the robot.
     
    +CartesianPose cartesian_pose {1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1}
     \(^O{\mathbf{T}_{EE}}_{d}\) sent to the robot.
     
    +CartesianVelocities cartesian_velocities {0, 0, 0, 0, 0, 0}
     \(^O\dot{P}_{EE}\) sent to the robot.
     
    +Torques torques {0, 0, 0, 0, 0, 0, 0}
     \({\tau_J}_d\) sent to the robot.
     
    +

    Detailed Description

    +

    Command sent to the robot.

    +

    Structure used only for logging purposes.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1RobotCommand__coll__graph.map b/structfranka_1_1RobotCommand__coll__graph.map new file mode 100644 index 00000000..619a4dd1 --- /dev/null +++ b/structfranka_1_1RobotCommand__coll__graph.map @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/structfranka_1_1RobotCommand__coll__graph.md5 b/structfranka_1_1RobotCommand__coll__graph.md5 new file mode 100644 index 00000000..dd237dcb --- /dev/null +++ b/structfranka_1_1RobotCommand__coll__graph.md5 @@ -0,0 +1 @@ +741793d1fa663b96ac22d465c4c7e858 \ No newline at end of file diff --git a/structfranka_1_1RobotCommand__coll__graph.png b/structfranka_1_1RobotCommand__coll__graph.png new file mode 100644 index 00000000..bd078d0f Binary files /dev/null and b/structfranka_1_1RobotCommand__coll__graph.png differ diff --git a/structfranka_1_1RobotState-members.html b/structfranka_1_1RobotState-members.html new file mode 100644 index 00000000..da33b7e4 --- /dev/null +++ b/structfranka_1_1RobotState-members.html @@ -0,0 +1,138 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::RobotState Member List
    +
    + + + + + diff --git a/structfranka_1_1RobotState.html b/structfranka_1_1RobotState.html new file mode 100644 index 00000000..d3ce5c39 --- /dev/null +++ b/structfranka_1_1RobotState.html @@ -0,0 +1,940 @@ + + + + + + + +libfranka: franka::RobotState Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    franka::RobotState Struct Reference
    +
    +
    + +

    Describes the robot state. + More...

    + +

    #include <robot_state.h>

    +
    +Collaboration diagram for franka::RobotState:
    +
    +
    Collaboration graph
    + + + + + +
    [legend]
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

    +Public Attributes

    std::array< double, 16 > O_T_EE {}
     \(^{O}T_{EE}\) Measured end effector pose in base frame. More...
     
    std::array< double, 16 > O_T_EE_d {}
     \({^OT_{EE}}_{d}\) Last desired end effector pose of motion generation in base frame. More...
     
    std::array< double, 16 > F_T_EE {}
     \(^{F}T_{EE}\) End effector frame pose in flange frame. More...
     
    std::array< double, 16 > F_T_NE {}
     \(^{F}T_{NE}\) Nominal end effector frame pose in flange frame. More...
     
    std::array< double, 16 > NE_T_EE {}
     \(^{NE}T_{EE}\) End effector frame pose in nominal end effector frame. More...
     
    std::array< double, 16 > EE_T_K {}
     \(^{EE}T_{K}\) Stiffness frame pose in end effector frame. More...
     
    +double m_ee {}
     \(m_{EE}\) Configured mass of the end effector.
     
    +std::array< double, 9 > I_ee {}
     \(I_{EE}\) Configured rotational inertia matrix of the end effector load with respect to center of mass.
     
    +std::array< double, 3 > F_x_Cee {}
     \(^{F}x_{C_{EE}}\) Configured center of mass of the end effector load with respect to flange frame.
     
    +double m_load {}
     \(m_{load}\) Configured mass of the external load.
     
    +std::array< double, 9 > I_load {}
     \(I_{load}\) Configured rotational inertia matrix of the external load with respect to center of mass.
     
    +std::array< double, 3 > F_x_Cload {}
     \(^{F}x_{C_{load}}\) Configured center of mass of the external load with respect to flange frame.
     
    +double m_total {}
     \(m_{total}\) Sum of the mass of the end effector and the external load.
     
    +std::array< double, 9 > I_total {}
     \(I_{total}\) Combined rotational inertia matrix of the end effector load and the external load with respect to the center of mass.
     
    +std::array< double, 3 > F_x_Ctotal {}
     \(^{F}x_{C_{total}}\) Combined center of mass of the end effector load and the external load with respect to flange frame.
     
    std::array< double, 2 > elbow {}
     Elbow configuration. More...
     
    std::array< double, 2 > elbow_d {}
     Desired elbow configuration. More...
     
    std::array< double, 2 > elbow_c {}
     Commanded elbow configuration. More...
     
    std::array< double, 2 > delbow_c {}
     Commanded elbow velocity. More...
     
    std::array< double, 2 > ddelbow_c {}
     Commanded elbow acceleration. More...
     
    std::array< double, 7 > tau_J {}
     \(\tau_{J}\) Measured link-side joint torque sensor signals. More...
     
    std::array< double, 7 > tau_J_d {}
     \({\tau_J}_d\) Desired link-side joint torque sensor signals without gravity. More...
     
    std::array< double, 7 > dtau_J {}
     \(\dot{\tau_{J}}\) Derivative of measured link-side joint torque sensor signals. More...
     
    std::array< double, 7 > q {}
     \(q\) Measured joint position. More...
     
    std::array< double, 7 > q_d {}
     \(q_d\) Desired joint position. More...
     
    std::array< double, 7 > dq {}
     \(\dot{q}\) Measured joint velocity. More...
     
    std::array< double, 7 > dq_d {}
     \(\dot{q}_d\) Desired joint velocity. More...
     
    std::array< double, 7 > ddq_d {}
     \(\ddot{q}_d\) Desired joint acceleration. More...
     
    std::array< double, 7 > joint_contact {}
     Indicates which contact level is activated in which joint. More...
     
    std::array< double, 6 > cartesian_contact {}
     Indicates which contact level is activated in which Cartesian dimension \((x,y,z,R,P,Y)\). More...
     
    std::array< double, 7 > joint_collision {}
     Indicates which contact level is activated in which joint. More...
     
    std::array< double, 6 > cartesian_collision {}
     Indicates which contact level is activated in which Cartesian dimension \((x,y,z,R,P,Y)\). More...
     
    std::array< double, 7 > tau_ext_hat_filtered {}
     \(\hat{\tau}_{\text{ext}}\) Low-pass filtered torques generated by external forces on the joints. More...
     
    std::array< double, 6 > O_F_ext_hat_K {}
     \(^OF_{K,\text{ext}}\) Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the base frame. More...
     
    std::array< double, 6 > K_F_ext_hat_K {}
     \(^{K}F_{K,\text{ext}}\) Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the stiffness frame. More...
     
    std::array< double, 6 > O_dP_EE_d {}
     \({^OdP_{EE}}_{d}\) Desired end effector twist in base frame. More...
     
    std::array< double, 3 > O_ddP_O {}
     \({^OddP}_O\) Linear component of the acceleration of the robot's base, expressed in frame parallel to the base frame, i.e. More...
     
    std::array< double, 16 > O_T_EE_c {}
     \({^OT_{EE}}_{c}\) Last commanded end effector pose of motion generation in base frame. More...
     
    std::array< double, 6 > O_dP_EE_c {}
     \({^OdP_{EE}}_{c}\) Last commanded end effector twist in base frame. More...
     
    std::array< double, 6 > O_ddP_EE_c {}
     \({^OddP_{EE}}_{c}\) Last commanded end effector acceleration in base frame. More...
     
    std::array< double, 7 > theta {}
     \(\theta\) Motor position. More...
     
    std::array< double, 7 > dtheta {}
     \(\dot{\theta}\) Motor velocity. More...
     
    +Errors current_errors {}
     Current error state.
     
    +Errors last_motion_errors {}
     Contains the errors that aborted the previous motion.
     
    double control_command_success_rate {}
     Percentage of the last 100 control commands that were successfully received by the robot. More...
     
    +RobotMode robot_mode = RobotMode::kUserStopped
     Current robot mode.
     
    Duration time {}
     Strictly monotonically increasing timestamp since robot start. More...
     
    +

    Detailed Description

    +

    Member Data Documentation

    + +

    ◆ cartesian_collision

    + +
    +
    + + + + +
    std::array<double, 6> franka::RobotState::cartesian_collision {}
    +
    + +

    Indicates which contact level is activated in which Cartesian dimension \((x,y,z,R,P,Y)\).

    +

    After contact disappears, the value stays the same until a reset command is sent.

    +
    See also
    Robot::setCollisionBehavior for setting sensitivity values.
    +
    +Robot::automaticErrorRecovery for performing a reset after a collision.
    + +
    +
    + +

    ◆ cartesian_contact

    + +
    +
    + + + + +
    std::array<double, 6> franka::RobotState::cartesian_contact {}
    +
    + +

    Indicates which contact level is activated in which Cartesian dimension \((x,y,z,R,P,Y)\).

    +

    After contact disappears, the value turns to zero.

    +
    See also
    Robot::setCollisionBehavior for setting sensitivity values.
    + +
    +
    + +

    ◆ control_command_success_rate

    + +
    +
    + + + + +
    double franka::RobotState::control_command_success_rate {}
    +
    + +

    Percentage of the last 100 control commands that were successfully received by the robot.

    +

    Shows a value of zero if no control or motion generator loop is currently running.

    +

    Range: \([0, 1]\).

    +
    Examples
    communication_test.cpp.
    +
    + +
    +
    + +

    ◆ ddelbow_c

    + +
    +
    + + + + +
    std::array<double, 2> franka::RobotState::ddelbow_c {}
    +
    + +

    Commanded elbow acceleration.

    +

    The values of the array are:

      +
    • ddelbow_c[0] Acceleration of the 3rd joint in \(\frac{rad}{s^2}\)
    • +
    • ddelbow_c[1] is always 0.
    • +
    + +
    +
    + +

    ◆ ddq_d

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::ddq_d {}
    +
    + +

    \(\ddot{q}_d\) Desired joint acceleration.

    +

    Unit: \([\frac{rad}{s^2}]\)

    + +
    +
    + +

    ◆ delbow_c

    + +
    +
    + + + + +
    std::array<double, 2> franka::RobotState::delbow_c {}
    +
    + +

    Commanded elbow velocity.

    +

    The values of the array are:

      +
    • delbow_c[0] Velocity of the 3rd joint in \(\frac{rad}{s}\)
    • +
    • delbow_c[1] is always 0.
    • +
    + +
    +
    + +

    ◆ dq

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::dq {}
    +
    + +

    \(\dot{q}\) Measured joint velocity.

    +

    Unit: \([\frac{rad}{s}]\)

    +
    Examples
    cartesian_impedance_control.cpp, motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.
    +
    + +
    +
    + +

    ◆ dq_d

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::dq_d {}
    +
    + +

    \(\dot{q}_d\) Desired joint velocity.

    +

    Unit: \([\frac{rad}{s}]\)

    + +
    +
    + +

    ◆ dtau_J

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::dtau_J {}
    +
    + +

    \(\dot{\tau_{J}}\) Derivative of measured link-side joint torque sensor signals.

    +

    Unit: \([\frac{Nm}{s}]\)

    + +
    +
    + +

    ◆ dtheta

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::dtheta {}
    +
    + +

    \(\dot{\theta}\) Motor velocity.

    +

    Unit: \([\frac{rad}{s}]\)

    + +
    +
    + +

    ◆ EE_T_K

    + +
    +
    + + + + +
    std::array<double, 16> franka::RobotState::EE_T_K {}
    +
    + +

    \(^{EE}T_{K}\) Stiffness frame pose in end effector frame.

    +

    Pose is represented as a 4x4 matrix in column-major format.

    +

    See also K frame.

    + +
    +
    + +

    ◆ elbow

    + +
    +
    + + + + +
    std::array<double, 2> franka::RobotState::elbow {}
    +
    + +

    Elbow configuration.

    +

    The values of the array are:

      +
    • elbow[0]: Position of the 3rd joint in \([rad]\).
    • +
    • elbow[1]: Flip direction of the elbow (4th joint):
        +
      • +1 if \(q_4 > q_{elbow-flip}\)
      • +
      • 0 if \(q_4 == q_{elbow-flip} \)
      • +
      • -1 if \(q_4 < q_{elbow-flip} \)
      • +
      +
    • +
    +

    with \(q_{elbow-flip}\) as specified in the robot interface specification page in the FCI Documentation.

    +
    Examples
    generate_elbow_motion.cpp.
    +
    + +
    +
    + +

    ◆ elbow_c

    + +
    +
    + + + + +
    std::array<double, 2> franka::RobotState::elbow_c {}
    +
    + +

    Commanded elbow configuration.

    +

    The values of the array are:

      +
    • elbow_c[0]: Position of the 3rd joint in \([rad]\).
    • +
    • elbow_c[1]: Flip direction of the elbow (4th joint):
        +
      • +1 if \(q_4 > q_{elbow-flip}\)
      • +
      • 0 if \(q_4 == q_{elbow-flip} \)
      • +
      • -1 if \(q_4 < q_{elbow-flip} \)
      • +
      +
    • +
    +

    with \(q_{elbow-flip}\) as specified in the robot interface specification page in the FCI Documentation.

    + +
    +
    + +

    ◆ elbow_d

    + +
    +
    + + + + +
    std::array<double, 2> franka::RobotState::elbow_d {}
    +
    + +

    Desired elbow configuration.

    +

    The values of the array are:

      +
    • elbow_d[0]: Position of the 3rd joint in \([rad]\).
    • +
    • elbow_d[1]: Flip direction of the elbow (4th joint):
        +
      • +1 if \(q_4 > q_{elbow-flip}\)
      • +
      • 0 if \(q_4 == q_{elbow-flip} \)
      • +
      • -1 if \(q_4 < q_{elbow-flip} \)
      • +
      +
    • +
    +

    with \(q_{elbow-flip}\) as specified in the robot interface specification page in the FCI Documentation.

    + +
    +
    + +

    ◆ F_T_EE

    + +
    +
    + + + + +
    std::array<double, 16> franka::RobotState::F_T_EE {}
    +
    + +

    \(^{F}T_{EE}\) End effector frame pose in flange frame.

    +

    Pose is represented as a 4x4 matrix in column-major format.

    +
    See also
    F_T_NE
    +
    +NE_T_EE
    +
    +Robot for an explanation of the F, NE and EE frames.
    + +
    +
    + +

    ◆ F_T_NE

    + +
    +
    + + + + +
    std::array<double, 16> franka::RobotState::F_T_NE {}
    +
    + +

    \(^{F}T_{NE}\) Nominal end effector frame pose in flange frame.

    +

    Pose is represented as a 4x4 matrix in column-major format.

    +
    See also
    F_T_EE
    +
    +NE_T_EE
    +
    +Robot for an explanation of the F, NE and EE frames.
    + +
    +
    + +

    ◆ joint_collision

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::joint_collision {}
    +
    + +

    Indicates which contact level is activated in which joint.

    +

    After contact disappears, the value stays the same until a reset command is sent.

    +
    See also
    Robot::setCollisionBehavior for setting sensitivity values.
    +
    +Robot::automaticErrorRecovery for performing a reset after a collision.
    + +
    +
    + +

    ◆ joint_contact

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::joint_contact {}
    +
    + +

    Indicates which contact level is activated in which joint.

    +

    After contact disappears, value turns to zero.

    +
    See also
    Robot::setCollisionBehavior for setting sensitivity values.
    + +
    +
    + +

    ◆ K_F_ext_hat_K

    + +
    +
    + + + + +
    std::array<double, 6> franka::RobotState::K_F_ext_hat_K {}
    +
    + +

    \(^{K}F_{K,\text{ext}}\) Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the stiffness frame.

    +

    Forces applied by the robot to the environment are positive, while forces applied by the environment on the robot are negative. Becomes \([0,0,0,0,0,0]\) when near or in a singularity. See also Stiffness frame K. Unit: \([N,N,N,Nm,Nm,Nm]\).

    + +
    +
    + +

    ◆ NE_T_EE

    + +
    +
    + + + + +
    std::array<double, 16> franka::RobotState::NE_T_EE {}
    +
    + +

    \(^{NE}T_{EE}\) End effector frame pose in nominal end effector frame.

    +

    Pose is represented as a 4x4 matrix in column-major format.

    +
    See also
    Robot::setEE to change this frame.
    +
    +F_T_EE
    +
    +F_T_NE
    +
    +Robot for an explanation of the F, NE and EE frames.
    + +
    +
    + +

    ◆ O_ddP_EE_c

    + +
    +
    + + + + +
    std::array<double, 6> franka::RobotState::O_ddP_EE_c {}
    +
    + +

    \({^OddP_{EE}}_{c}\) Last commanded end effector acceleration in base frame.

    +

    Unit: \([\frac{m}{s^2},\frac{m}{s^2},\frac{m}{s^2},\frac{rad}{s^2},\frac{rad}{s^2},\frac{rad}{s^2}]\).

    + +
    +
    + +

    ◆ O_ddP_O

    + +
    +
    + + + + +
    std::array<double, 3> franka::RobotState::O_ddP_O {}
    +
    + +

    \({^OddP}_O\) Linear component of the acceleration of the robot's base, expressed in frame parallel to the base frame, i.e.

    +

    the base's translational acceleration. If the base is resting this shows the direction of the gravity vector. It is harcoded for now to {0, 0, -9.81}.

    + +
    +
    + +

    ◆ O_dP_EE_c

    + +
    +
    + + + + +
    std::array<double, 6> franka::RobotState::O_dP_EE_c {}
    +
    + +

    \({^OdP_{EE}}_{c}\) Last commanded end effector twist in base frame.

    +

    Unit: \([\frac{m}{s},\frac{m}{s},\frac{m}{s},\frac{rad}{s},\frac{rad}{s},\frac{rad}{s}]\).

    + +
    +
    + +

    ◆ O_dP_EE_d

    + +
    +
    + + + + +
    std::array<double, 6> franka::RobotState::O_dP_EE_d {}
    +
    + +

    \({^OdP_{EE}}_{d}\) Desired end effector twist in base frame.

    +

    Unit: \([\frac{m}{s},\frac{m}{s},\frac{m}{s},\frac{rad}{s},\frac{rad}{s},\frac{rad}{s}]\).

    + +
    +
    + +

    ◆ O_F_ext_hat_K

    + +
    +
    + + + + +
    std::array<double, 6> franka::RobotState::O_F_ext_hat_K {}
    +
    + +

    \(^OF_{K,\text{ext}}\) Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the base frame.

    +

    Forces applied by the robot to the environment are positive, while forces applied by the environment on the robot are negative. Becomes \([0,0,0,0,0,0]\) when near or in a singularity. See also Stiffness frame K. Unit: \([N,N,N,Nm,Nm,Nm]\).

    + +
    +
    + +

    ◆ O_T_EE

    + +
    +
    + + + + +
    std::array<double, 16> franka::RobotState::O_T_EE {}
    +
    + +

    \(^{O}T_{EE}\) Measured end effector pose in base frame.

    +

    Pose is represented as a 4x4 matrix in column-major format.

    +
    Examples
    cartesian_impedance_control.cpp, generate_cartesian_pose_motion.cpp, and generate_elbow_motion.cpp.
    +
    + +
    +
    + +

    ◆ O_T_EE_c

    + +
    +
    + + + + +
    std::array<double, 16> franka::RobotState::O_T_EE_c {}
    +
    + +

    \({^OT_{EE}}_{c}\) Last commanded end effector pose of motion generation in base frame.

    +

    Pose is represented as a 4x4 matrix in column-major format.

    + +
    +
    + +

    ◆ O_T_EE_d

    + +
    +
    + + + + +
    std::array<double, 16> franka::RobotState::O_T_EE_d {}
    +
    + +

    \({^OT_{EE}}_{d}\) Last desired end effector pose of motion generation in base frame.

    +

    Pose is represented as a 4x4 matrix in column-major format.

    + +
    +
    + +

    ◆ q

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::q {}
    +
    +
    + +

    ◆ q_d

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::q_d {}
    +
    + +

    \(q_d\) Desired joint position.

    +

    Unit: \([rad]\)

    +
    Examples
    motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.
    +
    + +
    +
    + +

    ◆ tau_ext_hat_filtered

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::tau_ext_hat_filtered {}
    +
    + +

    \(\hat{\tau}_{\text{ext}}\) Low-pass filtered torques generated by external forces on the joints.

    +

    It does not include configured end-effector and load nor the mass and dynamics of the robot. tau_ext_hat_filtered is the error between tau_J and the expected torques given by the robot model. Unit: \([Nm]\).

    + +
    +
    + +

    ◆ tau_J

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::tau_J {}
    +
    + +

    \(\tau_{J}\) Measured link-side joint torque sensor signals.

    +

    Unit: \([Nm]\)

    +
    Examples
    force_control.cpp.
    +
    + +
    +
    + +

    ◆ tau_J_d

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::tau_J_d {}
    +
    + +

    \({\tau_J}_d\) Desired link-side joint torque sensor signals without gravity.

    +

    Unit: \([Nm]\)

    + +
    +
    + +

    ◆ theta

    + +
    +
    + + + + +
    std::array<double, 7> franka::RobotState::theta {}
    +
    + +

    \(\theta\) Motor position.

    +

    Unit: \([rad]\)

    + +
    +
    + +

    ◆ time

    + +
    +
    + + + + +
    Duration franka::RobotState::time {}
    +
    + +

    Strictly monotonically increasing timestamp since robot start.

    +

    Inside of control loops time_step parameter of Robot::control can be used instead.

    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1RobotState__coll__graph.map b/structfranka_1_1RobotState__coll__graph.map new file mode 100644 index 00000000..8f9d0c51 --- /dev/null +++ b/structfranka_1_1RobotState__coll__graph.map @@ -0,0 +1,5 @@ + + + + + diff --git a/structfranka_1_1RobotState__coll__graph.md5 b/structfranka_1_1RobotState__coll__graph.md5 new file mode 100644 index 00000000..974a4cf7 --- /dev/null +++ b/structfranka_1_1RobotState__coll__graph.md5 @@ -0,0 +1 @@ +559ffee771d54faefa00178ada80a094 \ No newline at end of file diff --git a/structfranka_1_1RobotState__coll__graph.png b/structfranka_1_1RobotState__coll__graph.png new file mode 100644 index 00000000..bf3ef354 Binary files /dev/null and b/structfranka_1_1RobotState__coll__graph.png differ diff --git a/structfranka_1_1VacuumGripperState-members.html b/structfranka_1_1VacuumGripperState-members.html new file mode 100644 index 00000000..d6706d83 --- /dev/null +++ b/structfranka_1_1VacuumGripperState-members.html @@ -0,0 +1,98 @@ + + + + + + + +libfranka: Member List + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    franka::VacuumGripperState Member List
    +
    + + + + + diff --git a/structfranka_1_1VacuumGripperState.html b/structfranka_1_1VacuumGripperState.html new file mode 100644 index 00000000..1384c2fa --- /dev/null +++ b/structfranka_1_1VacuumGripperState.html @@ -0,0 +1,194 @@ + + + + + + + +libfranka: franka::VacuumGripperState Struct Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    franka::VacuumGripperState Struct Reference
    +
    +
    + +

    Describes the vacuum gripper state. + More...

    + +

    #include <vacuum_gripper_state.h>

    +
    +Collaboration diagram for franka::VacuumGripperState:
    +
    +
    Collaboration graph
    + + + + +
    [legend]
    + + + + + + + + + + + + + + + + + + + + + + + +

    +Public Attributes

    +bool in_control_range {}
     Vacuum value within in setpoint area.
     
    +bool part_detached {}
     The part has been detached after a suction cycle.
     
    bool part_present {}
     Vacuum is over H2 and not yet under H2-h2. More...
     
    +VacuumGripperDeviceStatus device_status {}
     Current vacuum gripper device status.
     
    uint16_t actual_power {}
     Current vacuum gripper actual power. More...
     
    uint16_t vacuum {}
     Current system vacuum. More...
     
    +Duration time {}
     Strictly monotonically increasing timestamp since robot start.
     
    +

    Detailed Description

    +

    Describes the vacuum gripper state.

    +

    For more information check the cobot-pump manual.

    +
    Examples
    vacuum_object.cpp.
    +
    +

    Member Data Documentation

    + +

    ◆ actual_power

    + +
    +
    + + + + +
    uint16_t franka::VacuumGripperState::actual_power {}
    +
    + +

    Current vacuum gripper actual power.

    +

    Unit: \([%]\).

    + +
    +
    + +

    ◆ part_present

    + +
    +
    + + + + +
    bool franka::VacuumGripperState::part_present {}
    +
    + +

    Vacuum is over H2 and not yet under H2-h2.

    +

    For more information check the cobot-pump manual.

    + +
    +
    + +

    ◆ vacuum

    + +
    +
    + + + + +
    uint16_t franka::VacuumGripperState::vacuum {}
    +
    + +

    Current system vacuum.

    +

    Unit: \([mbar]\).

    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/structfranka_1_1VacuumGripperState__coll__graph.map b/structfranka_1_1VacuumGripperState__coll__graph.map new file mode 100644 index 00000000..9dba4cc0 --- /dev/null +++ b/structfranka_1_1VacuumGripperState__coll__graph.map @@ -0,0 +1,4 @@ + + + + diff --git a/structfranka_1_1VacuumGripperState__coll__graph.md5 b/structfranka_1_1VacuumGripperState__coll__graph.md5 new file mode 100644 index 00000000..9d8aff1c --- /dev/null +++ b/structfranka_1_1VacuumGripperState__coll__graph.md5 @@ -0,0 +1 @@ +7a1edd2fcd8c4eb577e9fd99d5db2f07 \ No newline at end of file diff --git a/structfranka_1_1VacuumGripperState__coll__graph.png b/structfranka_1_1VacuumGripperState__coll__graph.png new file mode 100644 index 00000000..819f8dcc Binary files /dev/null and b/structfranka_1_1VacuumGripperState__coll__graph.png differ diff --git a/sync_off.png b/sync_off.png new file mode 100644 index 00000000..3b443fc6 Binary files /dev/null and b/sync_off.png differ diff --git a/sync_on.png b/sync_on.png new file mode 100644 index 00000000..e08320fb Binary files /dev/null and b/sync_on.png differ diff --git a/tab_a.png b/tab_a.png new file mode 100644 index 00000000..3b725c41 Binary files /dev/null and b/tab_a.png differ diff --git a/tab_b.png b/tab_b.png new file mode 100644 index 00000000..e2b4a863 Binary files /dev/null and b/tab_b.png differ diff --git a/tab_h.png b/tab_h.png new file mode 100644 index 00000000..fd5cb705 Binary files /dev/null and b/tab_h.png differ diff --git a/tab_s.png b/tab_s.png new file mode 100644 index 00000000..ab478c95 Binary files /dev/null and b/tab_s.png differ diff --git a/tabs.css b/tabs.css new file mode 100644 index 00000000..7d45d36c --- /dev/null +++ b/tabs.css @@ -0,0 +1 @@ +.sm{position:relative;z-index:9999}.sm,.sm ul,.sm li{display:block;list-style:none;margin:0;padding:0;line-height:normal;direction:ltr;text-align:left;-webkit-tap-highlight-color:rgba(0,0,0,0)}.sm-rtl,.sm-rtl ul,.sm-rtl li{direction:rtl;text-align:right}.sm>li>h1,.sm>li>h2,.sm>li>h3,.sm>li>h4,.sm>li>h5,.sm>li>h6{margin:0;padding:0}.sm ul{display:none}.sm li,.sm a{position:relative}.sm a{display:block}.sm a.disabled{cursor:not-allowed}.sm:after{content:"\00a0";display:block;height:0;font:0px/0 serif;clear:both;visibility:hidden;overflow:hidden}.sm,.sm *,.sm *:before,.sm *:after{-moz-box-sizing:border-box;-webkit-box-sizing:border-box;box-sizing:border-box}.sm-dox{background-image:url("tab_b.png")}.sm-dox a,.sm-dox a:focus,.sm-dox a:hover,.sm-dox a:active{padding:0px 12px;padding-right:43px;font-family:"Lucida Grande","Geneva","Helvetica",Arial,sans-serif;font-size:13px;font-weight:bold;line-height:36px;text-decoration:none;text-shadow:0px 1px 1px rgba(255,255,255,0.9);color:#283A5D;outline:none}.sm-dox a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:#fff;text-shadow:0px 1px 1px #000}.sm-dox a.current{color:#D23600}.sm-dox a.disabled{color:#bbb}.sm-dox a span.sub-arrow{position:absolute;top:50%;margin-top:-14px;left:auto;right:3px;width:28px;height:28px;overflow:hidden;font:bold 12px/28px monospace !important;text-align:center;text-shadow:none;background:rgba(255,255,255,0.5);border-radius:5px}.sm-dox a.highlighted span.sub-arrow:before{display:block;content:'-'}.sm-dox>li:first-child>a,.sm-dox>li:first-child>:not(ul) a{border-radius:5px 5px 0 0}.sm-dox>li:last-child>a,.sm-dox>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul{border-radius:0 0 5px 5px}.sm-dox>li:last-child>a.highlighted,.sm-dox>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted{border-radius:0}.sm-dox ul{background:rgba(162,162,162,0.1)}.sm-dox ul a,.sm-dox ul a:focus,.sm-dox ul a:hover,.sm-dox ul a:active{font-size:12px;border-left:8px solid transparent;line-height:36px;text-shadow:none;background-color:white;background-image:none}.sm-dox ul a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:#fff;text-shadow:0px 1px 1px #000}.sm-dox ul ul a,.sm-dox ul ul a:hover,.sm-dox ul ul a:focus,.sm-dox ul ul a:active{border-left:16px solid transparent}.sm-dox ul ul ul a,.sm-dox ul ul ul a:hover,.sm-dox ul ul ul a:focus,.sm-dox ul ul ul a:active{border-left:24px solid transparent}.sm-dox ul ul ul ul a,.sm-dox ul ul ul ul a:hover,.sm-dox ul ul ul ul a:focus,.sm-dox ul ul ul ul a:active{border-left:32px solid transparent}.sm-dox ul ul ul ul ul a,.sm-dox ul ul ul ul ul a:hover,.sm-dox ul ul ul ul ul a:focus,.sm-dox ul ul ul ul ul a:active{border-left:40px solid transparent}@media (min-width: 768px){.sm-dox ul{position:absolute;width:12em}.sm-dox li{float:left}.sm-dox.sm-rtl li{float:right}.sm-dox ul li,.sm-dox.sm-rtl ul li,.sm-dox.sm-vertical li{float:none}.sm-dox a{white-space:nowrap}.sm-dox ul a,.sm-dox.sm-vertical a{white-space:normal}.sm-dox .sm-nowrap>li>a,.sm-dox .sm-nowrap>li>:not(ul) a{white-space:nowrap}.sm-dox{padding:0 10px;background-image:url("tab_b.png");line-height:36px}.sm-dox a span.sub-arrow{top:50%;margin-top:-2px;right:12px;width:0;height:0;border-width:4px;border-style:solid dashed dashed dashed;border-color:#283A5D transparent transparent transparent;background:transparent;border-radius:0}.sm-dox a,.sm-dox a:focus,.sm-dox a:active,.sm-dox a:hover,.sm-dox a.highlighted{padding:0px 12px;background-image:url("tab_s.png");background-repeat:no-repeat;background-position:right;border-radius:0 !important}.sm-dox a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:#fff;text-shadow:0px 1px 1px #000}.sm-dox a:hover span.sub-arrow{border-color:#fff transparent transparent transparent}.sm-dox a.has-submenu{padding-right:24px}.sm-dox li{border-top:0}.sm-dox>li>ul:before,.sm-dox>li>ul:after{content:'';position:absolute;top:-18px;left:30px;width:0;height:0;overflow:hidden;border-width:9px;border-style:dashed dashed solid dashed;border-color:transparent transparent #bbb transparent}.sm-dox>li>ul:after{top:-16px;left:31px;border-width:8px;border-color:transparent transparent #fff transparent}.sm-dox ul{border:1px solid #bbb;padding:5px 0;background:#fff;border-radius:5px !important;box-shadow:0 5px 9px rgba(0,0,0,0.2)}.sm-dox ul a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-color:transparent transparent transparent #555;border-style:dashed dashed dashed solid}.sm-dox ul a,.sm-dox ul a:hover,.sm-dox ul a:focus,.sm-dox ul a:active,.sm-dox ul a.highlighted{color:#555;background-image:none;border:0 !important;color:#555;background-image:none}.sm-dox ul a:hover{background-image:url("tab_a.png");background-repeat:repeat-x;color:#fff;text-shadow:0px 1px 1px #000}.sm-dox ul a:hover span.sub-arrow{border-color:transparent transparent transparent #fff}.sm-dox span.scroll-up,.sm-dox span.scroll-down{position:absolute;display:none;visibility:hidden;overflow:hidden;background:#fff;height:36px}.sm-dox span.scroll-up:hover,.sm-dox span.scroll-down:hover{background:#eee}.sm-dox span.scroll-up:hover span.scroll-up-arrow,.sm-dox span.scroll-up:hover span.scroll-down-arrow{border-color:transparent transparent #D23600 transparent}.sm-dox span.scroll-down:hover span.scroll-down-arrow{border-color:#D23600 transparent transparent transparent}.sm-dox span.scroll-up-arrow,.sm-dox span.scroll-down-arrow{position:absolute;top:0;left:50%;margin-left:-6px;width:0;height:0;overflow:hidden;border-width:6px;border-style:dashed dashed solid dashed;border-color:transparent transparent #555 transparent}.sm-dox span.scroll-down-arrow{top:8px;border-style:solid dashed dashed dashed;border-color:#555 transparent transparent transparent}.sm-dox.sm-rtl a.has-submenu{padding-right:12px;padding-left:24px}.sm-dox.sm-rtl a span.sub-arrow{right:auto;left:12px}.sm-dox.sm-rtl.sm-vertical a.has-submenu{padding:10px 20px}.sm-dox.sm-rtl.sm-vertical a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-rtl>li>ul:before{left:auto;right:30px}.sm-dox.sm-rtl>li>ul:after{left:auto;right:31px}.sm-dox.sm-rtl ul a.has-submenu{padding:10px 20px !important}.sm-dox.sm-rtl ul a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-vertical{padding:10px 0;border-radius:5px}.sm-dox.sm-vertical a{padding:10px 20px}.sm-dox.sm-vertical a:hover,.sm-dox.sm-vertical a:focus,.sm-dox.sm-vertical a:active,.sm-dox.sm-vertical a.highlighted{background:#fff}.sm-dox.sm-vertical a.disabled{background-image:url("tab_b.png")}.sm-dox.sm-vertical a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-style:dashed dashed dashed solid;border-color:transparent transparent transparent #555}.sm-dox.sm-vertical>li>ul:before,.sm-dox.sm-vertical>li>ul:after{display:none}.sm-dox.sm-vertical ul a{padding:10px 20px}.sm-dox.sm-vertical ul a:hover,.sm-dox.sm-vertical ul a:focus,.sm-dox.sm-vertical ul a:active,.sm-dox.sm-vertical ul a.highlighted{background:#eee}.sm-dox.sm-vertical ul a.disabled{background:#fff}} diff --git a/vacuum__gripper_8h.html b/vacuum__gripper_8h.html new file mode 100644 index 00000000..d82c0612 --- /dev/null +++ b/vacuum__gripper_8h.html @@ -0,0 +1,125 @@ + + + + + + + +libfranka: include/franka/vacuum_gripper.h File Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    vacuum_gripper.h File Reference
    +
    +
    + +

    Contains the franka::VacuumGripper type. +More...

    +
    #include <chrono>
    +#include <cstdint>
    +#include <memory>
    +#include <string>
    +#include <franka/vacuum_gripper_state.h>
    +
    +Include dependency graph for vacuum_gripper.h:
    +
    +
    + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  franka::VacuumGripper
     Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state, and allows the execution of commands. More...
     
    +

    Detailed Description

    +

    Contains the franka::VacuumGripper type.

    +
    + + + + diff --git a/vacuum__gripper_8h__incl.map b/vacuum__gripper_8h__incl.map new file mode 100644 index 00000000..75515a93 --- /dev/null +++ b/vacuum__gripper_8h__incl.map @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/vacuum__gripper_8h__incl.md5 b/vacuum__gripper_8h__incl.md5 new file mode 100644 index 00000000..f650075e --- /dev/null +++ b/vacuum__gripper_8h__incl.md5 @@ -0,0 +1 @@ +16de7b04545bf404fbfa68245069dcca \ No newline at end of file diff --git a/vacuum__gripper_8h__incl.png b/vacuum__gripper_8h__incl.png new file mode 100644 index 00000000..467c2c70 Binary files /dev/null and b/vacuum__gripper_8h__incl.png differ diff --git a/vacuum__gripper_8h_source.html b/vacuum__gripper_8h_source.html new file mode 100644 index 00000000..8d30b52f --- /dev/null +++ b/vacuum__gripper_8h_source.html @@ -0,0 +1,153 @@ + + + + + + + +libfranka: include/franka/vacuum_gripper.h Source File + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    vacuum_gripper.h
    +
    +
    +Go to the documentation of this file.
    1 // Copyright (c) 2023 Franka Robotics GmbH
    +
    2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    3 #pragma once
    +
    4 
    +
    5 #include <chrono>
    +
    6 #include <cstdint>
    +
    7 #include <memory>
    +
    8 #include <string>
    +
    9 
    + +
    11 
    +
    17 namespace franka {
    +
    18 
    +
    19 class Network;
    +
    20 
    + +
    29  public:
    +
    33  using ServerVersion = uint16_t;
    +
    34 
    +
    38  enum class ProductionSetupProfile { kP0, kP1, kP2, kP3 };
    +
    39 
    +
    48  explicit VacuumGripper(const std::string& franka_address);
    +
    49 
    +
    55  VacuumGripper(VacuumGripper&& vacuum_gripper) noexcept;
    +
    56 
    +
    64  VacuumGripper& operator=(VacuumGripper&& vacuum_gripper) noexcept;
    +
    65 
    +
    69  ~VacuumGripper() noexcept;
    +
    70 
    +
    83  bool vacuum(uint8_t vacuum,
    +
    84  std::chrono::milliseconds timeout,
    +
    85  ProductionSetupProfile profile = ProductionSetupProfile::kP0) const;
    +
    86 
    +
    97  bool dropOff(std::chrono::milliseconds timeout) const;
    +
    98 
    +
    107  bool stop() const;
    +
    108 
    + +
    118 
    +
    124  ServerVersion serverVersion() const noexcept;
    +
    125 
    +
    127  VacuumGripper(const VacuumGripper&) = delete;
    +
    128  VacuumGripper& operator=(const VacuumGripper&) = delete;
    +
    130 
    +
    131  private:
    +
    132  std::unique_ptr<Network> network_;
    +
    133 
    +
    134  uint16_t ri_version_;
    +
    135 };
    +
    136 
    +
    137 } // namespace franka
    +
    Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state,...
    Definition: vacuum_gripper.h:28
    +
    bool dropOff(std::chrono::milliseconds timeout) const
    Drops the grasped object off.
    +
    ProductionSetupProfile
    Vacuum production setup profile.
    Definition: vacuum_gripper.h:38
    +
    ServerVersion serverVersion() const noexcept
    Returns the software version reported by the connected server.
    +
    VacuumGripper & operator=(VacuumGripper &&vacuum_gripper) noexcept
    Move-assigns this VacuumGripper from another VacuumGripper instance.
    +
    bool stop() const
    Stops a currently running vacuum gripper vacuum or drop off operation.
    +
    bool vacuum(uint8_t vacuum, std::chrono::milliseconds timeout, ProductionSetupProfile profile=ProductionSetupProfile::kP0) const
    Vacuums an object.
    +
    uint16_t ServerVersion
    Version of the vacuum gripper server.
    Definition: vacuum_gripper.h:33
    +
    VacuumGripperState readOnce() const
    Waits for a vacuum gripper state update and returns it.
    +
    VacuumGripper(const std::string &franka_address)
    Establishes a connection with a vacuum gripper connected to a robot.
    +
    VacuumGripper(VacuumGripper &&vacuum_gripper) noexcept
    Move-constructs a new VacuumGripper instance.
    +
    ~VacuumGripper() noexcept
    Closes the connection.
    +
    Describes the vacuum gripper state.
    Definition: vacuum_gripper_state.h:31
    +
    Contains the franka::VacuumGripperState type.
    +
    + + + + diff --git a/vacuum__gripper__state_8h.html b/vacuum__gripper__state_8h.html new file mode 100644 index 00000000..22de8815 --- /dev/null +++ b/vacuum__gripper__state_8h.html @@ -0,0 +1,223 @@ + + + + + + + +libfranka: include/franka/vacuum_gripper_state.h File Reference + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    + +
    +
    vacuum_gripper_state.h File Reference
    +
    +
    + +

    Contains the franka::VacuumGripperState type. +More...

    +
    #include <cstdint>
    +#include <ostream>
    +#include <string>
    +#include <franka/duration.h>
    +
    +Include dependency graph for vacuum_gripper_state.h:
    +
    +
    + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    struct  franka::VacuumGripperState
     Describes the vacuum gripper state. More...
     
    + + + + +

    +Enumerations

    enum class  franka::VacuumGripperDeviceStatus : uint8_t { kGreen +, kYellow +, kOrange +, kRed + }
     Vacuum gripper device status. More...
     
    + + + + +

    +Functions

    std::ostream & franka::operator<< (std::ostream &ostream, const franka::VacuumGripperState &vacuum_gripper_state)
     Streams the vacuum gripper state as JSON object: {"field_name_1": value, "field_name_2": value, ...}. More...
     
    +

    Detailed Description

    +

    Contains the franka::VacuumGripperState type.

    +

    Enumeration Type Documentation

    + +

    ◆ VacuumGripperDeviceStatus

    + +
    +
    + + + + + +
    + + + + +
    enum franka::VacuumGripperDeviceStatus : uint8_t
    +
    +strong
    +
    + +

    Vacuum gripper device status.

    + + + + + +
    Enumerator
    kGreen 

    Device is working optimally.

    +
    kYellow 

    Device is working but there are warnings.

    +
    kOrange 

    Device is working but there are severe warnings.

    +
    kRed 

    Device is not working properly.

    +
    + +
    +
    +

    Function Documentation

    + +

    ◆ operator<<()

    + +
    +
    + + + + + + + + + + + + + + + + + + +
    std::ostream& franka::operator<< (std::ostream & ostream,
    const franka::VacuumGripperStatevacuum_gripper_state 
    )
    +
    + +

    Streams the vacuum gripper state as JSON object: {"field_name_1": value, "field_name_2": value, ...}.

    +
    Parameters
    + + + +
    [in]ostreamOstream instance
    [in]vacuum_gripper_stateVacuumGripperState struct instance to stream
    +
    +
    +
    Returns
    Ostream instance
    + +
    +
    +
    + + + + diff --git a/vacuum__gripper__state_8h__dep__incl.map b/vacuum__gripper__state_8h__dep__incl.map new file mode 100644 index 00000000..6b7154e2 --- /dev/null +++ b/vacuum__gripper__state_8h__dep__incl.map @@ -0,0 +1,4 @@ + + + + diff --git a/vacuum__gripper__state_8h__dep__incl.md5 b/vacuum__gripper__state_8h__dep__incl.md5 new file mode 100644 index 00000000..a4becc4b --- /dev/null +++ b/vacuum__gripper__state_8h__dep__incl.md5 @@ -0,0 +1 @@ +8e5086ecd9bfe0cb2bec5c8975cb5d3d \ No newline at end of file diff --git a/vacuum__gripper__state_8h__dep__incl.png b/vacuum__gripper__state_8h__dep__incl.png new file mode 100644 index 00000000..1472cf20 Binary files /dev/null and b/vacuum__gripper__state_8h__dep__incl.png differ diff --git a/vacuum__gripper__state_8h__incl.map b/vacuum__gripper__state_8h__incl.map new file mode 100644 index 00000000..7f248e57 --- /dev/null +++ b/vacuum__gripper__state_8h__incl.map @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/vacuum__gripper__state_8h__incl.md5 b/vacuum__gripper__state_8h__incl.md5 new file mode 100644 index 00000000..1c9c2b6d --- /dev/null +++ b/vacuum__gripper__state_8h__incl.md5 @@ -0,0 +1 @@ +3fe9235157066f1570010a22f2cda39e \ No newline at end of file diff --git a/vacuum__gripper__state_8h__incl.png b/vacuum__gripper__state_8h__incl.png new file mode 100644 index 00000000..314f1efa Binary files /dev/null and b/vacuum__gripper__state_8h__incl.png differ diff --git a/vacuum__gripper__state_8h_source.html b/vacuum__gripper__state_8h_source.html new file mode 100644 index 00000000..4fac4e7c --- /dev/null +++ b/vacuum__gripper__state_8h_source.html @@ -0,0 +1,143 @@ + + + + + + + +libfranka: include/franka/vacuum_gripper_state.h Source File + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + + +
    +
    + + +
    + +
    + + +
    +
    +
    +
    vacuum_gripper_state.h
    +
    +
    +Go to the documentation of this file.
    1 // Copyright (c) 2023 Franka Robotics GmbH
    +
    2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    3 #pragma once
    +
    4 
    +
    5 #include <cstdint>
    +
    6 #include <ostream>
    +
    7 #include <string>
    +
    8 
    +
    9 #include <franka/duration.h>
    +
    10 
    +
    16 namespace franka {
    +
    17 
    +
    21 enum class VacuumGripperDeviceStatus : uint8_t {
    +
    22  kGreen,
    +
    23  kYellow,
    +
    24  kOrange,
    +
    25  kRed
    +
    26 };
    +
    27 
    + + +
    36 
    +
    40  bool part_detached{};
    +
    41 
    +
    45  bool part_present{};
    +
    46 
    + +
    51 
    +
    55  uint16_t actual_power{};
    +
    56 
    +
    60  uint16_t vacuum{};
    +
    61 
    + +
    66 };
    +
    67 
    +
    77 std::ostream& operator<<(std::ostream& ostream,
    +
    78  const franka::VacuumGripperState& vacuum_gripper_state);
    +
    79 
    +
    80 } // namespace franka
    +
    Represents a duration with millisecond resolution.
    Definition: duration.h:19
    +
    Contains the franka::Duration type.
    +
    std::ostream & operator<<(std::ostream &ostream, const Errors &errors)
    Streams the errors as JSON array.
    +
    Describes the vacuum gripper state.
    Definition: vacuum_gripper_state.h:31
    +
    uint16_t actual_power
    Current vacuum gripper actual power.
    Definition: vacuum_gripper_state.h:55
    +
    bool in_control_range
    Vacuum value within in setpoint area.
    Definition: vacuum_gripper_state.h:35
    +
    bool part_detached
    The part has been detached after a suction cycle.
    Definition: vacuum_gripper_state.h:40
    +
    Duration time
    Strictly monotonically increasing timestamp since robot start.
    Definition: vacuum_gripper_state.h:65
    +
    VacuumGripperDeviceStatus device_status
    Current vacuum gripper device status.
    Definition: vacuum_gripper_state.h:50
    +
    uint16_t vacuum
    Current system vacuum.
    Definition: vacuum_gripper_state.h:60
    +
    bool part_present
    Vacuum is over H2 and not yet under H2-h2.
    Definition: vacuum_gripper_state.h:45
    +
    VacuumGripperDeviceStatus
    Vacuum gripper device status.
    Definition: vacuum_gripper_state.h:21
    +
    @ kOrange
    Device is working but there are severe warnings.
    +
    @ kGreen
    Device is working optimally.
    +
    @ kYellow
    Device is working but there are warnings.
    +
    @ kRed
    Device is not working properly.
    +
    + + + + diff --git a/vacuum_object_8cpp-example.html b/vacuum_object_8cpp-example.html new file mode 100644 index 00000000..ba2ec2bd --- /dev/null +++ b/vacuum_object_8cpp-example.html @@ -0,0 +1,144 @@ + + + + + + + +libfranka: vacuum_object.cpp + + + + + + + + + + + +
    +
    + + + + + + + +
    +
    libfranka +  0.14.0 +
    +
    FCI C++ API
    +
    +
    + + + + + + + +
    + +
    +
    + + +
    + +
    + +
    +
    +
    vacuum_object.cpp
    +
    +
    +

    An example showing how to control FRANKA's vacuum gripper.

    +
    // Copyright (c) 2019 Franka Robotics GmbH
    +
    // Use of this source code is governed by the Apache-2.0 license, see LICENSE
    +
    #include <iostream>
    +
    #include <thread>
    +
    + + +
    +
    int main(int argc, char** argv) {
    +
    if (argc != 2) {
    +
    std::cerr << "Usage: ./vacuum_object <vacuum-gripper-hostname>" << std::endl;
    +
    return -1;
    +
    }
    +
    +
    franka::VacuumGripper vacuum_gripper(argv[1]);
    +
    try {
    +
    // Print a vacuum gripper state.
    +
    franka::VacuumGripperState vacuum_gripper_state = vacuum_gripper.readOnce();
    +
    std::cout << "Initial vacuum gripper state: " << vacuum_gripper_state << std::endl;
    +
    +
    // Vacuum the object.
    +
    if (!vacuum_gripper.vacuum(100, std::chrono::milliseconds(1000))) {
    +
    std::cout << "Failed to vacuum the object." << std::endl;
    +
    return -1;
    +
    }
    +
    +
    vacuum_gripper_state = vacuum_gripper.readOnce();
    +
    std::cout << "Vacuum gripper state after applying vacuum: " << vacuum_gripper_state
    +
    << std::endl;
    +
    +
    // Wait 3s and check afterwards, if the object is still grasped.
    +
    std::this_thread::sleep_for(std::chrono::duration<double, std::milli>(3000));
    +
    +
    vacuum_gripper_state = vacuum_gripper.readOnce();
    +
    if (!vacuum_gripper_state.in_control_range) {
    +
    std::cout << "Object lost." << std::endl;
    +
    return -1;
    +
    }
    +
    +
    std::cout << "Vacuumed object, will release it now." << std::endl;
    +
    vacuum_gripper.dropOff(std::chrono::milliseconds(1000));
    +
    } catch (franka::Exception const& e) {
    +
    vacuum_gripper.stop();
    +
    std::cout << e.what() << std::endl;
    +
    return -1;
    +
    }
    +
    +
    return 0;
    +
    }
    +
    Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state,...
    Definition: vacuum_gripper.h:28
    +
    bool dropOff(std::chrono::milliseconds timeout) const
    Drops the grasped object off.
    +
    bool stop() const
    Stops a currently running vacuum gripper vacuum or drop off operation.
    +
    bool vacuum(uint8_t vacuum, std::chrono::milliseconds timeout, ProductionSetupProfile profile=ProductionSetupProfile::kP0) const
    Vacuums an object.
    +
    VacuumGripperState readOnce() const
    Waits for a vacuum gripper state update and returns it.
    +
    Contains exception definitions.
    +
    Base class for all exceptions used by libfranka.
    Definition: exception.h:20
    +
    Describes the vacuum gripper state.
    Definition: vacuum_gripper_state.h:31
    +
    bool in_control_range
    Vacuum value within in setpoint area.
    Definition: vacuum_gripper_state.h:35
    +
    Contains the franka::VacuumGripper type.
    +
    + + + +