|
47 | 47 | from rclpy.node import Node |
48 | 48 |
|
49 | 49 | from controller_manager_msgs.srv import SwitchController |
| 50 | +from ur_msgs.msg import FrictionModelParameters |
50 | 51 |
|
51 | 52 | sys.path.append(os.path.dirname(__file__)) |
52 | 53 | from test_common import ( # noqa: E402 |
@@ -113,8 +114,10 @@ def test_set_friction_model_parameters(self, tf_prefix): |
113 | 114 | self._friction_model_interface = FrictionModelInterface(self.node) |
114 | 115 |
|
115 | 116 | res = self._friction_model_interface.set_friction_model_parameters( |
116 | | - viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9, 0.9], |
117 | | - coulomb_scale=[0.8, 0.8, 0.7, 0.8, 0.8, 0.8], |
| 117 | + parameters=FrictionModelParameters( |
| 118 | + viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9, 0.9], |
| 119 | + coulomb_scale=[0.8, 0.8, 0.7, 0.8, 0.8, 0.8], |
| 120 | + ), |
118 | 121 | ) |
119 | 122 | self.assertTrue(res.success) |
120 | 123 |
|
@@ -145,15 +148,19 @@ def test_invalid_viscous_array_length(self, tf_prefix): |
145 | 148 |
|
146 | 149 | # Too few elements |
147 | 150 | res = self._friction_model_interface.set_friction_model_parameters( |
148 | | - viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9], |
149 | | - coulomb_scale=[0.8, 0.8, 0.7, 0.8, 0.8, 0.8], |
| 151 | + parameters=FrictionModelParameters( |
| 152 | + viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9], |
| 153 | + coulomb_scale=[0.8, 0.8, 0.7, 0.8, 0.8, 0.8], |
| 154 | + ), |
150 | 155 | ) |
151 | 156 | self.assertFalse(res.success) |
152 | 157 |
|
153 | 158 | # Too many elements |
154 | 159 | res = self._friction_model_interface.set_friction_model_parameters( |
155 | | - viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9, 0.9, 0.9], |
156 | | - coulomb_scale=[0.8, 0.8, 0.7, 0.8, 0.8, 0.8], |
| 160 | + parameters=FrictionModelParameters( |
| 161 | + viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9, 0.9, 0.9], |
| 162 | + coulomb_scale=[0.8, 0.8, 0.7, 0.8, 0.8, 0.8], |
| 163 | + ), |
157 | 164 | ) |
158 | 165 | self.assertFalse(res.success) |
159 | 166 |
|
@@ -183,8 +190,10 @@ def test_invalid_coulomb_array_length(self, tf_prefix): |
183 | 190 | self._friction_model_interface = FrictionModelInterface(self.node) |
184 | 191 |
|
185 | 192 | res = self._friction_model_interface.set_friction_model_parameters( |
186 | | - viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9, 0.9], |
187 | | - coulomb_scale=[0.8, 0.8, 0.7], |
| 193 | + parameters=FrictionModelParameters( |
| 194 | + viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9, 0.9], |
| 195 | + coulomb_scale=[0.8, 0.8, 0.7], |
| 196 | + ), |
188 | 197 | ) |
189 | 198 | self.assertFalse(res.success) |
190 | 199 |
|
@@ -213,7 +222,9 @@ def test_set_friction_model_parameters_on_inactive_controller_fails(self, tf_pre |
213 | 222 | self._friction_model_interface = FrictionModelInterface(self.node) |
214 | 223 |
|
215 | 224 | res = self._friction_model_interface.set_friction_model_parameters( |
216 | | - viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9, 0.9], |
217 | | - coulomb_scale=[0.8, 0.8, 0.7, 0.8, 0.8, 0.8], |
| 225 | + parameters=FrictionModelParameters( |
| 226 | + viscous_scale=[0.9, 0.9, 0.8, 0.9, 0.9, 0.9], |
| 227 | + coulomb_scale=[0.8, 0.8, 0.7, 0.8, 0.8, 0.8], |
| 228 | + ), |
218 | 229 | ) |
219 | 230 | self.assertFalse(res.success) |
0 commit comments