Skip to content

Commit b7b6de3

Browse files
committed
Add test of force mode and add arguments in hardware_interface
1 parent 5c4d560 commit b7b6de3

File tree

2 files changed

+73
-10
lines changed

2 files changed

+73
-10
lines changed

Diff for: ur_robot_driver/src/hardware_interface.cpp

+23-9
Original file line numberDiff line numberDiff line change
@@ -1185,17 +1185,19 @@ bool HardwareInterface::startForceMode(ur_msgs::SetForceModeRequest& req, ur_msg
11851185
{
11861186
bool HardwareInterface::setForceMode(ur_msgs::SetForceModeRequest & req, ur_msgs::SetForceModeResponse & res)
11871187
{
1188-
if (req.task_frame.size() != 6 || req.selection_vector.size() != 6 || req.wrench.size() != 6 ||
1189-
req.limits.size() != 6)
1190-
{
1191-
URCL_LOG_WARN("Size of received SetForceMode message is wrong");
1192-
res.success = false;
1193-
return false;
1194-
}
1188+
// This may need to be added back in depending on the final format of the srv file
1189+
// if (req.limits.size() != 6)
1190+
// {
1191+
// URCL_LOG_WARN("Size of received SetForceMode message is wrong");
1192+
// res.success = false;
1193+
// return false;
1194+
// }
11951195
urcl::vector6d_t task_frame;
11961196
urcl::vector6uint32_t selection_vector;
11971197
urcl::vector6d_t wrench;
11981198
urcl::vector6d_t limits;
1199+
double damping_factor = req.damping_factor;
1200+
double gain_scale = req.gain_scaling;
11991201

12001202
task_frame[0] = req.task_frame.pose.position.x;
12011203
task_frame[1] = req.task_frame.pose.position.x;
@@ -1226,9 +1228,21 @@ bool HardwareInterface::startForceMode(ur_msgs::SetForceModeRequest& req, ur_msg
12261228
limits[3] = req.limits.twist.angular.x;
12271229
limits[4] = req.limits.twist.angular.y;
12281230
limits[5] = req.limits.twist.angular.z;
1229-
12301231
unsigned int type = req.type;
1231-
res.success = this->ur_driver_->startForceMode(task_frame, selection_vector, wrench, type, limits);
1232+
if (ur_driver_->getVersion().major < 5)
1233+
{
1234+
if (gain_scale != 0)
1235+
{
1236+
ROS_WARN("Force mode gain scaling cannot be used on CB3 robots. The specified gain scaling will be ignored.");
1237+
}
1238+
res.success =
1239+
this->ur_driver_->startForceMode(task_frame, selection_vector, wrench, type, limits, damping_factor);
1240+
}
1241+
else
1242+
{
1243+
res.success = this->ur_driver_->startForceMode(task_frame, selection_vector, wrench, type, limits, damping_factor,
1244+
gain_scale);
1245+
}
12321246
return res.success;
12331247
}
12341248

Diff for: ur_robot_driver/test/integration_test.py

+50-1
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,8 @@
1515
from std_srvs.srv import Trigger, TriggerRequest
1616
import tf
1717
from trajectory_msgs.msg import JointTrajectoryPoint
18-
from ur_msgs.srv import SetIO, SetIORequest
18+
from geometry_msgs.msg import Pose, PoseStamped, Quaternion, Point, WrenchStamped, TwistStamped, Wrench, Twist, Vector3
19+
from ur_msgs.srv import SetIO, SetIORequest, SetForceModeRequest, SetForceMode
1920
from ur_msgs.msg import IOStates
2021

2122
from cartesian_control_msgs.msg import (
@@ -119,6 +120,20 @@ def init_robot(self):
119120
"Could not reach resend_robot_program service. Make sure that the driver is "
120121
"actually running in headless mode."
121122
" Msg: {}".format(err))
123+
124+
self.start_force_mode_srv = rospy.ServiceProxy('/ur_hardware_interface/start_force_mode', SetForceMode)
125+
try:
126+
self.start_force_mode_srv.wait_for_service(timeout)
127+
except rospy.exceptions.ROSException as err:
128+
self.fail("Could not reach start force mode service. Make sure that the driver is actually running."
129+
" Msg: {}".format(err))
130+
131+
self.end_force_mode_srv = rospy.ServiceProxy('/ur_hardware_interface/end_force_mode', Trigger)
132+
try:
133+
self.end_force_mode_srv.wait_for_service(timeout)
134+
except rospy.exceptions.ROSException as err:
135+
self.fail("Could not reach end force mode service. Make sure that the driver is actually running."
136+
" Msg: {}".format(err))
122137

123138
self.script_publisher = rospy.Publisher("/ur_hardware_interface/script_command", std_msgs.msg.String, queue_size=1)
124139
self.tf_listener = tf.TransformListener()
@@ -135,6 +150,40 @@ def set_robot_to_mode(self, target_mode):
135150
self.set_mode_client.wait_for_result()
136151
return self.set_mode_client.get_result().success
137152

153+
def test_force_mode_srv(self):
154+
point = Point(0.1, 0.1, 0.1)
155+
orientation = Quaternion(0, 0, 0, 0)
156+
task_frame_pose = Pose(point, orientation)
157+
header = std_msgs.msg.Header(seq=1, frame_id="robot")
158+
header.stamp.secs = int(time.time())+1
159+
header.stamp.nsecs = 0
160+
frame_stamp = PoseStamped(header, task_frame_pose)
161+
compliance = [0,0,1,0,0,1]
162+
wrench_vec = Wrench(Vector3(0,0,1),Vector3(0,0,1))
163+
wrench_stamp = WrenchStamped(header,wrench_vec)
164+
type_spec = 2
165+
limits = Twist(Vector3(0.1,0.1,0.1), Vector3(0.1,0.1,0.1))
166+
limits_stamp = TwistStamped(header, limits)
167+
damping_factor = 0.8
168+
gain_scale = 0.8
169+
req = SetForceModeRequest()
170+
req.task_frame = frame_stamp
171+
req.selection_vector_x = compliance[0]
172+
req.selection_vector_y = compliance[1]
173+
req.selection_vector_z = compliance[2]
174+
req.selection_vector_rx = compliance[3]
175+
req.selection_vector_ry = compliance[4]
176+
req.selection_vector_rz = compliance[5]
177+
req.wrench = wrench_stamp
178+
req.type = type_spec
179+
req.limits = limits_stamp
180+
req.damping_factor = damping_factor
181+
req.gain_scaling = gain_scale
182+
res = self.start_force_mode_srv.call(req)
183+
self.assertEqual(res.success, True)
184+
res = self.end_force_mode_srv.call(TriggerRequest())
185+
self.assertEqual(res.success, True)
186+
138187

139188
def test_joint_trajectory_position_interface(self):
140189
"""Test robot movement"""

0 commit comments

Comments
 (0)