Skip to content

Commit e0d43f7

Browse files
committed
Resolve conflicts
1 parent e58ce47 commit e0d43f7

File tree

8 files changed

+85
-354
lines changed

8 files changed

+85
-354
lines changed

ur_bringup/config/ur_controllers.yaml

Lines changed: 77 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -24,35 +24,51 @@ controller_manager:
2424
forward_position_controller:
2525
type: position_controllers/JointGroupPositionController
2626

27+
tcp_pose_broadcaster:
28+
type: pose_broadcaster/PoseBroadcaster
29+
30+
passthrough_trajectory_controller:
31+
type: ur_controllers/PassthroughTrajectoryController
32+
33+
ur_configuration_controller:
34+
type: ur_controllers/URConfigurationController
2735

2836
speed_scaling_state_broadcaster:
2937
ros__parameters:
3038
state_publish_rate: 100.0
39+
tf_prefix: "$(var tf_prefix)"
40+
41+
io_and_status_controller:
42+
ros__parameters:
43+
tf_prefix: "$(var tf_prefix)"
3144

45+
ur_configuration_controller:
46+
ros__parameters:
47+
tf_prefix: "$(var tf_prefix)"
3248

3349
force_torque_sensor_broadcaster:
3450
ros__parameters:
35-
sensor_name: tcp_fts_sensor
51+
sensor_name: $(var tf_prefix)tcp_fts_sensor
3652
state_interface_names:
3753
- force.x
3854
- force.y
3955
- force.z
4056
- torque.x
4157
- torque.y
4258
- torque.z
43-
frame_id: tool0
59+
frame_id: $(var tf_prefix)tool0
4460
topic_name: ft_data
4561

4662

4763
joint_trajectory_controller:
4864
ros__parameters:
4965
joints:
50-
- shoulder_pan_joint
51-
- shoulder_lift_joint
52-
- elbow_joint
53-
- wrist_1_joint
54-
- wrist_2_joint
55-
- wrist_3_joint
66+
- $(var tf_prefix)shoulder_pan_joint
67+
- $(var tf_prefix)shoulder_lift_joint
68+
- $(var tf_prefix)elbow_joint
69+
- $(var tf_prefix)wrist_1_joint
70+
- $(var tf_prefix)wrist_2_joint
71+
- $(var tf_prefix)wrist_3_joint
5672
command_interfaces:
5773
- position
5874
state_interfaces:
@@ -64,23 +80,23 @@ joint_trajectory_controller:
6480
constraints:
6581
stopped_velocity_tolerance: 0.2
6682
goal_time: 0.0
67-
shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
68-
shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
69-
elbow_joint: { trajectory: 0.2, goal: 0.1 }
70-
wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
71-
wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
72-
wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
83+
$(var tf_prefix)shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
84+
$(var tf_prefix)shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
85+
$(var tf_prefix)elbow_joint: { trajectory: 0.2, goal: 0.1 }
86+
$(var tf_prefix)wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
87+
$(var tf_prefix)wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
88+
$(var tf_prefix)wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
7389

7490

7591
scaled_joint_trajectory_controller:
7692
ros__parameters:
7793
joints:
78-
- shoulder_pan_joint
79-
- shoulder_lift_joint
80-
- elbow_joint
81-
- wrist_1_joint
82-
- wrist_2_joint
83-
- wrist_3_joint
94+
- $(var tf_prefix)shoulder_pan_joint
95+
- $(var tf_prefix)shoulder_lift_joint
96+
- $(var tf_prefix)elbow_joint
97+
- $(var tf_prefix)wrist_1_joint
98+
- $(var tf_prefix)wrist_2_joint
99+
- $(var tf_prefix)wrist_3_joint
84100
command_interfaces:
85101
- position
86102
state_interfaces:
@@ -92,30 +108,53 @@ scaled_joint_trajectory_controller:
92108
constraints:
93109
stopped_velocity_tolerance: 0.2
94110
goal_time: 0.0
95-
shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
96-
shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
97-
elbow_joint: { trajectory: 0.2, goal: 0.1 }
98-
wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
99-
wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
100-
wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
111+
$(var tf_prefix)shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
112+
$(var tf_prefix)shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
113+
$(var tf_prefix)elbow_joint: { trajectory: 0.2, goal: 0.1 }
114+
$(var tf_prefix)wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
115+
$(var tf_prefix)wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
116+
$(var tf_prefix)wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
117+
speed_scaling_interface_name: $(var tf_prefix)speed_scaling/speed_scaling_factor
118+
119+
passthrough_trajectory_controller:
120+
ros__parameters:
121+
tf_prefix: "$(var tf_prefix)"
122+
joints:
123+
- $(var tf_prefix)shoulder_pan_joint
124+
- $(var tf_prefix)shoulder_lift_joint
125+
- $(var tf_prefix)elbow_joint
126+
- $(var tf_prefix)wrist_1_joint
127+
- $(var tf_prefix)wrist_2_joint
128+
- $(var tf_prefix)wrist_3_joint
129+
state_interfaces:
130+
- position
131+
- velocity
132+
speed_scaling_interface_name: $(var tf_prefix)speed_scaling/speed_scaling_factor
101133

