7#include <initializer_list>
52 Torques(
const std::array<double, 7>& torques)
noexcept;
61 Torques(std::initializer_list<double> torques);
93 std::array<double, 7>
q{};
121 std::array<double, 7>
dq{};
147 const std::array<double, 2>&
elbow)
noexcept;
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 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