Skip to content

Commit

Permalink
Merge pull request #143 in SWDEV/libfranka from api-documentation-upd…
Browse files Browse the repository at this point in the history
…ate to develop

* commit '906c5470439d28df25c50520c1ca08c353e20bf4':
  Add missing `include`s
  Check for errors on the socket in `Network::tcpReadFromBuffer`. An error could occur for example when the TCP connection is reset.
  Add CI config for Focal
  use CMAKE_CURRENT_SOURCE_DIR instead of CMAKE_SOURCE_DIR
  Updates and improvements to api documentation
  Updated description in robot_state.h
  • Loading branch information
christoph-jaehne committed Nov 25, 2021
2 parents 952af1a + 906c547 commit 976a143
Show file tree
Hide file tree
Showing 8 changed files with 144 additions and 78 deletions.
2 changes: 1 addition & 1 deletion examples/examples_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
*/

/**
* Sets a default collision behavior, joint impedance, Cartesian impedance, and filter frequency.
* Sets a default collision behavior, joint impedance and Cartesian impedance.
*
* @param[in] robot Robot instance to set behavior on.
*/
Expand Down
61 changes: 40 additions & 21 deletions include/franka/control_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,14 @@ class Torques : public Finishable {
/**
* Creates a new Torques instance.
*
* @param[in] torques Desired joint-level torques without gravity and friction in [Nm].
* @param[in] torques Desired joint-level torques without gravity and friction in \f$[Nm]\f$.
*/
Torques(const std::array<double, 7>& torques) noexcept;

/**
* Creates a new Torques instance.
*
* @param[in] torques Desired joint-level torques without gravity and friction in [Nm].
* @param[in] torques Desired joint-level torques without gravity and friction in \f$[Nm]\f$.
*
* @throw std::invalid_argument if the given initializer list has an invalid number of arguments.
*/
Expand All @@ -74,14 +74,14 @@ class JointPositions : public Finishable {
/**
* Creates a new JointPositions instance.
*
* @param[in] joint_positions Desired joint angles in [rad].
* @param[in] joint_positions Desired joint angles in \f$[rad]\f$.
*/
JointPositions(const std::array<double, 7>& joint_positions) noexcept;

/**
* Creates a new JointPositions instance.
*
* @param[in] joint_positions Desired joint angles in [rad].
* @param[in] joint_positions Desired joint angles in \f$[rad]\f$.
*
* @throw std::invalid_argument if the given initializer list has an invalid number of arguments.
*/
Expand All @@ -101,22 +101,22 @@ class JointVelocities : public Finishable {
/**
* Creates a new JointVelocities instance.
*
* @param[in] joint_velocities Desired joint velocities in [rad/s].
* @param[in] joint_velocities Desired joint velocities in \f$[\frac{rad}{s}]\f$.
*
*/
JointVelocities(const std::array<double, 7>& joint_velocities) noexcept;

/**
* Creates a new JointVelocities instance.
*
* @param[in] joint_velocities Desired joint velocities in [rad/s].
* @param[in] joint_velocities Desired joint velocities in \f$[\frac{rad}{s}]\f$.
*
* @throw std::invalid_argument if the given initializer list has an invalid number of arguments.
*/
JointVelocities(std::initializer_list<double> joint_velocities);

/**
* Desired joint velocities in [rad/s].
* Desired joint velocities in \f$[\frac{rad}{s}]\f$.
*/
std::array<double, 7> dq{};
};
Expand Down Expand Up @@ -181,8 +181,14 @@ class CartesianPose : public Finishable {
* Elbow configuration.
*
* The values of the array are:
* - [0] Position of the 3rd joint in [rad].
* - [1] Sign of the 4th joint. Can be +1 or -1.
* - elbow[0]: Position of the 3rd joint in \f$[rad]\f$.
* - elbow[1]: Flip direction of the elbow (4th joint):
* - +1 if \f$q_4 > q_{elbow-flip}\f$
* - 0 if \f$q_4 == q_{elbow-flip} \f$
* - -1 if \f$q_4 < q_{elbow-flip} \f$
* .
* with \f$q_{elbow-flip}\f$ as specified in the robot interface specification page in the FCI
* Documentation.
*/
std::array<double, 2> elbow{};

Expand All @@ -197,22 +203,28 @@ class CartesianPose : public Finishable {

/**
* 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.
*/
class CartesianVelocities : public Finishable {
public:
/**
* Creates a new CartesianVelocities instance.
*
* @param[in] cartesian_velocities Desired Cartesian velocity w.r.t. O-frame {dx in [m/s], dy in
* [m/s], dz in [m/s], omegax in [rad/s], omegay in [rad/s], omegaz in [rad/s]}.
* @param[in] cartesian_velocities Desired Cartesian velocity with respect to the @ref o-frame
* "base frame O" with \f$(\dot x, \dot y, \dot z)\f$ in \f$[m/s]\f$ and \f$(\omega_x,
* \omega_y, \omega_z)\f$ in \f$[rad/s]\f$.
*/
CartesianVelocities(const std::array<double, 6>& cartesian_velocities) noexcept;

/**
* Creates a new CartesianVelocities instance.
*
* @param[in] cartesian_velocities Desired Cartesian velocity w.r.t. O-frame {dx in [m/s], dy in
* [m/s], dz in [m/s], omegax in [rad/s], omegay in [rad/s], omegaz in [rad/s]}.
* @param[in] cartesian_velocities Desired Cartesian velocity with respect to the @ref o-frame
* "base frame O" with \f$(\dot x, \dot y, \dot z)\f$ in \f$[m/s]\f$ and \f$(\omega_x,
* \omega_y, \omega_z)\f$ in \f$[rad/s]\f$.
* @param[in] elbow Elbow configuration (see @ref elbow member for more details).
*/
CartesianVelocities(const std::array<double, 6>& cartesian_velocities,
Expand All @@ -221,8 +233,9 @@ class CartesianVelocities : public Finishable {
/**
* Creates a new CartesianVelocities instance.
*
* @param[in] cartesian_velocities Desired Cartesian velocity w.r.t. O-frame {dx in [m/s], dy in
* [m/s], dz in [m/s], omegax in [rad/s], omegay in [rad/s], omegaz in [rad/s]}.
* @param[in] cartesian_velocities Desired Cartesian velocity with respect to the @ref o-frame
* "base frame O" with \f$(\dot x, \dot y, \dot z)\f$ in \f$[m/s]\f$ and \f$(\omega_x,
* \omega_y, \omega_z)\f$ in \f$[rad/s]\f$.
*
* @throw std::invalid_argument if the given initializer list has an invalid number of arguments.
*/
Expand All @@ -231,8 +244,9 @@ class CartesianVelocities : public Finishable {
/**
* Creates a new CartesianVelocities instance.
*
* @param[in] cartesian_velocities Desired Cartesian velocity w.r.t. O-frame {dx in [m/s], dy in
* [m/s], dz in [m/s], omegax in [rad/s], omegay in [rad/s], omegaz in [rad/s]}.
* @param[in] cartesian_velocities Desired Cartesian velocity with respect to the @ref o-frame
* "base frame O" with \f$(\dot x, \dot y, \dot z)\f$ in \f$[m/s]\f$ and \f$(\omega_x,
* \omega_y, \omega_z)\f$ in \f$[rad/s]\f$.
* @param[in] elbow Elbow configuration (see @ref elbow member for more details).
*
* @throw std::invalid_argument if a given initializer list has an invalid number of arguments.
Expand All @@ -241,17 +255,22 @@ class CartesianVelocities : public Finishable {
std::initializer_list<double> elbow);

/**
* Desired Cartesian velocity w.r.t. O-frame {dx in [m/s], dy in [m/s], dz in [m/s], omegax in
* [rad/s], omegay in [rad/s], omegaz in [rad/s]}.
* Cartesian velocity with respect to the @ref o-frame "base frame O" with \f$(\dot x, \dot y,
* \dot z)\f$ in \f$[m/s]\f$ and \f$(\omega_x, \omega_y, \omega_z)\f$ in \f$[rad/s]\f$.
*/
std::array<double, 6> O_dP_EE{}; // NOLINT(readability-identifier-naming)

/**
* Elbow configuration.
*
* The values of the array are:
* - [0] Position of the 3rd joint in [rad].
* - [1] Sign of the 4th joint. Can be +1 or -1.
* - elbow[0]: Position of the 3rd joint in \f$[rad]\f$.
* - elbow[1]: Flip direction of the elbow (4th joint):
* - +1 if \f$q_4 > \alpha\f$
* - 0 if \f$q_4 == \alpha \f$
* - -1 if \f$q_4 < \alpha \f$
* .
* with \f$\alpha = -0.467002423653011\f$ \f$rad\f$
*/
std::array<double, 2> elbow{};

Expand Down
2 changes: 1 addition & 1 deletion include/franka/exception.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ struct ControlException : public Exception {
explicit ControlException(const std::string& what, std::vector<franka::Record> log = {}) noexcept;

/**
* Vector of states and commands logged just before the exception occured.
* Vector of states and commands logged just before the exception occurred.
*/
const std::vector<franka::Record> log;
};
Expand Down
10 changes: 5 additions & 5 deletions include/franka/gripper.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,9 @@ class Gripper {
* An object is considered grasped if the distance \f$d\f$ between the gripper fingers satisfies
* \f$(\text{width} - \text{epsilon_inner}) < d < (\text{width} + \text{epsilon_outer})\f$.
*
* @param[in] width Size of the object to grasp. [m]
* @param[in] speed Closing speed. [m/s]
* @param[in] force Grasping force. [N]
* @param[in] width Size of the object to grasp in \f$[m]\f$.
* @param[in] speed Closing speed in \f$[\frac{m}{s}]\f$.
* @param[in] force Grasping force in \f$[N]\f$.
* @param[in] epsilon_inner Maximum tolerated deviation when the actual grasped width is smaller
* than the commanded grasp width.
* @param[in] epsilon_outer Maximum tolerated deviation when the actual grasped width is larger
Expand All @@ -105,8 +105,8 @@ class Gripper {
/**
* Moves the gripper fingers to a specified width.
*
* @param[in] width Intended opening width. [m]
* @param[in] speed Closing speed. [m/s]
* @param[in] width Intended opening width in \f$[m]\f$.
* @param[in] speed Closing speed in \f$[\frac{m}{s}]\f$.
*
* @return True if command was successful, false otherwise.
*
Expand Down
2 changes: 1 addition & 1 deletion include/franka/model.h
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ class Model {
/**
* Calculates the 7x7 mass matrix. Unit: \f$[kg \times m^2]\f$.
*
* @param[in] robot_state State from which the pose should be calculated.
* @param[in] robot_state State from which the mass matrix should be calculated.
*
* @return Vectorized 7x7 mass matrix, column-major.
*/
Expand Down
16 changes: 8 additions & 8 deletions include/franka/rate_limiting.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ constexpr double kLimitEps = 1e-3;
*/
constexpr double kNormEps = std::numeric_limits<double>::epsilon();
/**
* Number of packets losts considered for the definition of velocity limits.
* Number of packets lost considered for the definition of velocity limits.
* When a packet is lost, FCI assumes a constant acceleration model
*/
constexpr double kTolNumberPacketsLost = 3.0;
Expand Down Expand Up @@ -131,7 +131,7 @@ std::array<double, 7> limitRate(const std::array<double, 7>& max_derivatives,
* @param[in] max_acceleration Maximum allowed acceleration.
* @param[in] max_jerk Maximum allowed jerk.
* @param[in] commanded_velocity Commanded joint velocity of the current time step.
* @param[in] last_commanded_velocity Commanded joint velocitiy of the previous time step.
* @param[in] last_commanded_velocity Commanded joint velocity of the previous time step.
* @param[in] last_commanded_acceleration Commanded joint acceleration of the previous time step.
*
* @throw std::invalid_argument if commanded_velocity is infinite or NaN.
Expand Down Expand Up @@ -202,12 +202,12 @@ std::array<double, 7> limitRate(const std::array<double, 7>& max_velocity,
* FCI filters must be deactivated to work properly.
*
* @param[in] max_velocity Per-joint maximum allowed velocity.
* @param[in] max_acceleration Per-joint maximum allowed velocity.
* @param[in] max_jerk Per-joint maximum allowed velocity.
* @param[in] commanded_positions Per-joint maximum allowed acceleration.
* @param[in] last_commanded_positions Commanded joint positions of the current time step.
* @param[in] last_commanded_velocities Commanded joint positions of the previous time step.
* @param[in] last_commanded_accelerations Commanded joint velocities of the previous time step.
* @param[in] max_acceleration Per-joint maximum allowed acceleration.
* @param[in] max_jerk Per-joint maximum allowed jerk.
* @param[in] commanded_positions Commanded joint positions of the current time step.
* @param[in] last_commanded_positions Commanded joint positions of the previous time step.
* @param[in] last_commanded_velocities Commanded joint velocities of the previous time step.
* @param[in] last_commanded_accelerations Commanded joint accelerations of the previous time step.
*
* @throw std::invalid_argument if commanded_positions are infinite or NaN.
*
Expand Down
57 changes: 40 additions & 17 deletions include/franka/robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,19 +29,38 @@ class Model;
* @note
* The members of this class are threadsafe.
*
* @anchor o-frame
* @par 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.
*
* @anchor f-frame
* @par 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.
*
* @anchor ne-frame
* @par Nominal end effector frame NE
* The nominal end effector frame is configured outside of libfranka and cannot be changed here.
* 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.
*
* @par End effector frame EE
* @anchor ee-frame
* @par 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).
* With Robot::setEE, a custom transformation matrix can be set.
* (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.
*
* @anchor k-frame
* @par 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.
* It can be set with Robot::setK.
* 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).
*/
class Robot {
public:
Expand Down Expand Up @@ -203,7 +222,7 @@ class Robot {
* @throw InvalidOperationException if a conflicting operation is already running.
* @throw NetworkException if the connection is lost, e.g. after a timeout.
* @throw RealtimeException if realtime priority cannot be set for the current thread.
* @throw std::invalid_argument if joint-level torque or joint velocitiy commands are NaN or
* @throw std::invalid_argument if joint-level torque or joint velocity commands are NaN or
* infinity.
*
* @see Robot::Robot to change behavior if realtime priority cannot be set.
Expand Down Expand Up @@ -527,7 +546,8 @@ class Robot {
*
* User-provided torques are not affected by this setting.
*
* @param[in] K_theta Joint impedance values \f$K_{\theta}\f$.
* @param[in] K_theta Joint impedance values \f$K_{\theta_{1-7}} = \in [0,14250]
* \frac{Nm}{rad}\f$
*
* @throw CommandException if the Control reports an error.
* @throw NetworkException if the connection is lost, e.g. after a timeout.
Expand All @@ -536,13 +556,16 @@ class Robot {
const std::array<double, 7>& K_theta); // NOLINT(readability-identifier-naming)

/**
* Sets the Cartesian impedance for (x, y, z, roll, pitch, yaw) in the internal controller.
* Sets the Cartesian stiffness/compliance (for x, y, z, roll, pitch, yaw) in the internal
* controller.
*
* User-provided torques are not affected by this setting.
* 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.
*
* @param[in] K_x Cartesian impedance values \f$K_x=(x \in [10,3000] \frac{N}{m}, y \in [10,3000]
* \frac{N}{m}, z \in [10,3000] \frac{N}{m}, R \in [1,300] \frac{Nm}{rad}, P \in [1,300]
* \frac{Nm}{rad}, Y \in [1,300] \frac{Nm}{rad})\f$
* @param[in] K_x Cartesian impedance values \f$K_x=(K_{x_{x,y,z}} \in [10,3000] \frac{N}{m},
* K_{x_{R,P,Y}} \in [1,300] \frac{Nm}{rad})\f$
* @throw CommandException if the Control reports an error.
* @throw NetworkException if the connection is lost, e.g. after a timeout.
*/
Expand Down Expand Up @@ -589,10 +612,10 @@ class Robot {
* @throw CommandException if the Control reports an error.
* @throw NetworkException if the connection is lost, e.g. after a timeout.
*
* @see RobotState::NE_T_EE for end effector pose in nominal end effector frame.
* @see RobotState::O_T_EE for end effector pose in world base frame.
* @see RobotState::F_T_EE for end effector pose in flange frame.
* @see Robot for an explanation of the NE and EE frames.
* @see RobotState::NE_T_EE for end effector pose in @ref ne-frame "nominal end effector frame
* NE".
* @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".
*/
void setEE(const std::array<double, 16>& NE_T_EE); // NOLINT(readability-identifier-naming)

Expand Down
Loading

0 comments on commit 976a143

Please sign in to comment.