102134
forward_velocity_controller:
103135
ros__parameters:
104136
joints:
105-
- shoulder_pan_joint
106-
- shoulder_lift_joint
107-
- elbow_joint
108-
- wrist_1_joint
109-
- wrist_2_joint
110-
- wrist_3_joint
137+
- $(var tf_prefix)shoulder_pan_joint
138+
- $(var tf_prefix)shoulder_lift_joint
139+
- $(var tf_prefix)elbow_joint
140+
- $(var tf_prefix)wrist_1_joint
141+
- $(var tf_prefix)wrist_2_joint
142+
- $(var tf_prefix)wrist_3_joint
111143
interface_name: velocity
112144

113145
forward_position_controller:
114146
ros__parameters:
115147
joints:
116-
- shoulder_pan_joint
117-
- shoulder_lift_joint
118-
- elbow_joint
119-
- wrist_1_joint
120-
- wrist_2_joint
121-
- wrist_3_joint
148+
- $(var tf_prefix)shoulder_pan_joint
149+
- $(var tf_prefix)shoulder_lift_joint
150+
- $(var tf_prefix)elbow_joint
151+
- $(var tf_prefix)wrist_1_joint
152+
- $(var tf_prefix)wrist_2_joint
153+
- $(var tf_prefix)wrist_3_joint
154+
155+
tcp_pose_broadcaster:
156+
ros__parameters:
157+
frame_id: $(var tf_prefix)base
158+
pose_name: $(var tf_prefix)tcp_pose
159+
tf:
160+
child_frame_id: $(var tf_prefix)tool0_controller

ur_controllers/src/passthrough_trajectory_controller.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -327,7 +327,7 @@ controller_interface::return_type PassthroughTrajectoryController::update(const
327327
scaling_factor_ = scaling_state_interface_->get().get_value();
328328
}
329329

330-
active_trajectory_elapsed_time_ += period * scaling_factor_;
330+
active_trajectory_elapsed_time_ = active_trajectory_elapsed_time_ + (period * scaling_factor_);
331331

332332
// RCLCPP_INFO(get_node()->get_logger(), "Elapsed trajectory time: %f. Scaling factor: %f, period: %f",
333333
// active_trajectory_elapsed_time_.seconds(), scaling_factor_, period.seconds());
@@ -356,7 +356,7 @@ rclcpp_action::GoalResponse PassthroughTrajectoryController::goal_received_callb
356356
{
357357
RCLCPP_INFO(get_node()->get_logger(), "Received new trajectory.");
358358
// Precondition: Running controller
359-
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
359+
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
360360
RCLCPP_ERROR(get_node()->get_logger(), "Can't accept new trajectories. Controller is not running.");
361361
return rclcpp_action::GoalResponse::REJECT;
362362
}

ur_robot_driver/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -156,6 +156,7 @@ ament_python_install_package(${PROJECT_NAME})
156156
# Install Python executables
157157
install(PROGRAMS
158158
scripts/tool_communication.py
159+
scripts/example_move.py
159160
DESTINATION lib/${PROJECT_NAME}
160161
)
161162

ur_robot_driver/config/ur_controllers.yaml

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -24,20 +24,12 @@ controller_manager:
2424
forward_position_controller:
2525
type: position_controllers/JointGroupPositionController
2626

27-
<<<<<<< HEAD
2827
tcp_pose_broadcaster:
2928
type: pose_broadcaster/PoseBroadcaster
3029

31-
=======
32-
<<<<<<< HEAD
33-
=======
3430
passthrough_trajectory_controller:
3531
type: ur_controllers/PassthroughTrajectoryController
36-
tcp_pose_broadcaster:
37-
type: pose_broadcaster/PoseBroadcaster
3832

