Program Listing for File errors.h

Return to documentation for file (include/franka/errors.h)

// Copyright (c) 2023 Franka Robotics GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
#pragma once

#include <array>
#include <ostream>

namespace franka {

struct Errors {
 private:
  std::array<bool, 41> errors_{};

 public:
  Errors();

  Errors(const Errors& other);

  Errors& operator=(Errors other);

  Errors(const std::array<bool, 41>& errors);

  explicit operator bool() const noexcept;

  explicit operator std::string() const;

  const bool&
      joint_position_limits_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_position_limits_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      self_collision_avoidance_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      joint_velocity_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_velocity_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      force_control_safety_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool& joint_reflex;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool& cartesian_reflex;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      max_goal_pose_deviation_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      max_path_pose_deviation_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_velocity_profile_safety_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      joint_position_motion_generator_start_pose_invalid;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      joint_motion_generator_position_limits_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      joint_motion_generator_velocity_limits_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      joint_motion_generator_velocity_discontinuity;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      joint_motion_generator_acceleration_discontinuity;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_position_motion_generator_start_pose_invalid;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_elbow_limit_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_velocity_limits_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_velocity_discontinuity;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_acceleration_discontinuity;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_elbow_sign_inconsistent;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_start_elbow_invalid;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_joint_position_limits_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_joint_velocity_limits_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_joint_velocity_discontinuity;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_motion_generator_joint_acceleration_discontinuity;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_position_motion_generator_invalid_frame;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      force_controller_desired_force_tolerance_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      controller_torque_discontinuity;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      start_elbow_sign_inconsistent;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      communication_constraints_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool& power_limit_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      joint_p2p_insufficient_torque_for_planning;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool& tau_j_range_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool& instability_detected;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      joint_move_in_wrong_direction;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      cartesian_spline_motion_generator_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      joint_via_motion_generator_planning_joint_limit_violation;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      base_acceleration_initialization_timeout;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
  const bool&
      base_acceleration_invalid_reading;  // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
};

std::ostream& operator<<(std::ostream& ostream, const Errors& errors);

}  // namespace franka