Skip to content

Commit 227140e

Browse files
committed
pass full interface names to the controller (such as $(var tf_prefix)motion_primitive/q1)
1 parent a60acf5 commit 227140e

File tree

2 files changed

+64
-64
lines changed

2 files changed

+64
-64
lines changed

ur_robot_driver/config/ur_controllers.yaml

Lines changed: 27 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -195,31 +195,31 @@ tool_contact_controller:
195195
motion_primitive_forward_controller:
196196
ros__parameters:
197197
command_interfaces:
198-
- motion_type
199-
- q1
200-
- q2
201-
- q3
202-
- q4
203-
- q5
204-
- q6
205-
- pos_x
206-
- pos_y
207-
- pos_z
208-
- pos_qx
209-
- pos_qy
210-
- pos_qz
211-
- pos_qw
212-
- pos_via_x
213-
- pos_via_y
214-
- pos_via_z
215-
- pos_via_qx
216-
- pos_via_qy
217-
- pos_via_qz
218-
- pos_via_qw
219-
- blend_radius
220-
- velocity
221-
- acceleration
222-
- move_time
198+
- $(var tf_prefix)motion_primitive/motion_type
199+
- $(var tf_prefix)motion_primitive/q1
200+
- $(var tf_prefix)motion_primitive/q2
201+
- $(var tf_prefix)motion_primitive/q3
202+
- $(var tf_prefix)motion_primitive/q4
203+
- $(var tf_prefix)motion_primitive/q5
204+
- $(var tf_prefix)motion_primitive/q6
205+
- $(var tf_prefix)motion_primitive/pos_x
206+
- $(var tf_prefix)motion_primitive/pos_y
207+
- $(var tf_prefix)motion_primitive/pos_z
208+
- $(var tf_prefix)motion_primitive/pos_qx
209+
- $(var tf_prefix)motion_primitive/pos_qy
210+
- $(var tf_prefix)motion_primitive/pos_qz
211+
- $(var tf_prefix)motion_primitive/pos_qw
212+
- $(var tf_prefix)motion_primitive/pos_via_x
213+
- $(var tf_prefix)motion_primitive/pos_via_y
214+
- $(var tf_prefix)motion_primitive/pos_via_z
215+
- $(var tf_prefix)motion_primitive/pos_via_qx
216+
- $(var tf_prefix)motion_primitive/pos_via_qy
217+
- $(var tf_prefix)motion_primitive/pos_via_qz
218+
- $(var tf_prefix)motion_primitive/pos_via_qw
219+
- $(var tf_prefix)motion_primitive/blend_radius
220+
- $(var tf_prefix)motion_primitive/velocity
221+
- $(var tf_prefix)motion_primitive/acceleration
222+
- $(var tf_prefix)motion_primitive/move_time
223223
state_interfaces:
224-
- execution_status
225-
- ready_for_new_primitive
224+
- $(var tf_prefix)motion_primitive/execution_status
225+
- $(var tf_prefix)motion_primitive/ready_for_new_primitive

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 37 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -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

Comments
 (0)