1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
/**
 * @file ethercatcpp/sensojoint.h
 * @author Robin Passama
 * @brief EtherCAT driver for ensodrive sensojoint actuator.
 * @date November 2024
 * @ingroup ethercatcpp-sensodrive
 */

#pragma once
#include <ethercatcpp/core.h>

#include <cmath>
#include <string>
#include <optional>
#include <memory>

/*! @namespace ethercatcpp
 *
 * Root namespace for common and general purpose ethercatcpp packages
 */
namespace ethercatcpp {
/**
 * @brief This class describe the EtherCAT driver for Sensodrive sensojoint
 * actuator. It allows to communicate with a "Sensodrive Sensojoint actuator"
 * through an ethercat bus managed by an ethercatcpp master.
 *
 */

class SensoJoint : public coe::cia402::CIA402Device {
public:
    struct EndStop {
        double stiffness{0.}; // Nm/rad<--- struct member 'EndStop::stiffness' is never used.
        double damping{0.};   // Nm x s /rad<--- struct member 'EndStop::damping' is never used.
        double position{0.};  // rad<--- struct member 'EndStop::position' is never used.
        double offset{0.};    // rad<--- struct member 'EndStop::offset' is never used.
    };
    struct Options {
        double control_period_{0.};                              // is s<--- struct member 'Options::control_period_' is never used.
        double initial_adjusted_position{0.};                    // in rad<--- struct member 'Options::initial_adjusted_position' is never used.
        double min_target_position{0.}, max_target_position{0.}; // in rad<--- struct member 'Options::min_target_position' is never used.<--- struct member 'Options::max_target_position' is never used.
        double zero_pos_offset{0.};                              // in rad<--- struct member 'Options::zero_pos_offset' is never used.
        double zero_torque_offset{0.};                           // in Nm<--- struct member 'Options::zero_torque_offset' is never used.
        double max_motor_torque{0.};                             // in Nm<--- struct member 'Options::max_motor_torque' is never used.
        double max_motor_velocity{0.};                           // in rad / s<--- struct member 'Options::max_motor_velocity' is never used.
        double output_inertia{0.};                               // in kg.m^2<--- struct member 'Options::output_inertia' is never used.
        double profile_velocity{0.};                             // in rad / s<--- struct member 'Options::profile_velocity' is never used.
        double profile_acceleration{0.};                         // in rad / s^2<--- struct member 'Options::profile_acceleration' is never used.
        double profile_deceleration{0.};                         // in rad / s^2<--- struct member 'Options::profile_deceleration' is never used.
        double position_window{0.};         // in positive rad<--- struct member 'Options::position_window' is never used.
        double position_window_time{0.};    // in s<--- struct member 'Options::position_window_time' is never used.
        double velocity_threshold{0.};      // in rad / s<--- struct member 'Options::velocity_threshold' is never used.
        double velocity_threshold_time{0.}; // in  s<--- struct member 'Options::velocity_threshold_time' is never used.
        double velocity_window{0.};         // in rad / s<--- struct member 'Options::velocity_window' is never used.
        double velocity_window_time{0.};    // in  s<--- struct member 'Options::velocity_window_time' is never used.
        double torque_slope{0.};            // in Nm / s<--- struct member 'Options::torque_slope' is never used.
        EndStop endstop_specs;<--- struct member 'Options::endstop_specs' is never used.
        bool enable_haptics{false};<--- struct member 'Options::enable_haptics' is never used.

        uint8_t controlled_digital_outputs{0};<--- struct member 'Options::controlled_digital_outputs' is never used.
        uint8_t digital_outputs_init_value{0};<--- struct member 'Options::digital_outputs_init_value' is never used.
        uint8_t digital_outputs_end_value{0};<--- struct member 'Options::digital_outputs_end_value' is never used.
        uint8_t read_digital_inputs{0};<--- struct member 'Options::read_digital_inputs' is never used.

