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

Addition of the vacuum grippers (only EPick at the moment) #175

Open
wants to merge 3 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
66 changes: 66 additions & 0 deletions robotiq_vacuum_grippers_control/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
cmake_minimum_required(VERSION 2.8.3)
project(robotiq_vacuum_grippers_control)
find_package(catkin REQUIRED COMPONENTS robotiq_ethercat roscpp rospy message_generation)


#set the default path for built executables to the "bin" directory
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
#set the default path for built libraries to the "lib" directory
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)

###################################
## catkin message generation ##
###################################
add_message_files(
FILES
RobotiqVacuumGrippers_robot_input.msg
RobotiqVacuumGrippers_robot_output.msg
)

catkin_python_setup()

generate_messages()

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
CATKIN_DEPENDS rospy message_runtime roscpp robotiq_ethercat
INCLUDE_DIRS include
)

include_directories(include)
include_directories(
${catkin_INCLUDE_DIRS}
${robotiq_ethercat_INCLUDE_DIRS}
)

add_executable(robotiq_vacuum_grippers_ethercat_node
src/robotiq_vacuum_grippers_control/robotiq_vacuum_grippers_ethercat_node.cpp
src/robotiq_vacuum_grippers_control/robotiq_vacuum_grippers_ethercat_client.cpp
)

target_link_libraries(robotiq_vacuum_grippers_ethercat_node
${robotiq_ethercat_LIBRARIES}
${catkin_LIBRARIES}

)

add_dependencies(robotiq_vacuum_grippers_ethercat_node robotiq_vacuum_grippers_control_generate_messages_cpp)

#############
## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/groovy/api/catkin/html/adv_user_guide/variables.html

