.. _program_listing_file_include_franka_errors.h: Program Listing for File errors.h ================================= |exhale_lsh| :ref:`Return to documentation for file ` (``include/franka/errors.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright (c) 2023 Franka Robotics GmbH // Use of this source code is governed by the Apache-2.0 license, see LICENSE #pragma once #include #include namespace franka { struct Errors { private: std::array errors_{}; public: Errors(); Errors(const Errors& other); Errors& operator=(Errors other); Errors(const std::array& errors); explicit operator bool() const noexcept; explicit operator std::string() const; const bool& joint_position_limits_violation; const bool& cartesian_position_limits_violation; const bool& self_collision_avoidance_violation; const bool& joint_velocity_violation; const bool& cartesian_velocity_violation; const bool& force_control_safety_violation; const bool& joint_reflex; const bool& cartesian_reflex; const bool& max_goal_pose_deviation_violation; const bool& max_path_pose_deviation_violation; const bool& cartesian_velocity_profile_safety_violation; const bool& joint_position_motion_generator_start_pose_invalid; const bool& joint_motion_generator_position_limits_violation; const bool& joint_motion_generator_velocity_limits_violation; const bool& joint_motion_generator_velocity_discontinuity; const bool& joint_motion_generator_acceleration_discontinuity; const bool& cartesian_position_motion_generator_start_pose_invalid; const bool& cartesian_motion_generator_elbow_limit_violation; const bool& cartesian_motion_generator_velocity_limits_violation; const bool& cartesian_motion_generator_velocity_discontinuity; const bool& cartesian_motion_generator_acceleration_discontinuity; const bool& cartesian_motion_generator_elbow_sign_inconsistent; const bool& cartesian_motion_generator_start_elbow_invalid; const bool& cartesian_motion_generator_joint_position_limits_violation; const bool& cartesian_motion_generator_joint_velocity_limits_violation; const bool& cartesian_motion_generator_joint_velocity_discontinuity; const bool& cartesian_motion_generator_joint_acceleration_discontinuity; const bool& cartesian_position_motion_generator_invalid_frame; const bool& force_controller_desired_force_tolerance_violation; const bool& controller_torque_discontinuity; const bool& start_elbow_sign_inconsistent; const bool& communication_constraints_violation; const bool& power_limit_violation; const bool& joint_p2p_insufficient_torque_for_planning; const bool& tau_j_range_violation; const bool& instability_detected; const bool& joint_move_in_wrong_direction; const bool& cartesian_spline_motion_generator_violation; const bool& joint_via_motion_generator_planning_joint_limit_violation; const bool& base_acceleration_initialization_timeout; const bool& base_acceleration_invalid_reading; }; std::ostream& operator<<(std::ostream& ostream, const Errors& errors); } // namespace franka