        Options& offsets(double pos_offset, double torque_offset);
        Options& use_haptics();
        Options& inertia(double output);
        Options& endstops(double stiffness, double damping);
        Options& max(double motor_torque, double motor_vel);
        Options& profile(double velocity, double accel = 0., double decel = 0.);
        Options& torque_profile(double slope);
        Options& position_reached(double window, double time);
        Options& velocity_reached(double window, double time);
        Options& standstill(double threshold = 0.001, double time = 0.001);
        Options& controlled_outputs(uint8_t outputs, uint8_t init_value = 0,
                                    uint8_t end_value = 0);
        Options& read_inputs(uint8_t inputs);
    };
    static SensoJoint::Options gen_options(double control_period,
                                           double min_target_pos,
                                           double max_target_pos);

    //! This enum define the possible "control modes" of the actuator
    enum class control_mode_t {
        monitor,
        profile_position,
        profile_velocity,
        profile_torque,
        cyclic_position,
        cyclic_velocity,
        cyclic_torque,
        profile_output_position_vibration_damping,
        profile_output_velocity,
        cyclic_output_position_vibration_damping,
        cyclic_output_velocity,
        cyclic_output_torque
    };

    virtual bool profile_mode() const override;
    virtual bool cyclic_mode() const override;
    virtual bool position_mode() const override;
    virtual bool velocity_mode() const override;
    virtual bool torque_mode() const override;
    virtual bool profile_mode_queried() const override;
    virtual bool cyclic_mode_queried() const override;
    virtual bool position_mode_queried() const override;
    virtual bool velocity_mode_queried() const override;
    virtual bool torque_mode_queried() const override;

    static bool is_advanced_mode(control_mode_t);
    static bool is_profile_mode(control_mode_t);
    static bool is_cyclic_mode(control_mode_t);
    static bool is_position_mode(control_mode_t);
    static bool is_velocity_mode(control_mode_t);
    static bool is_torque_mode(control_mode_t);

    using operation_state_t = CIA402Device::state_t;

    enum Model { MODEL_7016, MODEL_5016, MODEL_4010, MODEL_3010 };
    /**
     * @brief Constructor of SensoJoint class
     */
    SensoJoint(const Model& model);
    SensoJoint(const Model& model, const Options& options);
    SensoJoint(const SensoJoint&) = delete;
    SensoJoint(SensoJoint&&) = delete;
    SensoJoint& operator=(const SensoJoint&) = delete;
    SensoJoint& operator=(SensoJoint&&) = delete;
    virtual ~SensoJoint();

    /**
     * @brief Function used to set the target position when device
     * is command in position mode.
     *
     * <B>unit: radian (rad)</B>.
     * @param [in] target_position is the position desired
     */
    void set_target_position(double target_position);

    /**
     * @brief Function used to set the target velocity when device
     * is command in velocity mode.
     *
     * <B>unit: radian per second (rad/s) </B>.
     * @param [in] target_velocity is the velocity desired
     */
    void set_target_velocity(double target_velocity);

    //////////////// torque controller ///////////////
    /**
     * @brief Function used to set the target torque on output shaft when device
     * is command in output or basic torque modes.
     *
     * <B>unit: Newton meter (Nm)</B>.
     * @param [in] target_torque is the torque desired
     */
    void set_target_output_torque(double target_torque);

    /**
     * @brief Function used to set the target motor torque when device
     * is command in basic torque mode.
     *
     * <B>unit: Newton meter (Nm)</B>.
     * @param [in] target_torque is the torque desired
     */
    void set_target_motor_torque(double target_torque);

    /**
     * @brief Function used to set the motor torque offset.
     *
     * Set the torque feedforward offset for the torque value. In <B>Cyclic
     * Synchronous Position Mode</B> and Cyclic Synchronous Velocity Mode, the
     * object contains the input value for torque feed forward. In <B>Cyclic
     * Synchronous Torque Mode</B>, it contains the commanded additive torque of
     * the drive, which is added to the Target Torque value. <B>unit: Newton
     * meter (Nm) </B>.
     * @param [in] torque_offset is the torque offset desired
     */
    void set_motor_torque_feedforward(double torque_offset);

    /**
     * @brief Function used to set the output torque offset.
     *
     * Same as set_motor_torque_feedforward but the input is expressed in
     * desired output torque and converted to desired motor torque
     *
     * @param [in] torque_offset is the desired output torque offset
     * @see set_motor_torque_feedforward
     */
    void set_output_torque_feedforward(double torque_offset);

