robotiq_rs/
lib.rs

1//! # Robotiq-rs
2//! 
3//! [![Static Badge](https://img.shields.io/badge/crate-robotiq--rs-red)](https://crates.io/crates/robotiq-rs)
4//! [![docs.rs](https://img.shields.io/docsrs/inovo-rs)](https://docs.rs/robotiq-rs/latest/robotiq_rs/)
5//! [![Static Badge](https://img.shields.io/badge/github-repo-blue)](https://github.com/dizzyi/robotiq-rs)
6//! 
7//! `robotiq-rs` is a library for interfacing with robotiq gripper
8//! ### Compatiable product
9//! - [x] Robotiq 2F-85
10//! - [x] Robotiq 2F-140 ~(i guess🤷🏻‍♂️)~
11//! - [x] HandE
12//! - [ ] 3-Finger Gripper
13//! - [ ] Vaccum Gripper
14//! 
15//! ## Example 
16//! ```no_run
17//! use robotiq_rs::*;
18//! 
19//! #[tokio::main]
20//! async fn main() -> Result<(), RobotiqError> {
21//!     // The serial port path
22//!     let path = "COM17";
23//! 
24//!     // create a connection to serial RS485 modbus
25//!     let mut gripper = RobotiqGripper::from_path(path)?;
26//! 
27//!     // Reset and Activation of Gripper
28//!     //
29//!     // reset gripper, recommended
30//!     gripper.reset().await?;
31//!     // activate the gripper, it will try to open and close.
32//!     gripper.activate().await?.await_activate().await?;
33//!     println!("finished activation.");
34//!     std::thread::sleep(std::time::Duration::from_millis(1000));
35//! 
36//!     // Basic Gripper Command
37//!     //
38//!     // set gripper with position, speed and force
39//!     gripper.go_to(0x08, 0x00, 0x00).await?;
40//!     // the result of the setting command, return whether or not it have clamp an object
41//!     let obj_detect_status = gripper.await_go_to().await?;
42//!     println!("Object Detect Status : {:?}", obj_detect_status);
43//!     std::thread::sleep(std::time::Duration::from_millis(1000));
44//! 
45//!     // Chained command
46//!     //
47//!     // chained command with builder pattern
48//!     let obj_detect_status = gripper.go_to(0xFF, 0xFF, 0xFF).await?.await_go_to().await?;
49//!     println!("Object Detect Status : {:?}", obj_detect_status);
50//!     std::thread::sleep(std::time::Duration::from_millis(1000));
51//! 
52//!     // Automatic Release Routine
53//!     //
54//!     // set the gripper into motion
55//!     gripper.go_to(0x08, 0x00, 0x00).await?;
56//!     std::thread::sleep(std::time::Duration::from_millis(100));
57//!     gripper.automatic_release(false).await?;
58//!     // you will need to reset and reactivate the gripper after automatic release routine
59//!     gripper
60//!         .reset()
61//!         .await?
62//!         .activate()
63//!         .await?
64//!         .await_activate()
65//!         .await?;
66//!     std::thread::sleep(std::time::Duration::from_millis(1000));
67//!     gripper.go_to(0x08, 0x00, 0x00).await?;
68//!     std::thread::sleep(std::time::Duration::from_millis(1000));
69//! 
70//!     // Gripper Command
71//!     //
72//!     // Construct GripperCommand to command gripper
73//!     //
74//!     // a null command, all zero, will deactivate and reset the gripper
75//!     let cmd_null = GripperCommand::new();
76//!     // command to activate the gripper
77//!     let cmd_act = GripperCommand::new().act(true);
78//!     // commands to set the gripper with position requested, speed, and force
79//!     let cmd_goto_1 = GripperCommand::new()
80//!         .act(true)
81//!         .gto(true)
82//!         .pos_req(0x08)
83//!         .speed(0x00)
84//!         .force(0x00);
85//!     let cmd_goto_2 = GripperCommand::new()
86//!         .act(true)
87//!         .gto(true)
88//!         .pos_req(0xFF)
89//!         .speed(0xFF)
90//!         .force(0xFF);
91//!     // command to perform automatic release routine
92//!     let cmd_atr = GripperCommand::new().act(true).atr(true).ard(true);
93//! 
94//!     //
95//!     //
96//!     gripper.write_async(cmd_null).await?;
97//!     gripper.write_async(cmd_act).await?;
98//!     while gripper.read_async().await?.sta != ActivationStatus::Completed {
99//!         std::thread::sleep(std::time::Duration::from_millis(100));
100//!     }
101//!     std::thread::sleep(std::time::Duration::from_millis(1000));
102//! 
103//!     //
104//!     //
105//!     gripper.write_async(cmd_goto_1).await?;
106//!     while gripper.read_async().await?.obj == ObjDetectStatus::InMotion {
107//!         std::thread::sleep(std::time::Duration::from_millis(100));
108//!     }
109//!     std::thread::sleep(std::time::Duration::from_millis(1000));
110//! 
111//!     //
112//!     //
113//!     gripper.write_async(cmd_goto_2).await?;
114//!     std::thread::sleep(std::time::Duration::from_millis(100));
115//!     gripper.write_async(cmd_atr).await?;
116//!     while gripper.read_async().await?.fault != GripperFault::AutomaticReleaseCompleted {
117//!         std::thread::sleep(std::time::Duration::from_millis(100));
118//!     }
119//!     std::thread::sleep(std::time::Duration::from_millis(1000));
120//! 
121//!     gripper
122//!         .reset()
123//!         .await?
124//!         .activate()
125//!         .await?
126//!         .await_activate()
127//!         .await?
128//!         .go_to(0x00, 0xFF, 0xFF)
129//!         .await?
130//!         .await_go_to()
131//!         .await?;
132//! 
133//!     Ok(())
134//! }
135//! ```
136
137
138use num::FromPrimitive;
139use num_derive::FromPrimitive;
140use serde::{Deserialize, Serialize};
141use tokio_modbus::prelude::*;
142use tokio_serial::SerialPortBuilderExt;
143
144/// Flag for `rACT` and `gACT`
145static FLAG_ACT: u8 = 1 << 0;
146/// Flag for `rGTO` and `gGTO`
147static FLAG_GTO: u8 = 1 << 3;
148/// Flag for `rATR`
149static FLAG_ATR: u8 = 1 << 4;
150/// Flag for `rARD`
151static FLAG_ADR: u8 = 1 << 5;
152
153/// The gripper's activation status
154#[repr(u8)]
155#[derive(Debug, Clone, FromPrimitive, PartialEq, Serialize, Deserialize)]
156pub enum ActivationStatus {
157    /// Gripper is in reset (or automatic release). See Fault Status if gripper is activated
158    InReset,
159    // Activation in Progress
160    InProgess,
161    /// Not used
162    NotUsed,
163    /// Activation is Completed
164    Completed,
165}
166
167/// Object Detection status, is a built-in feature that provides information
168/// on possible object pick-up. Ignore if `gGTO == 0`.
169#[repr(u8)]
170#[derive(Debug, Clone, FromPrimitive, PartialEq, Serialize, Deserialize)]
171pub enum ObjDetectStatus {
172    /// Fingers are in motion towards requested position. No object detected
173    InMotion,
174    /// Fingers have stopped due to a contact while opening before requested position
175    /// Object detected opening.
176    DetectedOpen,
177    /// Fingers have stopped due to a contact while closing before requested position
178    /// Object detected closing.
179    DetectedClose,
180    /// Fingers are at requested position. No object detected or object has been loss/dropped.
181    NoObject,
182}
183
184impl ObjDetectStatus {
185    pub fn detected_obj(&self) -> bool {
186        match self {
187            ObjDetectStatus::DetectedClose | ObjDetectStatus::DetectedOpen => true,
188            _ => false,
189        }
190    }
191}
192
193/// Fault status return general error messages that are useful for troubleshooting.
194/// Fault LED (red) is present on the gripper chassis,
195/// LED can be blue, red or both and be solid or blinking.
196#[repr(u8)]
197#[derive(Debug, Clone, FromPrimitive, PartialEq, Error, Serialize, Deserialize)]
198pub enum GripperFault {
199    /// No fault (solid blue LED)
200    NoFault = 0x00,
201
202    /// Action delayed. the activation (re-activation) must be completed piror to performing the action
203    ActionDelay = 0x05,
204    /// THe activation bit must be set prior to performing the action
205    NotActivated = 0x07,
206
207    /// Maximum operating temperature exceeded (>= 85 degree celsius internally), let cool down (below 80 degree celsius)
208    OverHeated = 0x08,
209    /// No communication during at least 1 second.
210    NoComm = 0x09,
211
212    /// Under minimum operating voltage
213    UnderVoltage = 0x0A,
214    /// Automatic release in progress
215    Releasing = 0x0B,
216    /// Internal fault; contact support@robotiq.com
217    InternalFault = 0x0C,
218    /// Activation fault, verify that no interference or other error occured.
219    AcitivationFault = 0x0D,
220    /// Overcurrent Triggered.
221    OverCurrent = 0x0E,
222    /// Automatic release compeleted
223    AutomaticReleaseCompleted = 0x0F,
224}
225
226impl GripperFault {
227    /// For Major faults (LED blinking red/blue) - Reset is required (rising edge on activation bit (`rACT`) needed).
228    pub fn reset_required(&self) -> bool {
229        self.clone() as u8 >= 0x0A
230    }
231}
232
233impl std::fmt::Display for GripperFault {
234    fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
235        write!(f, "{:?}", self)
236    }
237}
238
239/// Robot Input / Status of the gripper
240///
241/// Read from register starting at `2000`, 6 bytes of data.
242/// Detailing the status of gripper, e.g. current position, speed, force ...
243#[derive(Debug, Clone, Serialize, Deserialize)]
244pub struct GripperStatus {
245    /// Activation status, echo of the `rACT` bit (activation bit).
246    pub act: bool,
247    /// Action status, echo of the `rGTO` bit (go to bit).
248    pub gto: bool,
249    /// gripper status, returns the current status and motion of the gripper fingers
250    pub sta: ActivationStatus,
251    /// Objected detection status, is a built-in feature that provides information on possible object pick-up. Ignore if `gto == 0`
252    pub obj: ObjDetectStatus,
253    /// Fault status returns general error messages that are useful for troubleshooting.
254    pub fault: GripperFault,
255    /// Other fault status, the masked higher 4 bits of register `FAULT STATUS`, (mask `0xF0`).
256    pub k_flt: u8,
257    /// Echo of the requested position for the gripper, value between `0x00` and `0xFF`.
258    pub pos_req: u8,
259    /// Actual position of the gripper obtained via the encoders, value between `0x00` and `0xFF`.
260    pub pos: u8,
261    /// The current is read instantaneously form the motor drive, value between `0x00` and `0xFF`, approximate current equivalent is `10 * current` in mA.
262    pub current: u8,
263}
264
265impl GripperStatus {
266    /// parse the gripper status from the registers.
267    pub fn parse(bytes: Vec<u8>) -> Self {
268        let act = bytes[0] & 1 != 0;
269        let gto = bytes[0] & 8 != 0;
270        let sta = ActivationStatus::from_u8((bytes[0] >> 4) & 0b11).unwrap();
271        let obj = ObjDetectStatus::from_u8((bytes[0] >> 6) & 0b11).unwrap();
272        let fault = GripperFault::from_u8(bytes[2]).unwrap();
273        let k_flt = bytes[2] & 0xF0;
274        let pos_req = bytes[3];
275        let pos = bytes[4];
276        let current = bytes[5];
277
278        GripperStatus {
279            act,
280            gto,
281            sta,
282            obj,
283            fault,
284            k_flt,
285            pos_req,
286            pos,
287            current,
288        }
289    }
290}
291
292impl From<Vec<u8>> for GripperStatus {
293    fn from(value: Vec<u8>) -> Self {
294        GripperStatus::parse(value)
295    }
296}
297
298/// Robot Output/ Functionalities
299///
300/// Write to registers starting at `1000`, 6 byte of data.
301/// specified the command parameter e.g. request position, speed, force ...
302///
303/// ## Reset
304/// To reset the gripper send a command with `act = false`.
305///
306/// ## Activating the gripper
307/// To activate the gripper, send a command with `act = true`.
308///
309/// `act` need to remain `true` in all following command, otherwise the gripper will reset.
310#[derive(Debug, Clone, Default, Serialize, Deserialize)]
311pub struct GripperCommand {
312    /// First action to be made prior to any other actions, `rACT` bit will activate the gripper.
313    /// Clear the `rACT` bit to reset the gripper and clear any fault status
314    ///
315    /// ## Warning
316    /// when setting `act = true`(`rACT == 1`), the gripper will begin movement to complete its activation feature.
317    ///
318    /// ## Info
319    /// Power loss will set `rACT == 1`; the `rACT` bit must be clear `act = false`(`rACT = 0`),
320    /// then set again to allow operation of the gripper
321    ///
322    /// ## Caution
323    /// The `rACT` bit must stay on (`act = true`) afterward for any other action to be performed.
324    pub act: bool,
325    /// The "Go To" action moves the gripper fingers to the requested position using the configuration defined by the other register,
326    /// `gto`(`rGTO`) will engage motion while byte 3,4,5 will determine aimed position, force, and speed.
327    /// The only motions performed without `gto`(`rGTO`) bit are activation and automation release routines.
328    pub gto: bool,
329    /// Automatic Release routine action slowly opens the gripper fingers until all motion axes reach their mechanical limits
330    /// After all motion are completed, the gripper sends a fault signal and needed to be reinitalized before any other motion is performed.
331    /// The `atr`(`rATR`) bit overrides all other commands excluding the activation bit `act`(`rACT`).
332    pub atr: bool,
333    /// Auto-release direction.
334    /// When auto-releasing, `ard`(`rARD`) commands the direction of the movement. The `ard`(`rARD`) bit should be set prior to
335    /// or at the same time as the `atr`(`rATR`) bit. as the motion direction is set when the auto-release is initated.
336    pub ard: bool,
337    /// This register is used to set the target position for the gripper's fingers.
338    /// The position `0x00` and `0xFF` correspond respectively to the fully opened and fully closed mechanical stops.
339    /// For detail finger trajectory, please refer to the Specifications section of repective manual.
340    ///
341    /// - `0x00` - Open position
342    /// - `0xFF` - Close position
343    ///
344    /// ## Info
345    /// The activation will allow the gripper to adjust to any fingertips.
346    /// No matter what is the size and/or shape of the fingertips,
347    /// `0` will always be fully opened and `255` fully closed,
348    /// with a quasi-linear relationship between the two values.
349    pub pos_req: u8,
350    /// This register is used to set the gripper closing and opening speed in real time,
351    /// however, setting a speed will not initiate a motion.
352    ///
353    /// - `0x00` - Minimum speed
354    /// - `0xFF` - Maximum speed
355    pub speed: u8,
356    /// The force setting defines the final gripper force for the gripper.
357    /// The force will fix the maximum current sent to the motor.
358    /// If the current limit is exceeded, the fingers stop and trigger an object detection notification.
359    /// Please refer to the "Picking Features" section of respective manual.
360    ///
361    /// - `0x00`- Minimum force
362    /// - `0xFF`- Maximum force
363    pub force: u8,
364}
365
366impl GripperCommand {
367    /// Create a new default gripper command.
368    pub fn new() -> Self {
369        Self::default()
370    }
371
372    /// First action to be made prior to any other actions, `rACT` bit will activate the gripper.
373    /// Clear the `rACT` bit to reset the gripper and clear any fault status
374    ///
375    /// ## Warning
376    /// when setting `act = true`(`rACT == 1`), the gripper will begin movement to complete its activation feature.
377    ///
378    /// ## Info
379    /// Power loss will set `rACT == 1`; the `rACT` bit must be clear `act = false`(`rACT = 0`),
380    /// then set again to allow operation of the gripper
381    ///
382    /// ## Caution
383    /// The `rACT` bit must stay on (`act = true`) afterward for any other action to be performed.
384    pub fn act(mut self, b: bool) -> Self {
385        self.act = b;
386        self
387    }
388    /// The "Go To" action moves the gripper fingers to the requested position using the configuration defined by the other register,
389    /// `gto`(`rGTO`) will engage motion while byte 3,4,5 will determine aimed position, force, and speed.
390    /// The only motions performed without `gto`(`rGTO`) bit are activation and automation release routines.
391    pub fn gto(mut self, b: bool) -> Self {
392        self.gto = b;
393        self
394    }
395    /// Automatic Release routine action slowly opens the gripper fingers until all motion axes reach their mechanical limits
396    /// After all motion are completed, the gripper sends a fault signal and needed to be reinitalized before any other motion is performed.
397    /// The `atr`(`rATR`) bit overrides all other commands excluding the activation bit `act`(`rACT`).
398    pub fn atr(mut self, b: bool) -> Self {
399        self.atr = b;
400        self
401    }
402    /// Auto-release direction.
403    ///
404    /// When auto-releasing, `ard`(`rARD`) commands the direction of the movement. The `ard`(`rARD`) bit should be set prior to
405    /// or at the same time as the `atr`(`rATR`) bit. as the motion direction is set when the auto-release is initated.
406    pub fn ard(mut self, b: bool) -> Self {
407        self.ard = b;
408        self
409    }
410    /// This register is used to set the target position for the gripper's fingers.
411    /// The position `0x00` and `0xFF` correspond respectively to the fully opened and fully closed mechanical stops.
412    /// For detail finger trajectory, please refer to the Specifications section of repective manual.
413    ///
414    /// - `0x00` - Open position
415    /// - `0xFF` - Close position
416    ///
417    /// ## Info
418    /// The activation will allow the gripper to adjust to any fingertips.
419    /// No matter what is the size and/or shape of the fingertips,
420    /// `0` will always be fully opened and `255` fully closed,
421    /// with a quasi-linear relationship between the two values.
422    pub fn pos_req(mut self, b: u8) -> Self {
423        self.pos_req = b;
424        self
425    }
426    /// This register is used to set the gripper closing and opening speed in real time,
427    /// however, setting a speed will not initiate a motion.
428    ///
429    /// - `0x00` - Minimum speed
430    /// - `0xFF` - Maximum speed
431    pub fn speed(mut self, b: u8) -> Self {
432        self.speed = b;
433        self
434    }
435    /// The force setting defines the final gripper force for the gripper.
436    /// The force will fix the maximum current sent to the motor.
437    /// If the current limit is exceeded, the fingers stop and trigger an object detection notification.
438    /// Please refer to the "Picking Features" section of respective manual.
439    ///
440    /// - `0x00`- Minimum force
441    /// - `0xFF`- Maximum force
442    pub fn force(mut self, b: u8) -> Self {
443        self.force = b;
444        self
445    }
446    /// make array for writing to register.
447    pub fn to_array(&self) -> [u16; 3] {
448        let mut req = 0;
449
450        if self.act {
451            req |= FLAG_ACT;
452        }
453        if self.gto {
454            req |= FLAG_GTO;
455        }
456        if self.atr {
457            req |= FLAG_ATR;
458        }
459        if self.ard {
460            req |= FLAG_ADR;
461        }
462
463        [
464            u16::from_be_bytes([req, 0]),
465            u16::from_be_bytes([0, self.pos_req]),
466            u16::from_be_bytes([self.speed, self.force]),
467        ]
468    }
469}
470
471/// Data Structure for interfacing with robotiq gripper with modbus rtu protocol.
472pub struct RobotiqGripper {
473    ctx: client::Context,
474}
475
476impl RobotiqGripper {
477    /// The Default Modbus slave ID of robotiq gripper
478    pub const DEFAULT_SLAVE_ID: u8 = 9;
479
480    /// Constructer from a modbus context.
481    pub fn new(ctx: client::Context) -> Self {
482        Self { ctx }
483    }
484
485    /// Constructer from USB port path, and slave id.
486    pub fn from_path_slave_id(
487        path: impl Into<String>,
488        slave_id: u8,
489    ) -> Result<Self, std::io::Error> {
490        let port = tokio_serial::new(path.into(), 115_200)
491            .data_bits(tokio_serial::DataBits::Eight)
492            .stop_bits(tokio_serial::StopBits::One)
493            .parity(tokio_serial::Parity::None)
494            .timeout(std::time::Duration::from_millis(500))
495            .open_native_async()?;
496
497        let ctx = rtu::attach_slave(port, Slave(slave_id));
498
499        Ok(Self::new(ctx))
500    }
501
502    /// Constructer form USB port path.
503    pub fn from_path(path: impl Into<String>) -> Result<Self, std::io::Error> {
504        Self::from_path_slave_id(path, Self::DEFAULT_SLAVE_ID)
505    }
506
507    /// Async function for writing a `GripperCommand` to the gripper
508    pub async fn write_async(&mut self, cmd: GripperCommand) -> Result<(), RobotiqError> {
509        Ok(self
510            .ctx
511            .write_multiple_registers(1000, &cmd.to_array())
512            .await??)
513    }
514    /// Async function for reading `GripperCommand` from the gripper
515    pub async fn read_async(&mut self) -> Result<GripperStatus, RobotiqError> {
516        Ok(self
517            .ctx
518            .read_holding_registers(2000, 3)
519            .await??
520            .into_iter()
521            .map(|u| u.to_be_bytes())
522            .flatten()
523            .collect::<Vec<_>>()
524            .into())
525    }
526
527    // /// Sync function for reading `GripperCommand` from the gripper
528    // pub fn read(&mut self) -> Result<GripperStatus, RobotiqError> {
529    //     let res = tokio::task::block_in_place(move || {
530    //         tokio::runtime::Handle::current().block_on(async { self.read_async().await })
531    //     })?;
532    //     Ok(res.into())
533    // }
534    // /// Sync function for writing a `GripperCommand` to the gripper
535    // pub fn write(&mut self, cmd: GripperCommand) -> Result<(), RobotiqError> {
536    //     tokio::task::block_in_place(move || {
537    //         tokio::runtime::Handle::current().block_on(async { self.write_async(cmd).await })
538    //     })
539    // }
540
541    /// Turn off the activation bit `rACT`, to reset fault.
542    pub async fn reset(&mut self) -> Result<&mut Self, RobotiqError> {
543        self.write_async(GripperCommand::default()).await?;
544        Ok(self)
545    }
546    /// Turn on the activation bit `rACT` to start initalization of the gripper
547    pub async fn activate(&mut self) -> Result<&mut Self, RobotiqError> {
548        self.write_async(GripperCommand::new().act(true)).await?;
549        Ok(self)
550    }
551    /// Await for the initalization process to finish.
552    pub async fn await_activate(&mut self) -> Result<&mut Self, RobotiqError> {
553        loop {
554            let status = self.read_async().await?;
555            if status.sta == ActivationStatus::Completed {
556                break;
557            }
558            if status.fault != GripperFault::NoFault {
559                return Err(status.fault.into());
560            }
561            std::thread::sleep(std::time::Duration::from_millis(100));
562        }
563        Ok(self)
564    }
565    /// Command the gripper to go to a certain set point with specified position, speed and force
566    ///
567    /// ## Parameter
568    /// ### `pos_req: u8`
569    /// This register is used to set the target position for the gripper's fingers.
570    /// The position `0x00` and `0xFF` correspond respectively to the fully opened and fully closed mechanical stops.
571    /// For detail finger trajectory, please refer to the Specifications section of repective manual.
572    ///
573    /// - `0x00` - Open position
574    /// - `0xFF` - Close position
575    ///
576    /// ## Info
577    /// The activation will allow the gripper to adjust to any fingertips.
578    /// No matter what is the size and/or shape of the fingertips,
579    /// `0` will always be fully opened and `255` fully closed,
580    /// with a quasi-linear relationship between the two values.
581    /// ### `speed: u8`
582    /// This register is used to set the gripper closing and opening speed in real time,
583    /// however, setting a speed will not initiate a motion.
584    ///
585    /// - `0x00` - Minimum speed
586    /// - `0xFF` - Maximum speed
587    /// ### `force: u8`
588    /// The force setting defines the final gripper force for the gripper.
589    /// The force will fix the maximum current sent to the motor.
590    /// If the current limit is exceeded, the fingers stop and trigger an object detection notification.
591    /// Please refer to the "Picking Features" section of respective manual.
592    ///
593    /// - `0x00`- Minimum force
594    /// - `0xFF`- Maximum force
595    pub async fn go_to(
596        &mut self,
597        pos_req: u8,
598        speed: u8,
599        force: u8,
600    ) -> Result<&mut Self, RobotiqError> {
601        let cmd = GripperCommand::new()
602            .act(true)
603            .gto(true)
604            .pos_req(pos_req)
605            .speed(speed)
606            .force(force);
607        self.write_async(cmd).await?;
608        Ok(self)
609    }
610    /// Await for the "Go To" command to finish.
611    ///
612    /// ## Return `ObjDetectStatus`
613    /// this function will return, when the gripper detected object at the end point, or reached target position.
614    pub async fn await_go_to(&mut self) -> Result<ObjDetectStatus, RobotiqError> {
615        loop {
616            let status = self.read_async().await?;
617            if status.obj != ObjDetectStatus::InMotion {
618                self.activate().await?;
619                return Ok(status.obj);
620            }
621            if status.fault != GripperFault::NoFault {
622                return Err(status.fault.into());
623            }
624            std::thread::sleep(std::time::Duration::from_millis(100));
625        }
626    }
627    /// ### Automatic release feature.
628    ///
629    /// Automatic Release routine action slowly opens the gripper fingers until all motion axes reach their mechanical limits
630    /// After all motion are completed, the gripper sends a fault signal and needed to be reinitalized before any other motion is performed.
631    /// The `atr`(`rATR`) bit overrides all other commands excluding the activation bit `act`(`rACT`).
632    ///
633    /// #### Auto-release direction.
634    ///
635    /// When auto-releasing, `ard`(`rARD`) commands the direction of the movement. The `ard`(`rARD`) bit should be set prior to
636    /// or at the same time as the `atr`(`rATR`) bit. as the motion direction is set when the auto-release is initated.
637    pub async fn automatic_release(&mut self, open: bool) -> Result<&mut Self, RobotiqError> {
638        let cmd = GripperCommand::new().act(true).atr(true).ard(open);
639        self.write_async(cmd).await?;
640        Ok(self)
641    }
642
643    /// Await for the automatic release routine to finish.
644    pub async fn await_automatic_release(&mut self) -> Result<&mut Self, RobotiqError> {
645        loop {
646            let status = self.read_async().await?;
647            match status.fault {
648                GripperFault::Releasing => {}
649                GripperFault::AutomaticReleaseCompleted => return Ok(self),
650                _ => return Err(status.fault.into()),
651            }
652            std::thread::sleep(std::time::Duration::from_millis(100));
653        }
654    }
655}
656
657impl Drop for RobotiqGripper {
658    fn drop(&mut self) {
659        tokio::task::block_in_place(move || {
660            tokio::runtime::Handle::current().block_on(async move {
661                let _ = self.ctx.disconnect().await;
662            });
663        });
664    }
665}
666
667use thiserror::Error;
668
669#[derive(Debug, Error)]
670pub enum RobotiqError {
671    #[error("std io error, serial comm error")]
672    IOError(#[from] std::io::Error),
673    #[error("Modbus protocol or transport errros.")]
674    ModbusError(#[from] tokio_modbus::Error),
675    #[error("A server (slave) exception.")]
676    ModbusException(#[from] tokio_modbus::Exception),
677    #[error("gripper fault")]
678    GripperFault(#[from] GripperFault),
679}