 |
libfranka
0.14.1
FCI C++ API
|
Go to the documentation of this file.
7 #include <initializer_list>
52 Torques(
const std::array<double, 7>& torques) noexcept;
61 Torques(std::initializer_list<double> torques);
79 JointPositions(
const std::array<double, 7>& joint_positions) noexcept;
93 std::array<double, 7>
q{};
107 JointVelocities(
const std::array<double, 7>& joint_velocities) noexcept;
121 std::array<double, 7>
dq{};
136 CartesianPose(
const std::array<double, 16>& cartesian_pose) noexcept;
147 const std::array<double, 2>&
elbow) noexcept;
171 CartesianPose(std::initializer_list<double> cartesian_pose, std::initializer_list<double>
elbow);
231 const std::array<double, 2>&
elbow) noexcept;
255 std::initializer_list<double>
elbow);
261 std::array<double, 6> O_dP_EE{};
Stores values for joint velocity motion generation.
Definition: control_types.h:99
JointPositions(const std::array< double, 7 > &joint_positions) noexcept
Creates a new JointPositions instance.
std::array< double, 7 > tau_J
Desired torques in [Nm].
Definition: control_types.h:66
Torques(const std::array< double, 7 > &torques) noexcept
Creates a new Torques instance.
CartesianPose(const std::array< double, 16 > &cartesian_pose) noexcept
Creates a new CartesianPose instance.
Stores values for Cartesian velocity motion generation.
Definition: control_types.h:211
JointVelocities(const std::array< double, 7 > &joint_velocities) noexcept
Creates a new JointVelocities instance.
Stores joint-level torque commands without gravity and friction.
Definition: control_types.h:45
std::array< double, 2 > elbow
Elbow configuration.
Definition: control_types.h:193
ControllerMode
Available controller modes for a franka::Robot.
Definition: control_types.h:19
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition: control_types.h:294
Stores values for joint position motion generation.
Definition: control_types.h:72
bool hasElbow() const noexcept
Determines whether there is a stored elbow configuration.
Helper type for control and motion generation loops.
Definition: control_types.h:35
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
bool motion_finished
Determines whether to finish a currently running motion.
Definition: control_types.h:39
RealtimeConfig
Used to decide whether to enforce realtime mode for a control loop thread.
Definition: control_types.h:26
std::array< double, 7 > dq
Desired joint velocities in .
Definition: control_types.h:121
std::array< double, 7 > q
Desired joint angles in [rad].
Definition: control_types.h:93