robotiq_3f_gripper_api.h
Go to the documentation of this file.
1 // Copyright (c) 2016, Toyota Research Institute. All rights reserved.
2 
3 // Redistribution and use in source and binary forms, with or without
4 // modification, are permitted provided that the following conditions are met:
5 
6 // 1. Redistributions of source code must retain the above copyright
7 // notice, this list of conditions and the following disclaimer.
8 
9 // 2. Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 
13 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
14 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
15 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
16 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
17 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
18 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
19 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
20 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
21 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
22 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
23 // POSSIBILITY OF SUCH DAMAGE.
24 
25 #ifndef ROBOTIQ_3F_GRIPPER_API_H
26 #define ROBOTIQ_3F_GRIPPER_API_H
27 
29 
30 namespace robotiq
31 {
42 
45 } // end namespace robotiq
46 
48 {
49 using namespace robotiq;
50 
52 {
53 public:
55 
56  void setInitialization(InitializationMode mode);
57  void setGraspingMode(GraspingMode mode);
58  void setActionMode(ActionMode mode);
59  void setEmergencyRelease(EmergencyRelease release);
60  void setInidividualControlMode(IndividualControl fingers, IndividualControl scissor);
61  void setPosition(const double &posA, const double &posB=0, const double &posC=0, const double &posS=0);
62  void setVelocity(const double &velA, const double &velB=0, const double &velC=0, const double &velS=0);
63  void setForce(const double &fA, const double &fB=0, const double &fC=0, const double &fS=0);
64  void setRaw(const Robotiq3FGripperClientBase::GripperOutput &raw);
65 
66  void getPosition(double *posA, double *posB, double *posC, double *posS) const;
67  void getPositionCmd(double *posA, double *posB, double *posC, double *posS) const;
68  void getCurrent(double *curA, double *curB, double *curC, double *curS) const;
69  void getGripperStatus(InitializationMode *gACT, GraspingMode *gMOD, ActionMode *gGTO, GripperStatus *gIMC, MotionStatus *gSTA) const;
70  void getFaultStatus(FaultStatus *gFLT) const;
71  void getObjectStatus(ObjectStatus *fA, ObjectStatus *fB, ObjectStatus *fC, ObjectStatus *fS) const;
72  void getRaw(Robotiq3FGripperClientBase::GripperInput *raw) const;
73 
74  void getCommandPos(double *posA, double *posB, double *posC, double *posS) const;
75 
76  bool isInitialized();
77  bool isReady();
78  bool isModeSet(GraspingMode mode);
79  bool isHalted();
80  bool isMoving();
81  bool isEmergReleaseComplete();
82 
83  void read();
84  void write();
85 
86 private:
88 
91 
93  double pos_to_ticks_;
94  double pos_offset_;
95  double sci_to_ticks_;
96  double sci_offset_;
97  double vel_to_ticks_;
98  double vel_offset_;
102 
103 };
104 
105 template <typename T>
106 inline T limit (double value)
107 {
108  value = value < std::numeric_limits<T>::min() ? std::numeric_limits<T>::min() : value;
109  value = value > std::numeric_limits<T>::max() ? std::numeric_limits<T>::max() : value;
110  return static_cast<T>(value);
111 }
112 
113 } //end namespace robotiq_3f_gripper_control
114 
115 #endif // ROBOTIQ_3F_GRIPPER_API_H
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput GripperOutput
boost::shared_ptr< Robotiq3FGripperClientBase > base_
ROSCPP_DECL bool isInitialized()
Robotiq3FGripperClientBase::GripperOutput command_
Robotiq3FGripperClientBase::GripperInput status_
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput GripperInput
int mode


robotiq_3f_gripper_control
Author(s): Nicolas Lauzier (Robotiq inc.), Allison Thackston
autogenerated on Tue Jun 1 2021 02:29:58