Public Member Functions | Public Attributes | Private Attributes | List of all members
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. More...
 
 Errors (const Errors &other)
 Copy constructs a new Errors instance. More...
 
 Errors (const std::array< bool, 37 > &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...
 
Errorsoperator= (Errors other)
 Assigns this Errors instance from another Errors value. More...
 

Public Attributes

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

Private Attributes

std::array< bool, 37 > errors_ {}
 

Detailed Description

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

Definition at line 18 of file errors.h.

Constructor & Destructor Documentation

franka::Errors::Errors ( )

Creates an empty Errors instance.

franka::Errors::Errors ( const Errors other)

Copy constructs a new Errors instance.

Parameters
[in]otherOther Errors instance.
franka::Errors::Errors ( const std::array< bool, 37 > &  errors)

Creates a new Errors instance from the given array.

Parameters
errorsArray of error flags.

Member Function Documentation

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

Check if any error flag is set to true.

Returns
True if any errors are set.
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
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

const bool& franka::Errors::cartesian_motion_generator_acceleration_discontinuity

True if commanded acceleration in Cartesian motion generators is discontinuous (target values are too far apart).

Definition at line 158 of file errors.h.

const bool& franka::Errors::cartesian_motion_generator_elbow_limit_violation

True if an external Cartesian motion generator would move into an elbow limit.

Definition at line 144 of file errors.h.

const bool& franka::Errors::cartesian_motion_generator_elbow_sign_inconsistent

True if commanded elbow values in Cartesian motion generators are inconsistent.

Definition at line 162 of file errors.h.

const bool& franka::Errors::cartesian_motion_generator_joint_acceleration_discontinuity

True if the joint acceleration in Cartesian motion generators is discontinuous after IK calculation.

Definition at line 184 of file errors.h.

const bool& franka::Errors::cartesian_motion_generator_joint_position_limits_violation

True if the joint position limits would be exceeded after IK calculation.

Definition at line 170 of file errors.h.

const bool& franka::Errors::cartesian_motion_generator_joint_velocity_discontinuity

True if the joint velocity in Cartesian motion generators is discontinuous after IK calculation.

Definition at line 179 of file errors.h.

const bool& franka::Errors::cartesian_motion_generator_joint_velocity_limits_violation

True if the joint velocity limits would be exceeded after IK calculation.

Definition at line 174 of file errors.h.

const bool& franka::Errors::cartesian_motion_generator_start_elbow_invalid

True if the first elbow value in Cartesian motion generators is too far from initial one.

Definition at line 166 of file errors.h.

const bool& franka::Errors::cartesian_motion_generator_velocity_discontinuity

True if commanded velocity in Cartesian motion generators is discontinuous (target values are too far apart).

Definition at line 153 of file errors.h.

const bool& franka::Errors::cartesian_motion_generator_velocity_limits_violation

True if an external Cartesian motion generator would move with too high velocity.

Definition at line 148 of file errors.h.

const bool& franka::Errors::cartesian_position_limits_violation

True if the robot moved past any of the virtual walls.

Definition at line 74 of file errors.h.

const bool& franka::Errors::cartesian_position_motion_generator_invalid_frame

True if the Cartesian pose is not a valid transformation matrix.

Definition at line 188 of file errors.h.

const bool& franka::Errors::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.

Definition at line 140 of file errors.h.

const bool& franka::Errors::cartesian_reflex

True if a collision was detected, i.e. the robot exceeded a torque threshold in a Cartesian motion.

Definition at line 100 of file errors.h.

const bool& franka::Errors::cartesian_velocity_profile_safety_violation

True if Cartesian velocity profile for internal motions was exceeded.

Definition at line 112 of file errors.h.

const bool& franka::Errors::cartesian_velocity_violation

True if the robot exceeded Cartesian velocity limits.

Definition at line 86 of file errors.h.

const bool& franka::Errors::communication_constraints_violation

True if minimum network communication quality could not be held during a motion.

Definition at line 206 of file errors.h.

const bool& franka::Errors::controller_torque_discontinuity

True if the torque set by the external controller is discontinuous.

Definition at line 196 of file errors.h.

std::array<bool, 37> franka::Errors::errors_ {}
private

Definition at line 20 of file errors.h.

const bool& franka::Errors::force_control_safety_violation

True if the robot exceeded safety threshold during force control.

Definition at line 90 of file errors.h.

const bool& franka::Errors::force_controller_desired_force_tolerance_violation

True if desired force exceeds the safety thresholds.

Definition at line 192 of file errors.h.

const bool& franka::Errors::instability_detected

True if an instability is detected.

Definition at line 224 of file errors.h.

const bool& franka::Errors::joint_motion_generator_acceleration_discontinuity

True if commanded acceleration in joint motion generators is discontinuous (target values are too far apart).

Definition at line 135 of file errors.h.

const bool& franka::Errors::joint_motion_generator_position_limits_violation

True if an external joint motion generator would move into a joint limit.

Definition at line 121 of file errors.h.

const bool& franka::Errors::joint_motion_generator_velocity_discontinuity

True if commanded velocity in joint motion generators is discontinuous (target values are too far apart).

Definition at line 130 of file errors.h.

const bool& franka::Errors::joint_motion_generator_velocity_limits_violation

True if an external joint motion generator exceeded velocity limits.

Definition at line 125 of file errors.h.

const bool& franka::Errors::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.

Definition at line 229 of file errors.h.

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.

Definition at line 216 of file errors.h.

const bool& franka::Errors::joint_position_limits_violation

True if the robot moved past the joint limits.

Definition at line 70 of file errors.h.

const bool& franka::Errors::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.

Definition at line 117 of file errors.h.

const bool& franka::Errors::joint_reflex

True if a collision was detected, i.e. the robot exceeded a torque threshold in a joint motion.

Definition at line 95 of file errors.h.

const bool& franka::Errors::joint_velocity_violation

True if the robot exceeded joint velocity limits.

Definition at line 82 of file errors.h.

const bool& franka::Errors::max_goal_pose_deviation_violation

True if internal motion generator did not reach the goal pose.

Definition at line 104 of file errors.h.

const bool& franka::Errors::max_path_pose_deviation_violation

True if internal motion generator deviated from the path.

Definition at line 108 of file errors.h.

const bool& franka::Errors::power_limit_violation

True if commanded values would result in exceeding the power limit.

Definition at line 210 of file errors.h.

const bool& franka::Errors::self_collision_avoidance_violation

True if the robot would have collided with itself.

Definition at line 78 of file errors.h.

const bool& franka::Errors::start_elbow_sign_inconsistent

True if the start elbow sign was inconsistent.

Applies only to motions started from Desk.

Definition at line 202 of file errors.h.

const bool& franka::Errors::tau_j_range_violation

True if the measured torque signal is out of the safe range.

Definition at line 220 of file errors.h.


The documentation for this struct was generated from the following file:


libfranka
Author(s): Franka Emika GmbH
autogenerated on Tue Jul 9 2019 03:32:01