install(PROGRAMS nodes/RobotiqVacuumGrippersSimpleController.py nodes/RobotiqVacuumGrippersStatusListener.py
nodes/RobotiqVacuumGrippersTcpNode.py nodes/RobotiqVacuumGrippersRtuNode.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
#ifndef ROBOTIQ_VACUUM_GRIPPERS_ETHERCAT_CLIENT_H
#define ROBOTIQ_VACUUM_GRIPPERS_ETHERCAT_CLIENT_H

#include <robotiq_vacuum_grippers_control/RobotiqVacuumGrippers_robot_output.h>
#include <robotiq_vacuum_grippers_control/RobotiqVacuumGrippers_robot_input.h>

// Forward declaration of EtherCatManager
namespace robotiq_ethercat
{
class EtherCatManager;
}

namespace robotiq_vacuum_grippers_control
{

/**
* \brief This class provides a client for the EtherCAT manager object that
* can translate robot input/output messages and translate them to
* the underlying IO Map.
*/

class RobotiqVacuumGrippersEtherCatClient
{
public:
typedef robotiq_vacuum_grippers_control::RobotiqVacuumGrippers_robot_output GripperOutput;
typedef robotiq_vacuum_grippers_control::RobotiqVacuumGrippers_robot_input GripperInput;

/**
* \brief Constructs a control interface to a vacuum Robotiq gripper on
* the given ethercat network and the given slave_no.
*
* @param[in] manager The interface to an EtherCAT network that the gripper
* is connected to.
*
* @param[in] slave_no The slave number of the gripper on the EtherCAT network
* (>= 1)
*/
RobotiqVacuumGrippersEtherCatClient(robotiq_ethercat::EtherCatManager& manager, int slave_no);

/**
* \brief Write the given set of control flags to the memory of the gripper
*
* @param[in] output The set of output-register values to write to the gripper
*/
void writeOutputs(const GripperOutput& output);

/**
* \brief Reads set of input-register values from the gripper.
* \return The gripper input registers as read from the controller IOMap
*/
GripperInput readInputs() const;

/**
* \brief Reads set of output-register values from the gripper.
* \return The gripper output registers as read from the controller IOMap
*/
GripperOutput readOutputs() const;

private:
robotiq_ethercat::EtherCatManager& manager_;
const int slave_no_;
};

}

#endif
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<launch>
<arg name="gripper_name" default="gripper" />
<arg name="slave_number" default="1" />
<arg name="activate" default="True" />
<arg name="ifname" default="eth1" />

<node pkg="robotiq_vacuum_grippers_control" type="robotiq_vacuum_grippers_ethercat_node" name="gripper_server" output="screen">
<param name="ifname" type="str" value="$(arg ifname)" />
<param name="activate" type="bool" value="$(arg activate)" />
<param name="slave_number" type="int" value="$(arg slave_number)"/>

<remap from="output" to="/$(arg gripper_name)/output" />
<remap from="input" to="/$(arg gripper_name)/input" />
</node>
</launch>
14 changes: 14 additions & 0 deletions robotiq_vacuum_grippers_control/mainpage.dox
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/**
\mainpage
\htmlinclude manifest.html

\b robotiq_vacuum_grippers_control

<!--
Provide an overview of your package.
-->

-->


*/
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
uint8 gACT
uint8 gMOD
uint8 gGTO
uint8 gSTA
uint8 gOBJ
uint8 gFLT
uint8 gPR
uint8 gPO
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
uint8 rACT
uint8 rMOD
uint8 rGTO
uint8 rATR
uint8 rPR
uint8 rSP
uint8 rFR

Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
#!/usr/bin/env python

# Software License Agreement (BSD License)
#
# Copyright (c) 2012, Robotiq, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of Robotiq, Inc. nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
# Copyright (c) 2012, Robotiq, Inc.
# Revision $Id$

"""@package docstring
ROS node for controling a Robotiq vacuum gripper using the Modbus RTU protocol.

The script takes as an argument the IP address of the gripper. It initializes a baseRobotiqVacuumGrippers object and adds a comModbusTcp client to it. It then loops forever, reading the gripper status and updating its command. The gripper status is published on the 'RobotiqVacuumGrippersRobotInput' topic using the 'RobotiqVacuumGrippers_robot_input' msg type. The node subscribes to the 'RobotiqVacuumGrippersRobotOutput' topic for new commands using the 'RobotiqVacuumGrippers_robot_output' msg type. Examples are provided to control the gripper (RobotiqVacuumGrippersSimpleController.py) and interpreting its status (RobotiqVacuumGrippersStatusListener.py).
"""

import roslib; roslib.load_manifest('robotiq_vacuum_grippers_control')
roslib.load_manifest('robotiq_modbus_rtu')
import rospy
import robotiq_vacuum_grippers_control.baseRobotiqVacuumGrippers
import robotiq_modbus_rtu.comModbusRtu
import os, sys
from robotiq_vacuum_grippers_control.msg import _RobotiqVacuumGrippers_robot_input as inputMsg
from robotiq_vacuum_grippers_control.msg import _RobotiqVacuumGrippers_robot_output as outputMsg

def mainLoop(device):

#Gripper is a Vacuum with a TCP connection
gripper = robotiq_vacuum_grippers_control.baseRobotiqVacuumGrippers.robotiqbaseRobotiqVacuumGrippers()
gripper.client = robotiq_modbus_rtu.comModbusRtu.communication()

#We connect to the address received as an argument
gripper.client.connectToDevice(device)

rospy.init_node('robotiqVacuumGrippers')

#The Gripper status is published on the topic named 'RobotiqVacuumGrippersRobotInput'
pub = rospy.Publisher('RobotiqVacuumGrippersRobotInput', inputMsg.RobotiqVacuumGrippers_robot_input)

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


#We loop
while not rospy.is_shutdown():

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

#Wait a little
#rospy.sleep(0.05)

#Send the most recent command
gripper.sendCommand()

#Wait a little
#rospy.sleep(0.05)

if __name__ == '__main__':
try:
mainLoop(sys.argv[1])
except rospy.ROSInterruptException: pass
Loading