Commit 43f3f26c authored by AndyZe's avatar AndyZe Committed by Miguel Prada
Browse files

Load the JointGroupPositionController so jog commands can be sent (#422)

* Load the JointGroupPositionController so jog commands can be sent

* Load new controllers for UR5/UR10, too

* Add other controllers in launch file

* Add JointGroupPositionController to UR e-series
parent 2665f4be
......@@ -19,3 +19,13 @@ arm_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
joint_group_position_controller:
type: position_controllers/JointGroupPositionController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
......@@ -19,3 +19,13 @@ arm_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
joint_group_position_controller:
type: position_controllers/JointGroupPositionController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
......@@ -19,3 +19,13 @@ arm_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
joint_group_position_controller:
type: position_controllers/JointGroupPositionController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
......@@ -21,7 +21,11 @@
<include file="$(find ur_e_gazebo)/launch/controller_utils.launch"/>
<!-- start this controller -->
<rosparam file="$(find ur_e_gazebo)/controller/arm_controller_ur10e.yaml" command="load"/>
<node name="arm_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller" respawn="false" output="screen"/>
<!-- load other controllers -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false" output="screen" args="load joint_group_position_controller" />
</launch>
......@@ -21,7 +21,11 @@
<include file="$(find ur_e_gazebo)/launch/controller_utils.launch"/>
<!-- start this controller -->
<rosparam file="$(find ur_e_gazebo)/controller/arm_controller_ur3e.yaml" command="load"/>
<node name="arm_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller" respawn="false" output="screen"/>
<!-- load other controllers -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false" output="screen" args="load joint_group_position_controller" />
</launch>
......@@ -21,7 +21,11 @@
<include file="$(find ur_e_gazebo)/launch/controller_utils.launch"/>
<!-- start this controller -->
<rosparam file="$(find ur_e_gazebo)/controller/arm_controller_ur5e.yaml" command="load"/>
<node name="arm_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller" respawn="false" output="screen"/>
<!-- load other controllers -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false" output="screen" args="load joint_group_position_controller" />
</launch>
......@@ -20,15 +20,16 @@
<buildtool_depend>catkin</buildtool_depend>
<test_depend>roslaunch</test_depend>
<run_depend>ur_e_description</run_depend>
<run_depend>gazebo_ros</run_depend>
<run_depend>gazebo_ros_control</run_depend>
<run_depend>controller_manager</run_depend>
<run_depend>effort_controllers</run_depend>
<run_depend>joint_state_controller</run_depend>
<run_depend>joint_trajectory_controller</run_depend>
<run_depend>effort_controllers</run_depend>
<run_depend>gazebo_ros</run_depend>
<run_depend>gazebo_ros_control</run_depend>
<run_depend>position_controllers</run_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>rostopic</run_depend>
<run_depend>controller_manager</run_depend>
<run_depend>ur_e_description</run_depend>
<export>
......
......@@ -19,3 +19,13 @@ arm_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
joint_group_position_controller:
type: position_controllers/JointGroupPositionController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
......@@ -19,3 +19,13 @@ arm_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
joint_group_position_controller:
type: position_controllers/JointGroupPositionController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
......@@ -19,3 +19,13 @@ arm_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
joint_group_position_controller:
type: position_controllers/JointGroupPositionController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
......@@ -21,7 +21,11 @@
<include file="$(find ur_gazebo)/launch/controller_utils.launch"/>
<!-- start this controller -->
<rosparam file="$(find ur_gazebo)/controller/arm_controller_ur10.yaml" command="load"/>
<node name="arm_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller" respawn="false" output="screen"/>
<!-- load other controllers -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false" output="screen" args="load joint_group_position_controller" />
</launch>
......@@ -21,7 +21,11 @@
<include file="$(find ur_gazebo)/launch/controller_utils.launch"/>
<!-- start this controller -->
<rosparam file="$(find ur_gazebo)/controller/arm_controller_ur3.yaml" command="load"/>
<node name="arm_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller" respawn="false" output="screen"/>
<!-- load other controllers -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false" output="screen" args="load joint_group_position_controller" />
</launch>
......@@ -21,7 +21,11 @@
<include file="$(find ur_gazebo)/launch/controller_utils.launch"/>
<!-- start this controller -->
<rosparam file="$(find ur_gazebo)/controller/arm_controller_ur5.yaml" command="load"/>
<node name="arm_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller" respawn="false" output="screen"/>
<!-- load other controllers -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false" output="screen" args="load joint_group_position_controller" />
</launch>
......@@ -20,16 +20,16 @@
<buildtool_depend>catkin</buildtool_depend>
<test_depend>roslaunch</test_depend>
<run_depend>ur_description</run_depend>
<run_depend>controller_manager</run_depend>
<run_depend>effort_controllers</run_depend>
<run_depend>gazebo_ros</run_depend>
<run_depend>gazebo_ros_control</run_depend>
<run_depend>joint_state_controller</run_depend>
<run_depend>joint_trajectory_controller</run_depend>
<run_depend>effort_controllers</run_depend>
<run_depend>position_controllers</run_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>rostopic</run_depend>
<run_depend>controller_manager</run_depend>
<run_depend>ur_description</run_depend>
<export>
</export>
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment