ABB ROS node by MCube Lab at MIT
- Setting up the package
- Operation modes
- Service calls
- Available services
- Standard services
PingSetCartesianSetCartesianJGetCartesianSetJointsGetJointsGetIKGetFKStopSetToolSetInertiaSetWorkObjectSetCommSetMotionSupervisionSetSpeedSetAccGetStateSetZoneSetTrackDistSetDefaultsIsMovingAddBufferExecuteBufferClearBufferAddJointPosBufferExecuteJointPosBufferClearJointPosBufferActivateCSSDeactivateCSSIOSignal
- EGM services
- Standard services
- Examples
- Clone this repo under the
catkin_wsfolder of your project. - Use
catkin_maketo compile all packages and dependencies. - Update the parameter file in
robot_node/parameters/mcubeRobotParams.yamlwith the proper robot values. - Update the launch file in
robot_node/launch/mcubeSystem.launchwith the proper robot identifier. - Start running the RAPID robot server pressing Play in the FlexPendant.
- Finally, launch
roslaunch robot_node mcubeSystem.launch.
If connection with the ABB controller is successful, a variety of ROS services will now be available. You can check them by typing rosservice call and then pressing Tab.
-
Standard blocking mode: User can operate the robot via standard services. Function calls (e.g. movements) are blocking until the operation is about to finish and cannot be stopped.
-
Standard non-blocking mode: User can operate the robot via standard services. Instructions are not sent immediately to the robot; intermediate targets are sent instead. Therefore, user can stop or change final destinations before final target is achieved. Function calls are non-blocking.
-
EGM mode: User can operate the robot pubishing target poses or velocities to the [
SetCartesian] topic, depending on the chosen EGM mode when callingActivateEGM. Current pose and joint state can be obtained viaGetCartesianandGetJointstopics, respectively. -
RRI mode: EGM predecessor, deprecated.
When started, the ROS node is working in standard and blocking mode. Standard non-blocking mode can be activated using the SetComm service, and EGM can be activated via the ActivateEGM service.
EGM operation mode relies in a constant flow of information between the robot and the computer. More concretely, the robot checks the incoming information (poses or speeds) from the computer and executes it at an approximate rate of 248 Hz. If the user publishes at /robotN_EGM/SetCartesian at a slower rate or does not publish at all, those queries will result in no motion (previously sent position or zero speed).
You can check some basic examples using EGM operation mode in the egm-demos repository.
Note that, for any interface, the specific service name is given by the robot identifier and the service type itself. For example, the Ping service for robot1 will be /robot1_Ping.
-
Command line: Any of the services listed below can be called via the
rosservice callcommand via terminal. For example, to ping a robot identified byrobot1, callrosservice call /robot1_Ping. -
Python: Check out the ROS tutorial on Writing a Simple Service Client (Python).
-
C++: Check out the ROS tutorial on Writing a Simple Service Client (C++).
-
Matlab: Check out the Matlab tutorial on Creating a Service Client. Note that Robotics System Toolbox is required.
Furthermore, as these services use custom messages for requests and returns, the Robotics System Toolbox Interface for ROS Custom Messages should be installed as well, in order to generate the custom messages for Matlab. After installed, use the
rosgenmsgto generate them and follow the instructions. For example:rosgenmsg('/home/mcube/example_project/catkin_ws/src/abb-ros-catkin/')
-
Pingsends a dummy message to the robot and waits for its answer, in order to check the connection. -
Input: empty
-
Output:
int64 ret,string msg
-
SetCartesianmoves the robot to a given cartesian position. -
Input:
float64 x,float64 y,float64 z,float64 q0,float64 qx,float64 qy,float64 qz -
Output:
int64 ret,string msg
-
SetCartesianJmoves the robot to a given cartesian position using a joint move. -
Input:
float64 x,float64 y,float64 z,float64 q0,float64 qx,float64 qy,float64 qz -
Output:
int64 ret,string msg
-
GetCartesianqueries the cartesian position of the robot. -
Input: empty
-
Output:
float64 x,float64 y,float64 z,float64 q0,float64 qx,float64 qy,float64 qz,int64 ret,string msg
-
SetJointsmoves the robot to a given joint position. -
Input:
float64 j1,float64 j2,float64 j3,float64 j4,float64 j5,float64 j6 -
Output:
int64 ret,string msg
-
GetJointsqueries the robot for the current position of its joints. -
Input: empty
-
Output:
float64 j1,float64 j2,float64 j3,float64 j4,float64 j5,float64 j6,int64 ret,string msg
-
GetIKqueries the robot for the inverse kinematics (joint angles) given a cartesian position. -
Input:
float64 x,float64 y,float64 z,float64 q0,float64 qx,float64 qy,float64 qz -
Output:
float64 j1,float64 j2,float64 j3,float64 j4,float64 j5,float64 j6,int64 ret,string msg
-
GetFKqueries the robot for the forward kinematics (cartesian position) given the joint angles. -
Input:
float64 j1,float64 j2,float64 j3,float64 j4,float64 j5,float64 j6 -
Output:
float64 x,float64 y,float64 z,float64 q0,float64 qx,float64 qy,float64 qz,int64 ret,string msg
-
Stopstops the robot when operating in standard non-blocking mode. -
Input: empty
-
Output:
int64 ret,string msg
-
SetToolsets the tool frame of the robot. -
Input:
float64 x,float64 y,float64 z,float64 q0,float64 qx,float64 qy,float64 qz -
Output:
int64 ret,string msg
-
SetInertiasets the inertia of the tool of the robot. -
Input:
float64 m,float64 cgx,float64 cgy,float64 cgz,float64 ix,float64 iy,float64 iz -
Output:
int64 ret,string msg
-
SetWorkObjectsets the work object of the robot. -
Input:
float64 x,float64 y,float64 z,float64 q0,float64 qx,float64 qy,float64 qz -
Output:
int64 ret,string msg
-
SetCommsets the communication mode of our robot (standard blocking mode or standard non-blocking mode). -
Input:
int64 mode(0 for non-blocking, 1 for blocking) -
Output:
int64 ret,string msg
-
SetMotionSupervisionsets the motion supervision of the robot. -
Input:
float64 supervision(between 1 and 300, recommended: 50) -
Output:
int64 ret,string msg
-
SetSpeedsets the speed of the robot in standard mode. This will affect the step size in non-blocking mode or the actual speed in blocking mode. -
Input:
float64 tcp(in mm/s),float64 ori(in deg/s) -
Output:
int64 ret,string msg
-
SetAccsets the acceleration of the robot in standard mode. This will affect the step size in non-blocking mode or the actual speed in blocking mode. -
Input:
float64 acc(in mm/s^2),float64 deacc(in mm/s^2) -
Output:
int64 ret,string msg
-
GetStategets the current state of the robot. -
Input: empty
-
Output:
float64 tcp(in mm/s),float64 ori(in deg/s),int64 zone,int64 vacuum,float64 workx,float64 worky,float64 workz,float64 workq0,float64 workqx,float64 workqy,float64 workqz,float64 toolx,float64 tooly,float64 toolz,float64 toolq0,float64 toolqx,float64 toolqy,float64 toolqz,float64 toolm,float64 toolcgx,float64 toolcgy,float64 toolcgz,float64 toolix,float64 tooliy,float64 tooliz,int64 ret,string msg
-
SetZonesets the zone of the robot. This is the distance before the end of a motion that the server will respond. This enables smooth motions. -
Read the service definition at
robot_comm/srv/robot_SetZone.srvfor more details.
-
SetTrackDistsets the tracking distance of the robot while in standard non-blocking mode. -
Input:
float64 pos_dist(in mm),float64 ang_dist(in deg) -
Output:
int64 ret,string msg
-
SetDefaultsrestores the robot to default configuration. -
Input: empty
-
Output:
int64 ret,string msg
-
IsMovingreturns whether the robot is moving or not. In blocking mode, this will always return false, as the robot will move only when a function is being called (and is blocking). -
Input: empty
-
Output:
bool moving,int64 ret,string msg
-
AddBufferadds a TCP pose buffer command. -
Input:
float64 x,float64 y,float64 z,float64 q0,float64 qx,float64 qy,float64 qz -
Output:
int64 ret,string msg
-
ExecuteBufferexecutes the buffer defined by severalAddBufferservice calls. -
Input: empty
-
Output:
int64 ret,string msg
-
ClearBufferclears the buffer defined by severalAddBufferservice calls. -
Input: empty
-
Output:
int64 ret,string msg
-
AddJointPosBufferadds a joint position buffer command. -
Input:
float64 j1,float64 j2,float64 j3,float64 j4,float64 j5,float64 j6 -
Output:
int64 ret,string msg
-
ExecuteBufferexecutes the buffer defined by severalAddJointPosBufferservice calls. -
Input: empty
-
Output:
int64 ret,string msg
-
ClearBufferclears the buffer defined by severalAddJointPosBufferservice calls. -
Input: empty
-
Output:
int64 ret,string msg
-
ActivateCSSactivates Cartesian Soft Servo. -
Input:
int32 refFrame,float64 refOrient_q0,float64 refOrient_qx,float64 refOrient_qy,float64 refOrient_qz,int32 softDir,float64 stiffness,float64 stiffnessNonSoftDir,int32 allowMove,float64 ramp -
Output:
int64 ret,string msg
-
DeactivateCSSdeactivates Cartesian Soft Servo. -
Input:
geometry_msgs/Pose ToPose -
Output:
int64 ret,string msg
-
IOSignalsets I/O signals to the robot. -
Input:
int32 output_num(from 1 to 4),int32 signal(0 for off, 1 for on) -
Output:
int64 ret,string msg
-
ActivateEGMactivates EGM. If called when standard non-blocking mode is running, all movements will be stopped. After calling it, all other services will be disabled exceptStopEGMuntil this last one is called or timeout. -
Input:
bool mode(0for pose mode,1for velocity mode),int64 timeout(in seconds) -
Output:
int64 ret,string msg
-
StopEGMstops EGM. After calling it, all other services will be enabled again and standard mode will be recovered. -
Input: empty
-
Output:
int64 ret,string msg
-
Run a series of joint configurations:
rosservice call /robot1_ClearJointPosBuffer rosservice call -- /robot1_AddJointPosBuffer 0 0 0 0 90 0 rosservice call -- /robot1_AddJointPosBuffer 0 0 0 0 91 0 rosservice call -- /robot1_AddJointPosBuffer 0 0 0 0 89 0 rosservice call /robot1_ExecuteJointPosBuffer -
Run a series of cartesian configurations:
rosservice call /robot1_ClearBuffer rosservice call /robot1_SetSpeed 50 50 # apply to the following knot points until the next set speed. rosservice call -- /robot1_AddBuffer 300 0 300 1 0 0 0 # x y z (mm) q0 qx qy qz rosservice call -- /robot1_AddBuffer 300 0 301 1 0 0 0 rosservice call /robot1_SetSpeed 50 100 rosservice call -- /robot1_AddBuffer 300 0 300 1 0 0 0 rosservice call /robot1_ExecuteBuffer # go through the whole trajectoryNote: Too small spacing between points may cause jerky motions. Try SetZone to higher value.
-
Set 24V IO signals:
rosservice call /robot1_IOSignal [output_num] [signal] # output_num = 1,2,3,4; #signal 1:on 0:off rosservice call /robot1_IOSignal 1 1 # signal output channel 1 to on rosservice call /robot1_IOSignal 1 0 # signal output channel 1 to off