Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Noetic modifications #184

Open
wants to merge 7 commits into
base: kinetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions robotiq_2f_gripper_control/nodes/Robotiq2FGripperRtuNode.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python
#!/usr/bin/env python3

# Software License Agreement (BSD License)
#
Expand Down Expand Up @@ -51,7 +51,7 @@
from robotiq_2f_gripper_control.msg import _Robotiq2FGripper_robot_output as outputMsg

def mainLoop(device):

#Gripper is a 2F with a TCP connection
gripper = robotiq_2f_gripper_control.baseRobotiq2FGripper.robotiqbaseRobotiq2FGripper()
gripper.client = robotiq_modbus_rtu.comModbusRtu.communication()
Expand All @@ -66,14 +66,14 @@ def mainLoop(device):

#The Gripper command is received from the topic named 'Robotiq2FGripperRobotOutput'
rospy.Subscriber('Robotiq2FGripperRobotOutput', outputMsg.Robotiq2FGripper_robot_output, gripper.refreshCommand)


#We loop
while not rospy.is_shutdown():

#Get and publish the Gripper status
status = gripper.getStatus()
pub.publish(status)
pub.publish(status)

#Wait a little
#rospy.sleep(0.05)
Expand All @@ -83,7 +83,7 @@ def mainLoop(device):

#Wait a little
#rospy.sleep(0.05)

if __name__ == '__main__':
try:
mainLoop(sys.argv[1])
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python
#!/usr/bin/env python3

# Software License Agreement (BSD License)
#
Expand Down Expand Up @@ -41,15 +41,21 @@
This serves as an example for publishing messages on the 'Robotiq2FGripperRobotOutput' topic using the 'Robotiq2FGripper_robot_output' msg type for sending commands to a 2F gripper.
"""

from __future__ import print_function

import roslib; roslib.load_manifest('robotiq_2f_gripper_control')
import rospy
from robotiq_2f_gripper_control.msg import _Robotiq2FGripper_robot_output as outputMsg
from time import sleep

try:
input = raw_input
except NameError:
pass

def genCommand(char, command):
"""Update the command according to the character entered by the user."""
"""Update the command according to the character entered by the user."""

if char == 'a':
command = outputMsg.Robotiq2FGripper_robot_output();
command.rACT = 1
Expand All @@ -65,44 +71,44 @@ def genCommand(char, command):
command.rPR = 255

if char == 'o':
command.rPR = 0
command.rPR = 0

#If the command entered is a int, assign this value to rPRA
try:
try:
command.rPR = int(char)
if command.rPR > 255:
command.rPR = 255
if command.rPR < 0:
command.rPR = 0
except ValueError:
pass
pass

if char == 'f':
command.rSP += 25
if command.rSP > 255:
command.rSP = 255

if char == 'l':
command.rSP -= 25
if command.rSP < 0:
command.rSP = 0


if char == 'i':
command.rFR += 25
if command.rFR > 255:
command.rFR = 255

if char == 'd':
command.rFR -= 25
if command.rFR < 0:
command.rFR = 0

return command


def askForCommand(command):
"""Ask the user for a command to send to the gripper."""
"""Ask the user for a command to send to the gripper."""

currentCommand = 'Simple 2F Gripper Controller\n-----\nCurrent command:'
currentCommand += ' rACT = ' + str(command.rACT)
Expand All @@ -113,7 +119,7 @@ def askForCommand(command):
currentCommand += ', rFR = ' + str(command.rFR )


print currentCommand
print(currentCommand)

strAskForCommand = '-----\nAvailable commands\n\n'
strAskForCommand += 'r: Reset\n'
Expand All @@ -125,27 +131,27 @@ def askForCommand(command):
strAskForCommand += 'l: Slower\n'
strAskForCommand += 'i: Increase force\n'
strAskForCommand += 'd: Decrease force\n'

strAskForCommand += '-->'

return raw_input(strAskForCommand)
return input(strAskForCommand)

def publisher():
"""Main loop which requests new commands and publish them on the Robotiq2FGripperRobotOutput topic."""
rospy.init_node('Robotiq2FGripperSimpleController')

pub = rospy.Publisher('Robotiq2FGripperRobotOutput', outputMsg.Robotiq2FGripper_robot_output)

command = outputMsg.Robotiq2FGripper_robot_output();

while not rospy.is_shutdown():

command = genCommand(askForCommand(command), command)
command = genCommand(askForCommand(command), command)

pub.publish(command)

rospy.sleep(0.1)


if __name__ == '__main__':
publisher()
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python
#!/usr/bin/env python3

# Software License Agreement (BSD License)
#
Expand Down Expand Up @@ -41,6 +41,8 @@
This serves as an example for receiving messages from the 'Robotiq2FGripperRobotInput' topic using the 'Robotiq2FGripper_robot_input' msg type and interpreting the corresponding status of the 2F gripper.
"""

