呼び出される順番
ファイルはpanda_moveit_configより引用。
demo.launchで起動したと仮定
demo.launch
<launch>
<!-- By default, we do not start a database (it can be large) -->
<arg name="db" default="false" />
<!-- Allow user to specify database location -->
<arg name="db_path" default="$(find panda_moveit_config)/default_warehouse_mongo_db" />
<!-- By default, we are not in debug mode -->
<arg name="debug" default="false" />
<arg name="pipeline" default="ompl" />
<!--
By default, hide joint_state_publisher's GUI
MoveIt!'s "demo" mode replaces the real robot driver with the joint_state_publisher.
The latter one maintains and publishes the current joint configuration of the simulated robot.
It also provides a GUI to move the simulated robot around "manually".
This corresponds to moving around the real robot without the use of MoveIt.
-->
<arg name="rviz_tutorial" default="false" />
<arg name="use_gui" default="false" />
<!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
<include file="$(find panda_moveit_config)/launch/planning_context.launch">
<arg name="load_robot_description" value="true"/>
</include>
<!-- If needed, broadcast static tf for robot root -->
<node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_1" args="0 0 0 0 0 0 world panda_link0" />
<!-- We do not have a robot connected, so publish fake joint states -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="/use_gui" value="$(arg use_gui)"/>
<rosparam param="/source_list">[/move_group/fake_controller_joint_states]</rosparam>
</node>
<node name="joint_state_desired_publisher" pkg="topic_tools" type="relay" args="joint_states joint_states_desired" />
<!-- Given the published joint states, publish tf for the robot links -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />
<!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
<include file="$(find panda_moveit_config)/launch/move_group.launch">
<arg name="allow_trajectory_execution" value="true"/>
<arg name="fake_execution" value="true"/>
<arg name="info" value="true"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="pipeline" value="$(arg pipeline)" />
</include>
<!-- Run Rviz -->
<include file="$(find panda_moveit_config)/launch/moveit_rviz.launch">
<arg name="rviz_tutorial" value="$(arg rviz_tutorial)"/>
<arg name="debug" value="$(arg debug)"/>
</include>
<!-- If database loading was enabled, start mongodb as well -->
<include file="$(find panda_moveit_config)/launch/default_warehouse_db.launch" if="$(arg db)">
<arg name="moveit_warehouse_database_path" value="$(arg db_path)"/>
</include>
</launch>
move_group.launchにfake_exectionのパラメタを渡している
move_group.launch
<launch>
<arg name="load_gripper" default="true" />
<include file="$(find panda_moveit_config)/launch/planning_context.launch">
<arg name="load_gripper" value="$(arg load_gripper)" />
</include>
<arg name="pipeline" default="ompl" />
<!-- GDB Debug Option -->
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix"
value="gdb -x $(find panda_moveit_config)/launch/gdb_settings.gdb --ex run --args" />
<!-- Verbose Mode Option -->
<arg name="info" default="$(arg debug)" />
<arg unless="$(arg info)" name="command_args" value="" />
<arg if="$(arg info)" name="command_args" value="--debug" />
<!-- move_group settings -->
<arg name="allow_trajectory_execution" default="true"/>
<arg name="fake_execution" default="false"/>
<arg name="max_safe_path_cost" default="1"/>
<arg name="jiggle_fraction" default="0.05" />
<arg name="publish_monitored_planning_scene" default="true"/>
<!-- Planning Functionality -->
<include ns="move_group" file="$(find panda_moveit_config)/launch/planning_pipeline.launch.xml">
<arg name="pipeline" value="$(arg pipeline)" />
</include>
<!-- Trajectory Execution Functionality -->
<include ns="move_group" file="$(find panda_moveit_config)/launch/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_manage_controllers" value="true" />
<arg name="moveit_controller_manager" value="panda" if="$(eval not arg('fake_execution') and not arg('load_gripper'))"/>
<arg name="moveit_controller_manager" value="panda_gripper" if="$(eval not arg('fake_execution') and arg('load_gripper'))"/>
<arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/>
</include>
<!-- Sensors Functionality -->
<include ns="move_group" file="$(find panda_moveit_config)/launch/sensor_manager.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_sensor_manager" value="panda" />
</include>
<!-- Start the actual move_group node/action server -->
<node name="move_group" launch-prefix="$(arg launch_prefix)" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen" args="$(arg command_args)">
<!-- Set the display variable, in case OpenGL code is used internally -->
<env name="DISPLAY" value="$(optenv DISPLAY :0)" />
<param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/>
<param name="max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
<param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
<!-- load these non-default MoveGroup capabilities -->
<!--
<param name="capabilities" value="
a_package/AwsomeMotionPlanningCapability
another_package/GraspPlanningPipeline
" />
-->
<!-- inhibit these default MoveGroup capabilities -->
<!--
<param name="disable_capabilities" value="
move_group/MoveGroupKinematicsService
move_group/ClearOctomapService
" />
-->
<!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot -->
<param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" />
<remap from="/joint_states" to="/joint_states_desired" />
</node>
</launch>
moveit_controller_manegerの値がfakeかpandaになる。
trajectory_execution.launch.xml
<launch>
<!-- This file makes it easy to include the settings for trajectory execution -->
<!-- Flag indicating whether MoveIt! is allowed to load/unload or switch controllers -->
<arg name="moveit_manage_controllers" default="true"/>
<param name="moveit_manage_controllers" value="$(arg moveit_manage_controllers)"/>
<!-- When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution -->
<param name="trajectory_execution/allowed_execution_duration_scaling" value="1.2"/> <!-- default 1.2 -->
<!-- Allow more than the expected execution time before triggering a trajectory cancel (applied after scaling) -->
<param name="trajectory_execution/allowed_goal_duration_margin" value="0.5"/> <!-- default 0.5 -->
<!-- Allowed joint-value tolerance for validation that trajectory's first point matches current robot state -->
<param name="trajectory_execution/allowed_start_tolerance" value="0.01"/> <!-- default 0.01 -->
<!-- Load the robot specific controller manager; this sets the moveit_controller_manager ROS parameter -->
<arg name="moveit_controller_manager" default="panda" />
<include file="$(find panda_moveit_config)/launch/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" />
</launch>
fake_moveit_controller_manager.launch.xmlかpanda_moveit_controller_manager.launch.xmlを呼び出す。
fake_moveit_controller_manager.launch.xml
<launch>
<!-- Set the param that trajectory_execution_manager needs to find the controller plugin -->
<param name="moveit_controller_manager" value="moveit_fake_controller_manager/MoveItFakeControllerManager"/>
<!-- The rest of the params are specific to this plugin -->
<rosparam file="$(find panda_moveit_config)/config/fake_controllers.yaml"/>
</launch>
panda_moveit_controller_manager.launch.xml
<launch>
<!-- Set the param that trajectory_execution_manager needs to find the controller plugin -->
<arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
<!-- load controller_list -->
<rosparam file="$(find panda_moveit_config)/config/panda_controllers.yaml"/>
</launch>
設定の二つのyamlファイルは以下の通り
fake_controllers.yaml
controller_list:
- name: fake_panda_arm_controller
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
- name: fake_hand_controller
joints:
- panda_finger_joint1
- panda_finger_joint2
initial:
- group: panda_arm
pose: ready
- group: hand
pose: open
panda_controllers.yaml
controller_list:
- name: position_joint_trajectory_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
MoveItFakeControllerManagerとは
- 実機を使わずにRVizで表示させたときに便利なコントローラ。使用する際にはfake_controllerの中身を変更する必要がありそう。[参考] (http://docs.ros.org/en/melodic/api/moveit_tutorials/html/doc/fake_controller_manager/fake_controller_manager_tutorial.html)
- interpolate、via points、last pointのtypeから指定する
For configuration, edit the file config/fake_controllers.yaml, and adjust the desired controller type. The following controllers are available:
fake_controller.yaml
rate: 10 (Hz, used for interpolation controller)
controller_list:
- name: fake_arm_controller
type: interpolate | via points | last point
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
- name: fake_gripper_controller
joints:
[]