MoveIt Configs
The Trossen Arm MoveIt configuration package provides the necessary files to control the Trossen Arm using MoveIt.
Two different hardware interfaces are supported:
Mock Hardware: For testing and development purposes, simulating the arm’s behavior.
Real Hardware: For controlling the actual Trossen Arm hardware.
These interfaces can be swapped by changing the ros2_control_hardware_type
launch argument when launching the MoveIt package by switching between mock_components
and real
.
Usage
We will first cover how to launch MoveIt with a mocked Trossen Arm hardware interface and associated controllers.
source ~/ros2_ws/install/setup.bash
ros2 launch trossen_arm_moveit moveit.launch.py robot_model:=wxai ros2_control_hardware_type:=mock_components
This will start the MoveIt move_group
node, which is responsible for planning and executing motions for the Trossen Arm.
You can read more about what you can do with the node on the move_group node documentation page.
You can see the topics, services, and actions that are available by running:
ros2 node info /move_group
You will see output similar to the following:
/move_group
Subscribers:
/parameter_events: rcl_interfaces/msg/ParameterEvent
/trajectory_execution_event: std_msgs/msg/String
Publishers:
/display_contacts: visualization_msgs/msg/MarkerArray
/display_planned_path: moveit_msgs/msg/DisplayTrajectory
/motion_plan_request: moveit_msgs/msg/MotionPlanRequest
/parameter_events: rcl_interfaces/msg/ParameterEvent
/rosout: rcl_interfaces/msg/Log
Service Servers:
/apply_planning_scene: moveit_msgs/srv/ApplyPlanningScene
/check_state_validity: moveit_msgs/srv/GetStateValidity
/clear_octomap: std_srvs/srv/Empty
/compute_cartesian_path: moveit_msgs/srv/GetCartesianPath
/compute_fk: moveit_msgs/srv/GetPositionFK
/compute_ik: moveit_msgs/srv/GetPositionIK
/get_planner_params: moveit_msgs/srv/GetPlannerParams
/load_map: moveit_msgs/srv/LoadMap
/move_group/describe_parameters: rcl_interfaces/srv/DescribeParameters
/move_group/get_parameter_types: rcl_interfaces/srv/GetParameterTypes
/move_group/get_parameters: rcl_interfaces/srv/GetParameters
/move_group/list_parameters: rcl_interfaces/srv/ListParameters
/move_group/set_parameters: rcl_interfaces/srv/SetParameters
/move_group/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically
/plan_kinematic_path: moveit_msgs/srv/GetMotionPlan
/query_planner_interface: moveit_msgs/srv/QueryPlannerInterfaces
/save_map: moveit_msgs/srv/SaveMap
/set_planner_params: moveit_msgs/srv/SetPlannerParams
Service Clients:
Action Servers:
/execute_trajectory: moveit_msgs/action/ExecuteTrajectory
/move_action: moveit_msgs/action/MoveGroup
Action Clients:
You will also see that RViz has been launched with the Trossen Arm model displayed along with MoveIt’s MotionPlanning display and panel. These new components allow you to plan, execute, and visualize motions for the Trossen Arm.

Let’s start using it by planning a motion to the upright
configuration.
In the MotionPlanning panel, select the following:
Planning Group:
arm
Start State:
<current>
Goal State:
upright
You will notice that orange “Goal State Query” robot model update to reflect the
upright
configuration.Click the Plan button to generate a motion plan to the
upright
configuration. If planning is successful, you will see a translucent robot move from the current configuration to theupright
configuration.Click the Execute button to execute the planned motion. The robot should move to the
upright
configuration.You can also use the sphere, arrow, and ring markers to interactively set the goal state. Click on the sphere marker and drag it to a new position to change the goal state. Then click Plan and Execute to see the robot move to the new position.
You can now proceed to launch MoveIt with your real Trossen Arm hardware. Run the command below to launch MoveIt and repeat the steps above to plan and execute motions with the real hardware.
source ~/ros2_ws/install/setup.bash
ros2 launch trossen_arm_moveit moveit.launch.py robot_model:=wxai ros2_control_hardware_type:=real
To further customize the moveit launch file at runtime, refer to the table below, or run the command below
ros2 launch trossen_arm_moveit moveit.launch.py --show-args
Argument |
Description |
Default |
Choices |
---|---|---|---|
robot_model |
model type of the Trossen Arm. |
|
|
arm_variant |
End effector variant of the Trossen Arm. |
|
|
ip_address |
IP address of the robot to connect to. |
‘192.168.1.2’ |
|
ros2_control_hardware_type |
Use real or mocked hardware interface. |
|
|
use_moveit_rviz |
Launches RViz with MoveIt’s RViz configuration. |
|
|
rviz_config_file |
Full path to the RVIZ config file to use. |
LocalVar(‘FindPackageShare(pkg= |