@@ -334,10 +334,10 @@ std::vector<hardware_interface::StateInterface> URPositionHardwareInterface::exp
334334 hardware_interface::StateInterface (tf_prefix + TOOL_CONTACT_GPIO, " tool_contact_state" , &tool_contact_state_));
335335
336336 // Motion primitives stuff
337- state_interfaces.emplace_back (
338- hardware_interface::StateInterface (HW_IF_MOTION_PRIMITIVES, " execution_status" , &hw_moprim_states_[0 ]));
339- state_interfaces.emplace_back (
340- hardware_interface::StateInterface (HW_IF_MOTION_PRIMITIVES, " ready_for_new_primitive" , &hw_moprim_states_[1 ]));
337+ state_interfaces.emplace_back (hardware_interface::StateInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES,
338+ " execution_status" , &hw_moprim_states_[0 ]));
339+ state_interfaces.emplace_back (hardware_interface::StateInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES,
340+ " ready_for_new_primitive" , &hw_moprim_states_[1 ]));
341341
342342 return state_interfaces;
343343}
@@ -481,60 +481,60 @@ std::vector<hardware_interface::CommandInterface> URPositionHardwareInterface::e
481481
482482 // Motion primitives stuff
483483 // Command for motion type (motion_type)
484- command_interfaces.emplace_back (
485- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " motion_type" , &hw_moprim_commands_[0 ]));
484+ command_interfaces.emplace_back (hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES,
485+ " motion_type" , &hw_moprim_commands_[0 ]));
486486 // Joint position commands (q1, q2, ..., q6)
487487 command_interfaces.emplace_back (
488- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " q1" , &hw_moprim_commands_[1 ]));
488+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " q1" , &hw_moprim_commands_[1 ]));
489489 command_interfaces.emplace_back (
490- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " q2" , &hw_moprim_commands_[2 ]));
490+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " q2" , &hw_moprim_commands_[2 ]));
491491 command_interfaces.emplace_back (
492- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " q3" , &hw_moprim_commands_[3 ]));
492+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " q3" , &hw_moprim_commands_[3 ]));
493493 command_interfaces.emplace_back (
494- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " q4" , &hw_moprim_commands_[4 ]));
494+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " q4" , &hw_moprim_commands_[4 ]));
495495 command_interfaces.emplace_back (
496- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " q5" , &hw_moprim_commands_[5 ]));
496+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " q5" , &hw_moprim_commands_[5 ]));
497497 command_interfaces.emplace_back (
498- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " q6" , &hw_moprim_commands_[6 ]));
498+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " q6" , &hw_moprim_commands_[6 ]));
499499 // Position commands (pos_x, pos_y, pos_z, pos_qx, pos_qy, pos_qz, pos_qz)
500500 command_interfaces.emplace_back (
501- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_x" , &hw_moprim_commands_[7 ]));
501+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_x" , &hw_moprim_commands_[7 ]));
502502 command_interfaces.emplace_back (
503- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_y" , &hw_moprim_commands_[8 ]));
503+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_y" , &hw_moprim_commands_[8 ]));
504504 command_interfaces.emplace_back (
505- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_z" , &hw_moprim_commands_[9 ]));
505+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_z" , &hw_moprim_commands_[9 ]));
506506 command_interfaces.emplace_back (
507- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_qx" , &hw_moprim_commands_[10 ]));
507+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_qx" , &hw_moprim_commands_[10 ]));
508508 command_interfaces.emplace_back (
509- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_qy" , &hw_moprim_commands_[11 ]));
509+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_qy" , &hw_moprim_commands_[11 ]));
510510 command_interfaces.emplace_back (
511- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_qz" , &hw_moprim_commands_[12 ]));
511+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_qz" , &hw_moprim_commands_[12 ]));
512512 command_interfaces.emplace_back (
513- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_qw" , &hw_moprim_commands_[13 ]));
513+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_qw" , &hw_moprim_commands_[13 ]));
514514 // Via Position commands for circula motion
515515 command_interfaces.emplace_back (
516- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_via_x" , &hw_moprim_commands_[14 ]));
517- command_interfaces.emplace_back (
518- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_via_y" , &hw_moprim_commands_[15 ]));
519- command_interfaces.emplace_back (
520- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_via_z" , &hw_moprim_commands_[16 ]));
516+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_via_x" , &hw_moprim_commands_[14 ]));
521517 command_interfaces.emplace_back (
522- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_via_qx " , &hw_moprim_commands_[17 ]));
518+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_via_y " , &hw_moprim_commands_[15 ]));
523519 command_interfaces.emplace_back (
524- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_via_qy" , &hw_moprim_commands_[18 ]));
525- command_interfaces.emplace_back (
526- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_via_qz" , &hw_moprim_commands_[19 ]));
527- command_interfaces.emplace_back (
528- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " pos_via_qw" , &hw_moprim_commands_[20 ]));
520+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " pos_via_z" , &hw_moprim_commands_[16 ]));
521+ command_interfaces.emplace_back (hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES,
522+ " pos_via_qx" , &hw_moprim_commands_[17 ]));
523+ command_interfaces.emplace_back (hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES,
524+ " pos_via_qy" , &hw_moprim_commands_[18 ]));
525+ command_interfaces.emplace_back (hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES,
526+ " pos_via_qz" , &hw_moprim_commands_[19 ]));
527+ command_interfaces.emplace_back (hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES,
528+ " pos_via_qw" , &hw_moprim_commands_[20 ]));
529529 // Other command parameters (blend_radius, velocity, acceleration, move_time)
530+ command_interfaces.emplace_back (hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES,
531+ " blend_radius" , &hw_moprim_commands_[21 ]));
530532 command_interfaces.emplace_back (
531- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " blend_radius" , &hw_moprim_commands_[21 ]));
532- command_interfaces.emplace_back (
533- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " velocity" , &hw_moprim_commands_[22 ]));
534- command_interfaces.emplace_back (
535- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " acceleration" , &hw_moprim_commands_[23 ]));
533+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " velocity" , &hw_moprim_commands_[22 ]));
534+ command_interfaces.emplace_back (hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES,
535+ " acceleration" , &hw_moprim_commands_[23 ]));
536536 command_interfaces.emplace_back (
537- hardware_interface::CommandInterface (HW_IF_MOTION_PRIMITIVES, " move_time" , &hw_moprim_commands_[24 ]));
537+ hardware_interface::CommandInterface (tf_prefix + HW_IF_MOTION_PRIMITIVES, " move_time" , &hw_moprim_commands_[24 ]));
538538
539539 return command_interfaces;
540540}
@@ -1274,7 +1274,7 @@ hardware_interface::return_type URPositionHardwareInterface::prepare_command_mod
12741274 { tf_prefix + PASSTHROUGH_GPIO + " /setpoint_positions_" + std::to_string (i), PASSTHROUGH_GPIO },
12751275 { tf_prefix + FREEDRIVE_MODE_GPIO + " /async_success" , FREEDRIVE_MODE_GPIO },
12761276 { tf_prefix + TOOL_CONTACT_GPIO + " /tool_contact_set_state" , TOOL_CONTACT_GPIO },
1277- { HW_IF_MOTION_PRIMITIVES + " /motion_type" , HW_IF_MOTION_PRIMITIVES },
1277+ { tf_prefix + HW_IF_MOTION_PRIMITIVES + " /motion_type" , HW_IF_MOTION_PRIMITIVES },
12781278 };
12791279
12801280 for (auto & item : start_modes_to_check) {
0 commit comments