.. _program_listing_file_include_franka_robot.h: Program Listing for File robot.h ================================ |exhale_lsh| :ref:`Return to documentation for file ` (``include/franka/robot.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 #include #include #include #include #include #include #include #include #include namespace franka { class Model; class ActiveControlBase; class Robot { public: using ServerVersion = uint16_t; explicit Robot(const std::string& franka_address, RealtimeConfig realtime_config = RealtimeConfig::kEnforce, size_t log_size = 50); Robot(Robot&& other) noexcept; Robot& operator=(Robot&& other) noexcept; virtual ~Robot() noexcept; void control(std::function control_callback, bool limit_rate = false, double cutoff_frequency = kDefaultCutoffFrequency); void control( std::function control_callback, std::function motion_generator_callback, bool limit_rate = false, double cutoff_frequency = kDefaultCutoffFrequency); void control( std::function control_callback, std::function motion_generator_callback, bool limit_rate = false, double cutoff_frequency = kDefaultCutoffFrequency); void control( std::function control_callback, std::function motion_generator_callback, bool limit_rate = false, double cutoff_frequency = kDefaultCutoffFrequency); void control(std::function control_callback, std::function motion_generator_callback, bool limit_rate = false, double cutoff_frequency = kDefaultCutoffFrequency); void control( std::function motion_generator_callback, ControllerMode controller_mode = ControllerMode::kJointImpedance, bool limit_rate = false, double cutoff_frequency = kDefaultCutoffFrequency); void control( std::function motion_generator_callback, ControllerMode controller_mode = ControllerMode::kJointImpedance, bool limit_rate = false, double cutoff_frequency = kDefaultCutoffFrequency); void control( std::function motion_generator_callback, ControllerMode controller_mode = ControllerMode::kJointImpedance, bool limit_rate = false, double cutoff_frequency = kDefaultCutoffFrequency); void control(std::function motion_generator_callback, ControllerMode controller_mode = ControllerMode::kJointImpedance, bool limit_rate = false, double cutoff_frequency = kDefaultCutoffFrequency); void read(std::function read_callback); virtual RobotState readOnce(); auto getRobotModel() -> std::string; void setCollisionBehavior(const std::array& lower_torque_thresholds_acceleration, const std::array& upper_torque_thresholds_acceleration, const std::array& lower_torque_thresholds_nominal, const std::array& upper_torque_thresholds_nominal, const std::array& lower_force_thresholds_acceleration, const std::array& upper_force_thresholds_acceleration, const std::array& lower_force_thresholds_nominal, const std::array& upper_force_thresholds_nominal); void setCollisionBehavior(const std::array& lower_torque_thresholds, const std::array& upper_torque_thresholds, const std::array& lower_force_thresholds, const std::array& upper_force_thresholds); void setJointImpedance( const std::array& K_theta); // NOLINT(readability-identifier-naming) void setCartesianImpedance( const std::array& K_x); // NOLINT(readability-identifier-naming) void setGuidingMode(const std::array& guiding_mode, bool elbow); void setK(const std::array& EE_T_K); // NOLINT(readability-identifier-naming) void setEE(const std::array& NE_T_EE); // NOLINT(readability-identifier-naming) void setLoad(double load_mass, const std::array& F_x_Cload, // NOLINT(readability-identifier-naming) const std::array& load_inertia); void automaticErrorRecovery(); virtual std::unique_ptr startTorqueControl(); virtual std::unique_ptr startJointPositionControl( const research_interface::robot::Move::ControllerMode& control_type); virtual std::unique_ptr startJointVelocityControl( const research_interface::robot::Move::ControllerMode& control_type); virtual std::unique_ptr startCartesianPoseControl( const research_interface::robot::Move::ControllerMode& control_type); virtual std::unique_ptr startCartesianVelocityControl( const research_interface::robot::Move::ControllerMode& control_type); void stop(); Model loadModel(); // Loads the model library for the unittests mockRobotModel Model loadModel(std::unique_ptr robot_model); ServerVersion serverVersion() const noexcept; Robot(const Robot&) = delete; Robot& operator=(const Robot&) = delete; class Impl; protected: Robot(std::shared_ptr robot_impl); Robot() = default; private: template std::unique_ptr startControl( const research_interface::robot::Move::ControllerMode& controller_type); std::shared_ptr impl_; std::mutex control_mutex_; }; } // namespace franka