Skip to content

Commit 4dac0e0

Browse files
committed
Initial import
0 parents  commit 4dac0e0

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

41 files changed

+2758
-0
lines changed

.gitignore

+40
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
# Compiled Object files
2+
*.slo
3+
*.lo
4+
*.o
5+
*.obj
6+
7+
# Precompiled Headers
8+
*.gch
9+
*.pch
10+
11+
# Compiled Dynamic libraries
12+
*.so
13+
*.dylib
14+
*.dll
15+
16+
# Fortran module files
17+
*.mod
18+
19+
# Compiled Static libraries
20+
*.lai
21+
*.la
22+
*.a
23+
*.lib
24+
25+
# Executables
26+
*.exe
27+
*.out
28+
*.app
29+
30+
# Mergetool
31+
*.orig
32+
33+
# Python
34+
*.pyc
35+
36+
# Temporary files
37+
*~
38+
39+
# Documentation
40+
doc

README.md

+72
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
# robotiq
2+
3+
ROS metapackage developed by the [Control Robotics Intelligence Group](http://www.ntu.edu.sg/home/cuong/) from the [Nanyang Technological University, Singapore](http://www.ntu.edu.sg).
4+
5+
## Setup
6+
7+
* Robotiq 85 Gripper with K-1363 Controller. (Modbus TCP/IP)
8+
9+
10+
## Maintainer
11+
12+
[Francisco Suárez Ruiz](fsuarez6.github.io)
13+
14+
## Documentation
15+
16+
* See the installation instructions below.
17+
* Throughout the various files in this repository.
18+
19+
## Installation
20+
21+
Go to your ROS working directory. e.g.
22+
```{bash}
23+
cd ~/catkin_ws/src
24+
```
25+
26+
Clone this repository:
27+
```{bash}
28+
git clone https://github.com/crigroup/robotiq.git
29+
```
30+
31+
Install any missing dependencies using rosdep:
32+
```{bash}
33+
rosdep update
34+
rosdep install --from-paths . --ignore-src -y
35+
```
36+
37+
Now compile your ROS workspace. e.g.
38+
```{bash}
39+
cd ~/catkin_ws && catkin_make
40+
```
41+
42+
### Testing the Installation
43+
44+
Be sure to always source the appropriate ROS setup file, e.g:
45+
```{bash}
46+
source ~/catkin_ws/devel/setup.bash
47+
```
48+
You might want to add that line to your `~/.bashrc`
49+
50+
Try the `cmodel_simple_controller`:
51+
```{bash}
52+
roslaunch robotiq cmodel_simple_controller.launch ip:=ROBOTIQ_IP_ADDRESS
53+
```
54+
Expected output:
55+
```
56+
Simple C-Model Controller
57+
-----
58+
Current command: rACT = 0, rGTO = 0, rATR = 0, rPR = 0, rSP = 0, rFR = 0
59+
-----
60+
Available commands
61+
62+
r: Reset
63+
a: Activate
64+
c: Close
65+
o: Open
66+
(0-255): Go to that position
67+
f: Faster
68+
l: Slower
69+
i: Increase force
70+
d: Decrease force
71+
-->
72+
```

robotiq/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(robotiq)
3+
find_package(catkin REQUIRED)
4+
catkin_metapackage()

robotiq/package.xml

+23
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
<?xml version="1.0"?>
2+
<package>
3+
<name>robotiq</name>
4+
<version>0.1.0</version>
5+
<description>Robotiq metapackage</description>
6+
7+
<maintainer email="[email protected]">Francisco Suarez Ruiz</maintainer>
8+
<license>BSD</license>
9+
<author email="[email protected]">Francisco Suarez Ruiz</author>
10+
<url type="website">https://github.com/crigroup/robotiq</url>
11+
<url type="bugtracker">https://github.com/crigroup/robotiq/issues</url>
12+
<url type="repository">https://github.com/crigroup/robotiq</url>
13+
14+
<buildtool_depend>catkin</buildtool_depend>
15+
16+
<run_depend>robotiq_control</run_depend>
17+
<run_depend>robotiq_description</run_depend>
18+
<run_depend>robotiq_msgs</run_depend>
19+
20+
<export>
21+
<metapackage/>
22+
</export>
23+
</package>

robotiq_control/CMakeLists.txt

+8
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(robotiq_control)
3+
4+
find_package(catkin REQUIRED COMPONENTS rospy)
5+
6+
catkin_python_setup()
7+
8+
catkin_package()
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
gripper_action_controller:
2+
# Feedback rate in Hz
3+
publish_rate: 100
4+
# Gripper width in meters [0, 0.085]
5+
min_gap: 0.0
6+
max_gap: 0.085
7+
# Gripper speed in m/s [0.013, 0.1]
8+
min_speed: 0.013
9+
max_speed: 0.1
10+
# Gripper force in N. [40, 100]
11+
min_force: 40.0
12+
max_force: 100.0
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<!-- launch file parameters -->
4+
<arg name="ip" default="192.168.0.13" />
5+
6+
<!-- CModel TCP Controller -->
7+
<node name="cmodel_tcp_driver" pkg="robotiq_control" type="cmodel_tcp_driver.py" output="screen" args="$(arg ip)"/>
8+
<!-- Simple action controller -->
9+
<rosparam file="$(find robotiq_control)/config/cmodel_action_controller.yaml" command="load" />
10+
<node name="cmodel_action_controller" pkg="robotiq_control" type="cmodel_action_controller.py" output="screen" />
11+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<!-- launch file parameters -->
4+
<arg name="ip" default="192.168.0.13" />
5+
6+
<!-- CModel TCP Controller -->
7+
<node name="cmodel_tcp_driver" pkg="robotiq_control" type="cmodel_tcp_driver.py" output="screen" args="$(arg ip)"/>
8+
<!-- Simple Controller -->
9+
<node name="robotiq_simple_controller" pkg="robotiq_control" type="robotiq_simple_controller.py" output="screen"/>
10+
</launch>

robotiq_control/package.xml

+18
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
<package>
2+
<name>robotiq_control</name>
3+
<version>0.1.0</version>
4+
<description>The robotiq_control package</description>
5+
6+
<maintainer email="[email protected]">Francisco Suarez Ruiz</maintainer>
7+
<license>BSD</license>
8+
<author email="[email protected]">Francisco Suarez Ruiz</author>
9+
<url type="website">https://github.com/crigroup/robotiq</url>
10+
<url type="bugtracker">https://github.com/crigroup/robotiq/issues</url>
11+
<url type="repository">https://github.com/crigroup/robotiq</url>
12+
13+
<buildtool_depend>catkin</buildtool_depend>
14+
<build_depend>rospy</build_depend>
15+
16+
<run_depend>robotiq_description</run_depend>
17+
<run_depend>robotiq_msgs</run_depend>
18+
</package>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,156 @@
1+
#!/usr/bin/env python
2+
import rospy, os
3+
import numpy as np
4+
# Actionlib
5+
from actionlib import SimpleActionServer
6+
from robotiq_msgs.msg import (
7+
CModelCommand,
8+
CModelStatus,
9+
CModelCommandAction,
10+
CModelCommandFeedback,
11+
CModelCommandResult,
12+
)
13+
14+
def read_parameter(name, default):
15+
if not rospy.has_param(name):
16+
rospy.logwarn('Parameter [%s] not found, using default: %s' % (name, default))
17+
return rospy.get_param(name, default)
18+
19+
20+
class CModelActionController(object):
21+
def __init__(self, activate=True):
22+
self._ns = rospy.get_namespace()
23+
# Read configuration parameters
24+
self._fb_rate = read_parameter(self._ns + 'gripper_action_controller/publish_rate', 60.0)
25+
self._min_gap = read_parameter(self._ns + 'gripper_action_controller/min_gap', 0.0)
26+
self._max_gap = read_parameter(self._ns + 'gripper_action_controller/max_gap', 0.085)
27+
self._min_speed = read_parameter(self._ns + 'gripper_action_controller/min_speed', 0.013)
28+
self._max_speed = read_parameter(self._ns + 'gripper_action_controller/max_speed', 0.1)
29+
self._min_force = read_parameter(self._ns + 'gripper_action_controller/min_force', 40.0)
30+
self._max_force = read_parameter(self._ns + 'gripper_action_controller/max_force', 100.0)
31+
# Configure and start the action server
32+
self._status = CModelStatus()
33+
self._name = self._ns + 'gripper_action_controller'
34+
self._server = SimpleActionServer(self._name, CModelCommandAction, execute_cb=self._execute_cb, auto_start = False)
35+
rospy.Subscriber('status', CModelStatus, self._status_cb)
36+
self._cmd_pub = rospy.Publisher('command', CModelCommand, queue_size=3)
37+
working = True
38+
if activate and not self._ready():
39+
rospy.sleep(2.0)
40+
working = self._activate()
41+
if not working:
42+
return
43+
self._server.start()
44+
rospy.loginfo(rospy.loginfo('%s: Started' % self._name))
45+
46+
def _preempt(self):
47+
self._stop()
48+
rospy.loginfo('%s: Preempted' % self._name)
49+
self._server.set_preempted()
50+
51+
def _status_cb(self, msg):
52+
self._status = msg
53+
54+
def _execute_cb(self, goal):
55+
success = True
56+
# Check that the gripper is active. If not, activate it.
57+
if not self._ready():
58+
if not self._activate():
59+
rospy.logwarn('%s could not accept goal because the gripper is not yet active' % self._name)
60+
return
61+
# check that preempt has not been requested by the client
62+
if self._server.is_preempt_requested():
63+
self._preempt()
64+
return
65+
# Send the goal to the gripper and feedback to the action client
66+
rate = rospy.Rate(self._fb_rate)
67+
rospy.loginfo('%s: Moving gripper to position: %.3f ' % (self._name, goal.position))
68+
feedback = CModelCommandFeedback()
69+
while not self._reached_goal(goal.position):
70+
self._goto_position(goal.position, goal.velocity, goal.force)
71+
if rospy.is_shutdown() or self._server.is_preempt_requested():
72+
self._preempt()
73+
return
74+
feedback.position = self._get_position()
75+
feedback.stalled = self._stalled()
76+
feedback.reached_goal = self._reached_goal(goal.position)
77+
self._server.publish_feedback(feedback)
78+
rate.sleep()
79+
if self._stalled():
80+
break
81+
rospy.loginfo('%s: Succeeded' % self._name)
82+
result = CModelCommandResult()
83+
result.position = self._get_position()
84+
result.stalled = self._stalled()
85+
result.reached_goal = self._reached_goal(goal.position)
86+
self._server.set_succeeded(result)
87+
88+
def _activate(self, timeout=5.0):
89+
command = CModelCommand();
90+
command.rACT = 1
91+
command.rGTO = 1
92+
command.rSP = 255
93+
command.rFR = 150
94+
start_time = rospy.get_time()
95+
while not self._ready():
96+
if rospy.is_shutdown():
97+
self._preempt()
98+
return False
99+
if rospy.get_time() - start_time > timeout:
100+
rospy.logwarn('Failed to activated gripper in ns [%s]' % (self._ns))
101+
return False
102+
self._cmd_pub.publish(command)
103+
rospy.sleep(0.1)
104+
rospy.loginfo('Successfully activated gripper in ns [%s]' % (self._ns))
105+
return True
106+
107+
def _get_position(self):
108+
gPO = self._status.gPO
109+
pos = np.clip((self._max_gap - self._min_gap)/(-230.)*(gPO-230.), self._min_gap, self._max_gap)
110+
return pos
111+
112+
def _goto_position(self, pos, vel, force):
113+
"""
114+
Goto position with desired force and velocity
115+
@type pos: float
116+
@param pos: Gripper width in meters
117+
@type vel: float
118+
@param vel: Gripper speed in m/s
119+
@type force: float
120+
@param force: Gripper force in N
121+
"""
122+
command = CModelCommand()
123+
command.rACT = 1
124+
command.rGTO = 1
125+
command.rPR = int(np.clip((-230)/(self._max_gap - self._min_gap) * (pos - self._min_gap) + 230., 0, 230))
126+
command.rSP = int(np.clip((255)/(self._max_speed - self._min_speed) * (vel - self._min_speed), 0, 255))
127+
command.rFR = int(np.clip((255)/(self._max_force - self._min_force) * (force - self._min_force), 0, 255))
128+
self._cmd_pub.publish(command)
129+
130+
def _moving(self):
131+
return self._status.gGTO == 1 and self._status.gOBJ == 0
132+
133+
def _reached_goal(self, goal, tol = 0.003):
134+
return (abs(goal - self._get_position()) < tol)
135+
136+
def _ready(self):
137+
return self._status.gSTA == 3 and self._status.gACT == 1
138+
139+
def _stalled(self):
140+
return self._status.gOBJ == 1 or self._status.gOBJ == 2
141+
142+
def _stop(self):
143+
command = CModelCommand()
144+
command.rACT = 1
145+
command.rGTO = 0
146+
self._cmd_pub.publish(command)
147+
rospy.loginfo('Stopping gripper in ns [%s]' % (self._ns))
148+
149+
150+
if __name__ == '__main__':
151+
node_name = os.path.splitext(os.path.basename(__file__))[0]
152+
rospy.init_node(node_name)
153+
rospy.loginfo('Starting [%s] node' % node_name)
154+
cmodel_server = CModelActionController()
155+
rospy.spin()
156+
rospy.loginfo('Shuting down [%s] node' % node_name)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
#!/usr/bin/env python
2+
import os, sys
3+
import rospy
4+
from robotiq_control.cmodel_base import RobotiqCModel, ComModbusTcp
5+
from robotiq_msgs.msg import CModelCommand, CModelStatus
6+
7+
def mainLoop(address):
8+
# Gripper is a C-Model with a TCP connection
9+
gripper = RobotiqCModel()
10+
gripper.client = ComModbusTcp()
11+
# We connect to the address received as an argument
12+
gripper.client.connectToDevice(address)
13+
# The Gripper status
14+
pub = rospy.Publisher('status', CModelStatus, queue_size=3)
15+
# The Gripper command
16+
rospy.Subscriber('command', CModelCommand, gripper.refreshCommand)
17+
18+
while not rospy.is_shutdown():
19+
# Get and publish the Gripper status
20+
status = gripper.getStatus()
21+
pub.publish(status)
22+
# Wait a little
23+
rospy.sleep(0.05)
24+
# Send the most recent command
25+
gripper.sendCommand()
26+
# Wait a little
27+
rospy.sleep(0.05)
28+
29+
if __name__ == '__main__':
30+
rospy.init_node('cmodel_tcp_driver')
31+
try:
32+
# TODO: Add verification that the argument is an IP address
33+
mainLoop(sys.argv[1])
34+
except rospy.ROSInterruptException: pass

0 commit comments

Comments
 (0)