    /**
     * @brief Set value of external load torque offset (gravity)
     *
     * @param offset additional torque due to gravity (to be compensated)
     */
    void set_external_load_torque_offset(double offset);

    /**
     * @brief Function used to set the velocity offset.
     *
     * Provides the feedforward offset of the velocity value. In <B>Cyclic
     * Synchronous Position Mode</B>, this object contains the input value for
     * velocity feed forward. In <B>Cyclic Synchronous Velocity Mode</B>, it
     * contains the commanded offset of the drive device. <B>unit: radian
     * (rad per second)</B>.
     * @param [in] velocity_offset is the velocity offset desired
     */
    void set_velocity_feedforward(double velocity_offset);

    /**
     * @brief Select the desired control mode.
     * @param [in] control_mode is the desired control mode
     * @return true if mode has changed, false otherwise
     */
    [[nodiscard]] bool set_control_mode(control_mode_t control_mode);

    /**
     * @brief Get current control mode used inside device
     * @return the current control mode
     */
    control_mode_t control_mode() const;

    /**
     * @brief Get current control mode used inside device as a string
     * @return explicit actual control mode like in "control_mode_t"
     */
    std::string_view control_mode_str() const;

    /**
     * @brief convert the operation state into a human readable information
     *
     * @return std::string
     */
    static std::string_view control_mode_to_str(control_mode_t);

    /**
     * @brief Get actual motor position in radians
     * @return position value
     */
    double position() const;

    /**
     * @brief Get actual motor velocity in radians per second
     * @return velocity value
     */
    double velocity() const;

    /**
     * @brief Get actual motor torque in newton meter
     * @return torque value
     */
    double motor_torque() const;

    /**
     * @brief Get actual motor current in A
     * @return motor current value
     */
    double motor_current() const;

    /**
     * @brief Get actual output torque in newton meter
     * (<B>Nm</B>).
     * @return torque value
     */
    double output_torque() const;

    /**
     * @brief Get actual friction torque in newton meter
     * (<B>Nm</B>).
     * @return torque value
     */
    double friction_torque() const;

    /**
     * @brief Get actual motor temperature in degrees celsius (<B>°C</B>).
     * @return  motor current temperature
     */
    double motor_temperature() const;

    /**
     * @brief Get actual drive temperature in degrees celsius (<B>°C</B>).
     * @return  drive current temperature
     */
    double drive_temperature() const;

    /**
     * @brief Get actual torque sensor temperature in degrees celsius
     * (<B>°C</B>).
     * @return torque sensor current temperature
     */
    double sensor_temperature() const;

    // Profile Position Mode (PPM) specific config

    /**
     * @brief In profile modes tell whether there is a following error.
     * @return true if there is a following error false otherwise
     */
    bool following_error() const;

    /**
     * @brief In profile velocity modes tell whether the motor is standstill.
     * @return true if standstill false otherwise
     */
    bool standstill() const;

    /**
     * @brief Check whether STO(Safe torque off) security has been triggerred.
     *
     * @return TRUE when STO triggerred, FALSE otherwise
     */
    bool sto_active() const;

    /**
     * @brief Check whether SBC(Safe braque control) security has been
     * triggerred.
     *
     * @return TRUE when SBC triggerred, FALSE otherwise
     */
    bool sbc_active() const;

    /**
     * @brief Tell whether Sensojoint brake is applied
     *
     * @return true if brake applied (joint cannot move), false otherwise
     */
    bool brake_applied() const;

    /**
     * @brief Get options used in the Sensojoint.
     *
     * @return reference on the option object
     */
    const Options& options() const;

    /**
     * @brief Get last fault description.
     *
     * @return the string explaining the fault
     * @see fault_type()
     */
    const std::string& fault() const;

    /**
     * @brief Get last error code.
     *
     * @see fault()
     */
    uint16_t error_code() const;

    /**
     * @brief check if a warning is currently emitted.
     *
     * @see fault()
     */
    bool warning() const;

    /**
     * @brief Set value of spring haptics effect parameters in advanced torque
     * controller
     *
     * @param neutral_position of spring
     * @param stiffness of spring
     * @param damping of spring
     */
    void set_spring(double neutral_position, double stiffness, double damping);

