libfranka 0.19.0
FCI C++ API
Loading...
Searching...
No Matches
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
14namespace franka {
15
19enum class ControllerMode { // NOLINT(performance-enum-size)
20 kJointImpedance,
21 kCartesianImpedance
22};
23
29enum class RealtimeConfig { kEnforce, kIgnore }; // NOLINT(performance-enum-size)
30
38struct Finishable {
42 bool motion_finished = false;
43};
44
48class Torques : public Finishable {
49 public:
55 Torques(const std::array<double, 7>& torques) noexcept;
56
64 Torques(std::initializer_list<double> torques);
65
69 std::array<double, 7> tau_J{}; // NOLINT(readability-identifier-naming)
70};
71
75class JointPositions : public Finishable {
76 public:
82 JointPositions(const std::array<double, 7>& joint_positions) noexcept;
83
91 JointPositions(std::initializer_list<double> joint_positions);
92
96 std::array<double, 7> q{};
97};
98
103 public:
110 JointVelocities(const std::array<double, 7>& joint_velocities) noexcept;
111
119 JointVelocities(std::initializer_list<double> joint_velocities);
120
124 std::array<double, 7> dq{};
125};
126
130class CartesianPose : public Finishable {
131 public:
139 CartesianPose(const std::array<double, 16>& cartesian_pose) noexcept;
140
149 CartesianPose(const std::array<double, 16>& cartesian_pose,
150 const std::array<double, 2>& elbow) noexcept;
151
161 CartesianPose(std::initializer_list<double> cartesian_pose);
162
174 CartesianPose(std::initializer_list<double> cartesian_pose, std::initializer_list<double> elbow);
175
181 std::array<double, 16> O_T_EE{}; // NOLINT(readability-identifier-naming)
182
196 std::array<double, 2> elbow{};
197
204 bool hasElbow() const noexcept;
205};
206
215 public:
223 CartesianVelocities(const std::array<double, 6>& cartesian_velocities) noexcept;
224
233 CartesianVelocities(const std::array<double, 6>& cartesian_velocities,
234 const std::array<double, 2>& elbow) noexcept;
235
245 CartesianVelocities(std::initializer_list<double> cartesian_velocities);
246
257 CartesianVelocities(std::initializer_list<double> cartesian_velocities,
258 std::initializer_list<double> elbow);
259
264 std::array<double, 6> O_dP_EE{}; // NOLINT(readability-identifier-naming)
265
278 std::array<double, 2> elbow{};
279
285 bool hasElbow() const noexcept;
286};
287
297inline Torques MotionFinished(Torques command) noexcept { // NOLINT(readability-identifier-naming)
298 command.motion_finished = true;
299 return command;
300}
301
311inline JointPositions MotionFinished( // NOLINT(readability-identifier-naming)
312 JointPositions command) noexcept {
313 command.motion_finished = true;
314 return command;
315}
316
326inline JointVelocities MotionFinished( // NOLINT(readability-identifier-naming)
327 JointVelocities command) noexcept {
328 command.motion_finished = true;
329 return command;
330}
331
341inline CartesianPose MotionFinished( // NOLINT(readability-identifier-naming)
342 CartesianPose command) noexcept {
343 command.motion_finished = true;
344 return command;
345}
346
356inline CartesianVelocities MotionFinished( // NOLINT(readability-identifier-naming)
357 CartesianVelocities command) noexcept {
358 command.motion_finished = true;
359 return command;
360}
361
362} // namespace franka
Stores values for Cartesian pose motion generation.
Definition control_types.h:130
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:181
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:196
Stores values for Cartesian velocity motion generation.
Definition control_types.h:214
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:75
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:96
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:102
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:124
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:48
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:69
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition control_types.h:297
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:29
Helper type for control and motion generation loops.
Definition control_types.h:38
bool motion_finished
Determines whether to finish a currently running motion.
Definition control_types.h:42