39-
>>>>>>> ca5fb3e (Add trajectory passthrough controller (#944))
40-
>>>>>>> f0879d8 (Add trajectory passthrough controller (#944))
4133
ur_configuration_controller:
4234
type: ur_controllers/URConfigurationController
4335

ur_robot_driver/launch/ur_control.launch.py

Lines changed: 0 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -342,9 +342,6 @@ def controller_spawner(controllers, active=True):
342342
"tcp_pose_broadcaster",
343343
"ur_configuration_controller",
344344
]
345-
<<<<<<< HEAD
346-
controllers_inactive = ["forward_position_controller"]
347-
=======
348345
controllers_inactive = [
349346
"scaled_joint_trajectory_controller",
350347
"joint_trajectory_controller",
@@ -355,39 +352,11 @@ def controller_spawner(controllers, active=True):
355352
if activate_joint_controller.perform(context) == "true":
356353
controllers_active.append(initial_joint_controller.perform(context))
357354
controllers_inactive.remove(initial_joint_controller.perform(context))
358-
>>>>>>> ca5fb3e (Add trajectory passthrough controller (#944))
359355

360356
controller_spawners = [controller_spawner(controllers_active)] + [
361357
controller_spawner(controllers_inactive, active=False)
362358
]
363359

364-
# There may be other controllers of the joints, but this is the initially-started one
365-
initial_joint_controller_spawner_started = Node(
366-
package="controller_manager",
367-
executable="spawner",
368-
arguments=[
369-
initial_joint_controller,
370-
"-c",
371-
"/controller_manager",
372-
"--controller-manager-timeout",
373-
controller_spawner_timeout,
374-
],
375-
condition=IfCondition(activate_joint_controller),
376-
)
377-
initial_joint_controller_spawner_stopped = Node(
378-
package="controller_manager",
379-
executable="spawner",
380-
arguments=[
381-
initial_joint_controller,
382-
"-c",
383-
"/controller_manager",
384-
"--controller-manager-timeout",
385-
controller_spawner_timeout,
386-
"--inactive",
387-
],
388-
condition=UnlessCondition(activate_joint_controller),
389-
)
390-
391360
nodes_to_start = [
392361
control_node,
393362
ur_control_node,
@@ -397,8 +366,6 @@ def controller_spawner(controllers, active=True):
397366
urscript_interface,
398367
robot_state_publisher_node,
399368
rviz_node,
400-
initial_joint_controller_spawner_stopped,
401-
initial_joint_controller_spawner_started,
402369
] + controller_spawners
403370

404371
return nodes_to_start
@@ -527,16 +494,13 @@ def generate_launch_description():
527494
DeclareLaunchArgument(
528495
"initial_joint_controller",
529496
default_value="scaled_joint_trajectory_controller",
530-
<<<<<<< HEAD
531-
=======
532497
choices=[
533498
"scaled_joint_trajectory_controller",
534499
"joint_trajectory_controller",
535500
"forward_velocity_controller",
536501
"forward_position_controller",
537502
"passthrough_trajectory_controller",
538503
],
539-
>>>>>>> ca5fb3e (Add trajectory passthrough controller (#944))
540504
description="Initially loaded robot controller.",
541505
)
542506
)

ur_robot_driver/scripts/example_move.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -48,24 +48,24 @@
4848
"traj0": [
4949
{
5050
"positions": [0.043128, -1.28824, 1.37179, -1.82208, -1.63632, -0.18],
51-
"velocities": [0, 0, 0, 0, 0, 0],
51+
"velocities": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
5252
"time_from_start": Duration(sec=4, nanosec=0),
5353
},
5454
{
5555
"positions": [-0.195016, -1.70093, 0.902027, -0.944217, -1.52982, -0.195171],
56-
"velocities": [0, 0, 0, 0, 0, 0],
56+
"velocities": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
5757
"time_from_start": Duration(sec=8, nanosec=0),
5858
},
5959
],
6060
"traj1": [
6161
{
6262
"positions": [-0.195016, -1.70094, 0.902027, -0.944217, -1.52982, -0.195171],
63-
"velocities": [0, 0, 0, 0, 0, 0],
63+
"velocities": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
6464
"time_from_start": Duration(sec=0, nanosec=0),
6565
},
6666
{
6767
"positions": [0.30493, -0.982258, 0.955637, -1.48215, -1.72737, 0.204445],
68-
"velocities": [0, 0, 0, 0, 0, 0],
68+
"velocities": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
6969
"time_from_start": Duration(sec=8, nanosec=0),
7070
},
7171
],

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -900,7 +900,7 @@ hardware_interface::return_type URPositionHardwareInterface::prepare_command_mod
900900

901901
if (!std::all_of(start_modes_.begin() + 1, start_modes_.end(),
902902
[&](const std::string& other) { return other == start_modes_[0]; })) {
903-
RCLCPP_ERROR(get_logger(), "Start modes of all joints have to be the same.");
903+
RCLCPP_ERROR(rclcpp::get_logger("URPositionHardwareInterface"), "Start modes of all joints have to be the same.");
904904
return hardware_interface::return_type::ERROR;
905905
}
906906

0 commit comments

Comments
 (0)