@@ -254,6 +254,58 @@ std::vector<hardware_interface::CommandInterface> URPositionHardwareInterface::e
254254 command_interfaces.emplace_back (
255255 hardware_interface::CommandInterface (" payload" , " payload_async_success" , &payload_async_success_));
256256
257+ command_interfaces.emplace_back (
258+ hardware_interface::CommandInterface (" force_mode" , " task_frame_x" , &force_mode_task_frame_[0 ]));
259+ command_interfaces.emplace_back (
260+ hardware_interface::CommandInterface (" force_mode" , " task_frame_y" , &force_mode_task_frame_[1 ]));
261+ command_interfaces.emplace_back (
262+ hardware_interface::CommandInterface (" force_mode" , " task_frame_z" , &force_mode_task_frame_[2 ]));
263+ command_interfaces.emplace_back (
264+ hardware_interface::CommandInterface (" force_mode" , " task_frame_rx" , &force_mode_task_frame_[3 ]));
265+ command_interfaces.emplace_back (
266+ hardware_interface::CommandInterface (" force_mode" , " task_frame_ry" , &force_mode_task_frame_[4 ]));
267+ command_interfaces.emplace_back (
268+ hardware_interface::CommandInterface (" force_mode" , " task_frame_rz" , &force_mode_task_frame_[5 ]));
269+ command_interfaces.emplace_back (
270+ hardware_interface::CommandInterface (" force_mode" , " selection_vector_x" , &force_mode_selection_vector_[0 ]));
271+ command_interfaces.emplace_back (
272+ hardware_interface::CommandInterface (" force_mode" , " selection_vector_y" , &force_mode_selection_vector_[1 ]));
273+ command_interfaces.emplace_back (
274+ hardware_interface::CommandInterface (" force_mode" , " selection_vector_z" , &force_mode_selection_vector_[2 ]));
275+ command_interfaces.emplace_back (
276+ hardware_interface::CommandInterface (" force_mode" , " selection_vector_rx" , &force_mode_selection_vector_[3 ]));
277+ command_interfaces.emplace_back (
278+ hardware_interface::CommandInterface (" force_mode" , " selection_vector_ry" , &force_mode_selection_vector_[4 ]));
279+ command_interfaces.emplace_back (
280+ hardware_interface::CommandInterface (" force_mode" , " selection_vector_rz" , &force_mode_selection_vector_[5 ]));
281+ command_interfaces.emplace_back (
282+ hardware_interface::CommandInterface (" force_mode" , " wrench_x" , &force_mode_wrench_[0 ]));
283+ command_interfaces.emplace_back (
284+ hardware_interface::CommandInterface (" force_mode" , " wrench_y" , &force_mode_wrench_[1 ]));
285+ command_interfaces.emplace_back (
286+ hardware_interface::CommandInterface (" force_mode" , " wrench_z" , &force_mode_wrench_[2 ]));
287+ command_interfaces.emplace_back (
288+ hardware_interface::CommandInterface (" force_mode" , " wrench_rx" , &force_mode_wrench_[3 ]));
289+ command_interfaces.emplace_back (
290+ hardware_interface::CommandInterface (" force_mode" , " wrench_ry" , &force_mode_wrench_[4 ]));
291+ command_interfaces.emplace_back (
292+ hardware_interface::CommandInterface (" force_mode" , " wrench_rz" , &force_mode_wrench_[5 ]));
293+ command_interfaces.emplace_back (hardware_interface::CommandInterface (" force_mode" , " type" , &force_mode_type_));
294+ command_interfaces.emplace_back (
295+ hardware_interface::CommandInterface (" force_mode" , " limits_x" , &force_mode_limits_[0 ]));
296+ command_interfaces.emplace_back (
297+ hardware_interface::CommandInterface (" force_mode" , " limits_y" , &force_mode_limits_[1 ]));
298+ command_interfaces.emplace_back (
299+ hardware_interface::CommandInterface (" force_mode" , " limits_z" , &force_mode_limits_[2 ]));
300+ command_interfaces.emplace_back (
301+ hardware_interface::CommandInterface (" force_mode" , " limits_rx" , &force_mode_limits_[3 ]));
302+ command_interfaces.emplace_back (
303+ hardware_interface::CommandInterface (" force_mode" , " limits_ry" , &force_mode_limits_[4 ]));
304+ command_interfaces.emplace_back (
305+ hardware_interface::CommandInterface (" force_mode" , " limits_rz" , &force_mode_limits_[5 ]));
306+ command_interfaces.emplace_back (
307+ hardware_interface::CommandInterface (" force_mode" , " force_mode_async_success" , &force_mode_async_success_));
308+
257309 for (size_t i = 0 ; i < 18 ; ++i) {
258310 command_interfaces.emplace_back (hardware_interface::CommandInterface (
259311 " gpio" , " standard_digital_output_cmd_" + std::to_string (i), &standard_dig_out_bits_cmd_[i]));
@@ -596,6 +648,14 @@ void URPositionHardwareInterface::initAsyncIO()
596648
597649 payload_mass_ = NO_NEW_CMD_;
598650 payload_center_of_gravity_ = { NO_NEW_CMD_, NO_NEW_CMD_, NO_NEW_CMD_ };
651+
652+ for (size_t i = 0 ; i < 6 ; i++) {
653+ force_mode_task_frame_[i] = NO_NEW_CMD_;
654+ force_mode_selection_vector_[i] = static_cast <uint32_t >(NO_NEW_CMD_);
655+ force_mode_wrench_[i] = NO_NEW_CMD_;
656+ force_mode_limits_[i] = NO_NEW_CMD_;
657+ }
658+ force_mode_type_ = static_cast <unsigned int >(NO_NEW_CMD_);
599659}
600660
601661void URPositionHardwareInterface::checkAsyncIO ()
@@ -656,6 +716,24 @@ void URPositionHardwareInterface::checkAsyncIO()
656716 payload_mass_ = NO_NEW_CMD_;
657717 payload_center_of_gravity_ = { NO_NEW_CMD_, NO_NEW_CMD_, NO_NEW_CMD_ };
658718 }
719+
720+ if (!std::isnan (force_mode_task_frame_[0 ]) && !std::isnan (force_mode_selection_vector_[0 ]) &&
721+ !std::isnan (force_mode_wrench_[0 ]) && !std::isnan (force_mode_type_) && !std::isnan (force_mode_limits_[0 ]) &&
722+ ur_driver_ != nullptr ) {
723+ urcl::vector6uint32_t force_mode_selection_vector;
724+ for (size_t i = 0 ; i < 6 ; i++) {
725+ force_mode_selection_vector[i] = force_mode_selection_vector_[i];
726+ }
727+ force_mode_async_success_ = ur_driver_->startForceMode (force_mode_task_frame_, force_mode_selection_vector,
728+ force_mode_wrench_, force_mode_type_, force_mode_limits_);
729+ for (size_t i = 0 ; i < 6 ; i++) {
730+ force_mode_task_frame_[i] = NO_NEW_CMD_;
731+ force_mode_selection_vector_[i] = static_cast <uint32_t >(NO_NEW_CMD_);
732+ force_mode_wrench_[i] = NO_NEW_CMD_;
733+ force_mode_limits_[i] = NO_NEW_CMD_;
734+ }
735+ force_mode_type_ = static_cast <unsigned int >(NO_NEW_CMD_);
736+ }
659737}
660738
661739void URPositionHardwareInterface::updateNonDoubleValues ()
0 commit comments