from __future__ import print_function

import roslib; roslib.load_manifest('robotiq_2f_gripper_control')
import rospy
from std_msgs.msg import String
Expand All @@ -49,7 +51,7 @@
def printStatus(status):
"""Print the status string generated by the statusInterpreter function."""

print statusInterpreter(status)
print(statusInterpreter(status))

def Robotiq2FGripperStatusListener():
"""Initialize the node and subscribe to the Robotiq2FGripperRobotInput topic."""
Expand Down Expand Up @@ -98,7 +100,7 @@ def statusInterpreter(status):
output += 'Fingers have stopped due to a contact while closing \n'
if(status.gOBJ == 3):
output += 'Fingers are at requested position\n'

#gFLT
output += 'gFLT = ' + str(status.gFLT) + ': '
if(status.gFLT == 0x00):
Expand All @@ -108,7 +110,7 @@ def statusInterpreter(status):
if(status.gFLT == 0x07):
output += 'Priority Fault: The activation bit must be set prior to action\n'
if(status.gFLT == 0x09):
output += 'Minor Fault: The communication chip is not ready (may be booting)\n'
output += 'Minor Fault: The communication chip is not ready (may be booting)\n'
if(status.gFLT == 0x0B):
output += 'Minor Fault: Automatic release in progress\n'
if(status.gFLT == 0x0E):
Expand All @@ -126,9 +128,9 @@ def statusInterpreter(status):

#gCU
output += 'gCU = ' + str(status.gCU) + ': '
output += 'Current of Fingers: ' + str(status.gCU * 10) + ' mA\n'
output += 'Current of Fingers: ' + str(status.gCU * 10) + ' mA\n'

return output

if __name__ == '__main__':
Robotiq2FGripperStatusListener()
10 changes: 5 additions & 5 deletions robotiq_2f_gripper_control/nodes/Robotiq2FGripperTcpNode.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python
#!/usr/bin/env python3

# Software License Agreement (BSD License)
#
Expand Down Expand Up @@ -51,7 +51,7 @@
from robotiq_2f_gripper_control.msg import _Robotiq2FGripper_robot_output as outputMsg

def mainLoop(address):

#Gripper is a 2F with a TCP connection
gripper = robotiq_2f_gripper_control.baseRobotiq2FGripper.robotiqbaseRobotiq2FGripper()
gripper.client = robotiq_modbus_tcp.comModbusTcp.communication()
Expand All @@ -66,14 +66,14 @@ def mainLoop(address):

#The Gripper command is received from the topic named 'Robotiq2FGripperRobotOutput'
rospy.Subscriber('Robotiq2FGripperRobotOutput', outputMsg.Robotiq2FGripper_robot_output, gripper.refreshCommand)


#We loop
while not rospy.is_shutdown():

#Get and publish the Gripper status
status = gripper.getStatus()
pub.publish(status)
pub.publish(status)

