Skip to content

Moveit launch setup

Yijiang Huang edited this page Jun 25, 2018 · 3 revisions

After we generate moveit pkg + ikfast plugin for our robot, we need to change a few places in the moveit launch file to make it work with Choreo, the files include:

  1. (modify) launch/<your robot>_moveit_controller_manager.launch.xml
  2. (modify) launch/moveit_planning_execution.launch
  3. (modify) launch/move_group.launch
  4. (add) config/controller.yaml

Optional: (modify) launch/move_group.launch (remove output="screen" from movegroup)


launch/moveit_planning_execution.launch:

check example code here.


launch/move_group.launch:

add this line to after :

  <!-- Planning pipeline, available options: ompl. chomp, stomp-->
  <arg name="planner" default="ompl"/>

and in Planning functionality, replace <arg name="pipeline" value="ompl"/> with <arg name="pipeline" value="$(arg planner)"/>.


launch/<your robot>_moveit_controller_manager.launch.xml:

<launch>
	<arg name="moveit_controller_manager"
		 default="moveit_simple_controller_manager/MoveItSimpleControllerManager"/>
	<param name="moveit_controller_manager"
		   value="$(arg moveit_controller_manager)"/>
	<rosparam file="$(find <your robot>_moveit_config)/config/controllers.yaml"/>
</launch>

controllers.yaml:

controller_list:
  - name: ""
    action_ns: joint_trajectory_action
    type: FollowJointTrajectory
    joints: [robot_joint_1, robot_joint_2, robot_joint_3, robot_joint_4, robot_joint_5, robot_joint_6]
Clone this wiki locally