    /**
     * @brief Flag to ease setting the controlled/read GPIOS
     * @details only 4 usable GPIOs in the sensojoint (=> only 4 first bits used
     * in flags)
     */
    enum IOFlag {
        gpio_3_io_fpp_pin = 1 << 0, // Fast push-pull
        gpio_4_out_pin = 1 << 1,    // Slow push-pull
        gpio_5_io_sbo_pin = 1 << 2, // Slow bi directionnal
        gpio_6_io_sbo_pin = 1 << 3, // Slow bi directionnal
    };

    /**
     * @brief Set value of digital outputs
     * @details only 4 first bits (0000 1111) are used, corresponding to GPIOs
     * 3,4,5,6 (from rightmost to leftmost bit => 1111 == 6 5 4 3)
     * @details you can use IOFlags to set the output values
     * @param outputs bitset value of digital outputs (1 for High, 0 for Low)
     */
    void set_digital_outputs(uint8_t outputs);

    /**
     * @brief Get value of digital inputs
     * @details only bits "0000 1101" are meaningfull, corresponding to
     * GPIOs 3,5,6 (from rightmost to leftmost bit => 1101 == 6 5 _ 3)
     * @details you can use IOFlags to check status of corresponding inputs
     * @return  digital inputs bitset value (1 for High, 0 for Low)
     */
    uint8_t digital_inputs() const;

    /**
     * @brief Get the theoric initial position from drive configuration
     *
     * @return the initial position
     */
    double initial_position() const;

protected:
    static bool advanced_mode(int8_t);
    static bool profile_mode(int8_t);
    static bool cyclic_mode(int8_t);
    static bool position_mode(int8_t);
    static bool velocity_mode(int8_t);
    static bool torque_mode(int8_t);

private:
    void initialize(const std::optional<Options>& options);
    void pdo_maps_configuration();

    void unpack_status_buffer();
    void update_internal_state();

    // Used to change device state in async mode (only on init)
    void read_base_units_values();
    void find_initial_position();
    void manage_ctrl_params(const std::optional<Options>& options);

    //----------------------------------------------------------------------------//
    //                           INTERNAL STATE //
    //----------------------------------------------------------------------------//
    Options options_;<--- class member 'SensoJoint::options_' is never used.
    Model model_;<--- class member 'SensoJoint::model_' is never used.
    // Status/Command datas
    struct OpaqueStateCommands;
    std::unique_ptr<OpaqueStateCommands> sta_cmd_;
    void bind_buffers();
    static const std::map<int8_t, std::string_view> control_mode_decode_;<--- class member 'SensoJoint::control_mode_decode_' is never used.
    struct InternalParameters;
    std::unique_ptr<InternalParameters> internal_parameters_;
    struct ConversionRatios;
    std::unique_ptr<ConversionRatios> conversion_;

    void manage_control_period(const std::optional<Options>& options);
    void manage_torque_slope(const std::optional<Options>& options);
    void manage_torque_offset(const std::optional<Options>& options);
    void manage_position_offset(const std::optional<Options>& options);
    void manage_max_output_torque();
    void manage_max_output_velocity();
    void manage_max_motor_torque();
    void manage_max_motor_current();
    void manage_max_motor_velocity();
    void manage_user_max_motor_torque(const std::optional<Options>& options);
    void manage_user_max_motor_velocity(const std::optional<Options>& options);
    void manage_user_position_limits(const std::optional<Options>& options);
    void manage_quickstop_config(const std::optional<Options>& options);
    void manage_profile_config(const std::optional<Options>& options);
    void manage_endstop_config(const std::optional<Options>& options);
    void manage_digital_ios(const std::optional<Options>& options);
    void manage_digital_ios_end();

    void manage_torque_based_quick_stop();
    void force_target_output_torque(double target_torque);
    void force_target_motor_torque(double target_torque);

    static int8_t control_mode_to_code(control_mode_t);
    static control_mode_t control_code_to_mode(int8_t);

    static bool can_swap_mode(control_mode_t current, control_mode_t next);
};

} // namespace ethercatcpp