#Wait a little
rospy.sleep(0.05)
Expand All @@ -83,7 +83,7 @@ def mainLoop(address):

#Wait a little
rospy.sleep(0.05)

if __name__ == '__main__':
try:
#TODO: Add verification that the argument is an IP address
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,34 +54,34 @@ def __init__(self):

def verifyCommand(self, command):
"""Function to verify that the value of each variable satisfy its limits."""
#Verify that each variable is in its correct range
command.rACT = max(0, command.rACT)
command.rACT = min(1, command.rACT)
command.rGTO = max(0, command.rGTO)
command.rGTO = min(1, command.rGTO)

command.rATR = max(0, command.rATR)
command.rATR = min(1, command.rATR)
command.rPR = max(0, command.rPR)
command.rPR = min(255, command.rPR)

command.rSP = max(0, command.rSP)
command.rSP = min(255, command.rSP)

command.rFR = max(0, command.rFR)
command.rFR = min(255, command.rFR)
#Return the modified command
return command

#Verify that each variable is in its correct range
command.rACT = max(0, command.rACT)
command.rACT = min(1, command.rACT)

command.rGTO = max(0, command.rGTO)
command.rGTO = min(1, command.rGTO)

command.rATR = max(0, command.rATR)
command.rATR = min(1, command.rATR)

command.rPR = max(0, command.rPR)
command.rPR = min(255, command.rPR)

command.rSP = max(0, command.rSP)
command.rSP = min(255, command.rSP)

command.rFR = max(0, command.rFR)
command.rFR = min(255, command.rFR)

#Return the modified command
return command

def refreshCommand(self, command):
"""Function to update the command which will be sent during the next sendCommand() call."""
#Limit the value of each variable
command = self.verifyCommand(command)

#Limit the value of each variable
command = self.verifyCommand(command)

#Initiate command as an empty list
self.message = []
Expand All @@ -93,11 +93,11 @@ def refreshCommand(self, command):
self.message.append(0)
self.message.append(command.rPR)
self.message.append(command.rSP)
self.message.append(command.rFR)
self.message.append(command.rFR)

def sendCommand(self):
"""Send the command to the Gripper."""
"""Send the command to the Gripper."""

self.client.sendCommand(self.message)

def getStatus(self):
Expand All @@ -110,14 +110,14 @@ def getStatus(self):
message = inputMsg.Robotiq2FGripper_robot_input()

#Assign the values to their respective variables
message.gACT = (status[0] >> 0) & 0x01;
message.gACT = (status[0] >> 0) & 0x01;
message.gGTO = (status[0] >> 3) & 0x01;
message.gSTA = (status[0] >> 4) & 0x03;
message.gOBJ = (status[0] >> 6) & 0x03;
message.gFLT = status[2]
message.gPR = status[3]
message.gPO = status[4]
message.gCU = status[5]
message.gCU = status[5]

return message

Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
#!/usr/bin/env python
#!/usr/bin/env python3

from __future__ import print_function

import numpy as np

Expand Down Expand Up @@ -166,12 +168,12 @@ def main():
if gripper.is_reset():
gripper.reset()
gripper.activate()
print gripper.close(block=True)
print(gripper.close(block=True))
while not rospy.is_shutdown():
print gripper.open(block=False)
print(gripper.open(block=False))
rospy.sleep(0.11)
gripper.stop()
print gripper.close(block=False)
print(gripper.close(block=False))
rospy.sleep(0.1)
gripper.stop()

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(robotiq_3f_gripper_articulated_gazebo_plugins)
add_compile_options(-std=c++11)
set(CMAKE_CXX_STANDARD 17)

find_package(catkin REQUIRED COMPONENTS std_msgs gazebo_plugins actionlib tf image_transport control_msgs trajectory_msgs geometry_msgs sensor_msgs roscpp gazebo_ros robotiq_3f_gripper_articulated_msgs)

Expand Down
Loading