Skip to content
Snippets Groups Projects
Commit c38a59af authored by Robert Haschke's avatar Robert Haschke
Browse files

Load ROS controllers

- Provide a transmission argument to switch between position, velocity, and effort controllers
- Implements https://github.com/frankaemika/franka_ros/pull/186#issuecomment-965338478
parent ce87ceb4
No related branches found
No related tags found
No related merge requests found
controller_list:
- name: joint_trajectory_controller
- name: $(arg transmission)_joint_trajectory_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: True
......@@ -17,4 +17,3 @@ controller_list:
default: True
joints:
- panda_finger_joint1
......@@ -21,6 +21,8 @@
<arg name="moveit_controller_manager" default="fake" />
<!-- Set execution mode for fake execution controllers -->
<arg name="fake_execution_type" default="interpolate" />
<!-- Transmission used for joint control: position, velocity, or effort -->
<arg name="transmission" />
<!-- By default, hide joint_state_publisher's GUI in 'fake' controller_manager mode -->
<arg name="use_gui" default="false" />
......@@ -50,15 +52,9 @@
</group>
<!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
<include file="$(dirname)/move_group.launch">
<arg name="allow_trajectory_execution" value="true"/>
<arg name="moveit_controller_manager" value="$(arg moveit_controller_manager)" />
<arg name="fake_execution_type" value="$(arg fake_execution_type)"/>
<arg name="info" value="true"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="pipeline" value="$(arg pipeline)"/>
<arg name="load_gripper" value="$(arg load_gripper)"/>
<arg name="load_robot_description" value="$(arg load_robot_description)"/>
<include file="$(dirname)/move_group.launch" pass_all_args="true">
<arg name="allow_trajectory_execution" value="true" />
<arg name="info" value="true" />
</include>
<!-- Run Rviz and load the default config to see the state of the move_group node -->
......
......@@ -14,7 +14,7 @@
<include file="$(find franka_gazebo)/launch/panda.launch" pass_all_args="true">
<arg name="headless" value="$(eval not arg('gazebo_gui'))" />
<arg name="use_gripper" default="$(arg load_gripper)" />
<arg name="controller" default="joint_trajectory_controller" />
<arg name="controller" default="$(arg transmission)_joint_trajectory_controller" />
</include>
<include file="$(dirname)/demo.launch" pass_all_args="true">
......
......@@ -2,9 +2,8 @@
<launch>
<!-- Launch real-robot control -->
<include file="$(find franka_control)/launch/franka_control.launch" pass_all_args="true" />
<!-- Load joint-trajectory controller into ROS controller_manager -->
<node name="trajectory_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="joint_trajectory_controller" />
<!-- By default use joint position controllers -->
<arg name="transmission" default="position" />
<!-- as well as MoveIt demo -->
<include file="$(dirname)/demo.launch" pass_all_args="true">
......
......@@ -74,10 +74,8 @@
</group>
<!-- Trajectory Execution Functionality -->
<include ns="move_group" file="$(dirname)/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)">
<include ns="move_group" file="$(dirname)/trajectory_execution.launch.xml" pass_all_args="true" if="$(arg allow_trajectory_execution)">
<arg name="moveit_manage_controllers" value="true" />
<arg name="moveit_controller_manager" value="$(arg moveit_controller_manager)" />
<arg name="fake_execution_type" value="$(arg fake_execution_type)" />
</include>
<!-- Sensors Functionality -->
......
......@@ -4,8 +4,7 @@
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find panda_moveit_config)/config/ros_controllers.yaml" command="load"/>
<!-- Load the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" args="franka_gripper "/>
<!-- Load and start the controllers -->
<node ns="/" name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen"
args="$(arg transmission)_joint_trajectory_controller franka_gripper" />
</launch>
......@@ -3,6 +3,7 @@
<param name="moveit_controller_manager" value="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
<!-- Load controller list to the parameter server -->
<rosparam file="$(find panda_moveit_config)/config/simple_moveit_controllers.yaml" />
<rosparam file="$(find panda_moveit_config)/config/ros_controllers.yaml" />
<rosparam subst_value="true" file="$(find panda_moveit_config)/config/simple_moveit_controllers.yaml" />
<!-- Start ROS controllers -->
<include file="$(dirname)/ros_controllers.launch" pass_all_args="true" />
</launch>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment