@@ -156,7 +156,9 @@ controller_interface::CallbackReturn
156156ur_controllers::ForceModeController::on_deactivate (const rclcpp_lifecycle::State& /* previous_state*/ )
157157{
158158 // Stop force mode if this controller is deactivated.
159- command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value (1.0 );
159+ if (!command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value (1.0 )) {
160+ return LifecycleNodeInterface::CallbackReturn::ERROR;
161+ }
160162 return LifecycleNodeInterface::CallbackReturn::SUCCESS;
161163}
162164
@@ -175,54 +177,80 @@ controller_interface::return_type ur_controllers::ForceModeController::update(co
175177
176178 // Publish state of force_mode?
177179 if (change_requested_) {
180+ bool write_successful = true ;
178181 if (force_mode_active_) {
179182 const auto force_mode_parameters = force_mode_params_buffer_.readFromRT ();
180- command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X].set_value (force_mode_parameters->task_frame [0 ]);
181- command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Y].set_value (force_mode_parameters->task_frame [1 ]);
182- command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Z].set_value (force_mode_parameters->task_frame [2 ]);
183- command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RX].set_value (force_mode_parameters->task_frame [3 ]);
184- command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RY].set_value (force_mode_parameters->task_frame [4 ]);
185- command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RZ].set_value (force_mode_parameters->task_frame [5 ]);
186-
187- command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_X].set_value (
183+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X].set_value (
184+ force_mode_parameters->task_frame [0 ]);
185+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Y].set_value (
186+ force_mode_parameters->task_frame [1 ]);
187+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Z].set_value (
188+ force_mode_parameters->task_frame [2 ]);
189+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RX].set_value (
190+ force_mode_parameters->task_frame [3 ]);
191+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RY].set_value (
192+ force_mode_parameters->task_frame [4 ]);
193+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RZ].set_value (
194+ force_mode_parameters->task_frame [5 ]);
195+
196+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_X].set_value (
188197 force_mode_parameters->selection_vec [0 ]);
189- command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Y].set_value (
198+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Y].set_value (
190199 force_mode_parameters->selection_vec [1 ]);
191- command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Z].set_value (
200+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Z].set_value (
192201 force_mode_parameters->selection_vec [2 ]);
193- command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RX].set_value (
202+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RX].set_value (
194203 force_mode_parameters->selection_vec [3 ]);
195- command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RY].set_value (
204+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RY].set_value (
196205 force_mode_parameters->selection_vec [4 ]);
197- command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RZ].set_value (
206+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RZ].set_value (
198207 force_mode_parameters->selection_vec [5 ]);
199208
200- command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value (force_mode_parameters->wrench .force .x );
201- command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value (force_mode_parameters->wrench .force .y );
202- command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value (force_mode_parameters->wrench .force .z );
203- command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value (force_mode_parameters->wrench .torque .x );
204- command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value (force_mode_parameters->wrench .torque .y );
205- command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value (force_mode_parameters->wrench .torque .z );
206-
207- command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X].set_value (force_mode_parameters->limits [0 ]);
208- command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Y].set_value (force_mode_parameters->limits [1 ]);
209- command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Z].set_value (force_mode_parameters->limits [2 ]);
210- command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RX].set_value (force_mode_parameters->limits [3 ]);
211- command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RY].set_value (force_mode_parameters->limits [4 ]);
212- command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RZ].set_value (force_mode_parameters->limits [5 ]);
213-
214- command_interfaces_[CommandInterfaces::FORCE_MODE_TYPE].set_value (force_mode_parameters->type );
215- command_interfaces_[CommandInterfaces::FORCE_MODE_DAMPING].set_value (force_mode_parameters->damping_factor );
216- command_interfaces_[CommandInterfaces::FORCE_MODE_GAIN_SCALING].set_value (force_mode_parameters->gain_scaling );
209+ write_successful &=
210+ command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value (force_mode_parameters->wrench .force .x );
211+ write_successful &=
212+ command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value (force_mode_parameters->wrench .force .y );
213+ write_successful &=
214+ command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value (force_mode_parameters->wrench .force .z );
215+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value (
216+ force_mode_parameters->wrench .torque .x );
217+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value (
218+ force_mode_parameters->wrench .torque .y );
219+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value (
220+ force_mode_parameters->wrench .torque .z );
221+
222+ write_successful &=
223+ command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X].set_value (force_mode_parameters->limits [0 ]);
224+ write_successful &=
225+ command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Y].set_value (force_mode_parameters->limits [1 ]);
226+ write_successful &=
227+ command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Z].set_value (force_mode_parameters->limits [2 ]);
228+ write_successful &=
229+ command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RX].set_value (force_mode_parameters->limits [3 ]);
230+ write_successful &=
231+ command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RY].set_value (force_mode_parameters->limits [4 ]);
232+ write_successful &=
233+ command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RZ].set_value (force_mode_parameters->limits [5 ]);
234+
235+ write_successful &=
236+ command_interfaces_[CommandInterfaces::FORCE_MODE_TYPE].set_value (force_mode_parameters->type );
237+ write_successful &=
238+ command_interfaces_[CommandInterfaces::FORCE_MODE_DAMPING].set_value (force_mode_parameters->damping_factor );
239+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_GAIN_SCALING].set_value (
240+ force_mode_parameters->gain_scaling );
217241
218242 // Signal that we are waiting for confirmation that force mode is activated
219- command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value (ASYNC_WAITING);
243+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value (ASYNC_WAITING);
220244 async_state_ = ASYNC_WAITING;
221245 } else {
222- command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value (1.0 );
223- command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value (ASYNC_WAITING);
246+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value (1.0 );
247+ write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value (ASYNC_WAITING);
224248 async_state_ = ASYNC_WAITING;
225249 }
250+ if (!write_successful) {
251+ RCLCPP_ERROR (get_node ()->get_logger (), " Could not write to a command interfaces." );
252+ return controller_interface::return_type::ERROR;
253+ }
226254 change_requested_ = false ;
227255 }
228256
0 commit comments