Browse Source

Port stretch_moveit_config

feature/ros2_diffdrive
JafarAbdi 3 years ago
parent
commit
462615fa0c
24 changed files with 892 additions and 431 deletions
  1. +6
    -6
      stretch_moveit_config/CMakeLists.txt
  2. +24
    -0
      stretch_moveit_config/config/gripper.ros2_control.xacro
  3. +23
    -0
      stretch_moveit_config/config/moveit_simple_controllers.yaml
  4. +19
    -40
      stretch_moveit_config/config/ros_controllers.yaml
  5. +14
    -0
      stretch_moveit_config/config/stretch.xacro
  6. +44
    -0
      stretch_moveit_config/config/stretch_arm.ros2_control.xacro
  7. +0
    -21
      stretch_moveit_config/launch/chomp_planning_pipeline.launch.xml
  8. +0
    -15
      stretch_moveit_config/launch/default_warehouse_db.launch
  9. +0
    -65
      stretch_moveit_config/launch/demo.launch
  10. +132
    -0
      stretch_moveit_config/launch/demo.launch.py
  11. +0
    -9
      stretch_moveit_config/launch/fake_moveit_controller_manager.launch.xml
  12. +0
    -82
      stretch_moveit_config/launch/move_group.launch
  13. +624
    -41
      stretch_moveit_config/launch/moveit.rviz
  14. +0
    -15
      stretch_moveit_config/launch/moveit_rviz.launch
  15. +0
    -25
      stretch_moveit_config/launch/ompl_planning_pipeline.launch.xml
  16. +0
    -25
      stretch_moveit_config/launch/planning_context.launch
  17. +0
    -10
      stretch_moveit_config/launch/planning_pipeline.launch.xml
  18. +0
    -11
      stretch_moveit_config/launch/ros_controllers.launch
  19. +0
    -10
      stretch_moveit_config/launch/stretch_description_moveit_controller_manager.launch.xml
  20. +0
    -3
      stretch_moveit_config/launch/stretch_description_moveit_sensor_manager.launch.xml
  21. +0
    -20
      stretch_moveit_config/launch/trajectory_execution.launch.xml
  22. +0
    -15
      stretch_moveit_config/launch/warehouse.launch
  23. +0
    -16
      stretch_moveit_config/launch/warehouse_settings.launch.xml
  24. +6
    -2
      stretch_moveit_config/package.xml

+ 6
- 6
stretch_moveit_config/CMakeLists.txt View File

@ -1,10 +1,10 @@
cmake_minimum_required(VERSION 3.1.3)
cmake_minimum_required(VERSION 3.10.2)
project(stretch_moveit_config)
find_package(catkin REQUIRED)
find_package(ament_cmake REQUIRED)
catkin_package()
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}
PATTERN "setup_assistant.launch" EXCLUDE)
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
ament_package()

+ 24
- 0
stretch_moveit_config/config/gripper.ros2_control.xacro View File

@ -0,0 +1,24 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="gripper_ros2_control" params="name">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>fake_joint_driver/FakeJointDriver</plugin>
</hardware>
<joint name="joint_gripper_finger_left">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
</joint>
<joint name="joint_gripper_finger_right">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>

+ 23
- 0
stretch_moveit_config/config/moveit_simple_controllers.yaml View File

@ -0,0 +1,23 @@
controller_names:
- stretch_arm_controller
- gripper_controller
stretch_arm_controller:
action_ns: follow_joint_trajectory
default: True
type: FollowJointTrajectory
joints:
- joint_lift
- joint_arm_l3
- joint_arm_l2
- joint_arm_l1
- joint_arm_l0
- joint_wrist_yaw
gripper_controller:
action_ns: follow_joint_trajectory
default: True
type: FollowJointTrajectory
joints:
- joint_gripper_finger_left
- joint_gripper_finger_right

+ 19
- 40
stretch_moveit_config/config/ros_controllers.yaml View File

@ -1,38 +1,18 @@
# Simulation settings for using moveit_sim_controllers
moveit_sim_hw_interface:
joint_model_group: stretch_arm
joint_model_group_pose: home
# Settings for ros_control_boilerplate control loop
generic_hw_control_loop:
loop_hz: 300
cycle_time_error_threshold: 0.01
# Settings for ros_control hardware interface
hardware_interface:
joints:
- position
- joint_left_wheel
- joint_head_pan
- joint_head_tilt
- joint_lift
- joint_arm_l3
- joint_arm_l2
- joint_arm_l1
- joint_arm_l0
- joint_wrist_yaw
- joint_gripper_finger_left
- joint_gripper_finger_right
- joint_right_wheel
sim_control_mode: 1 # 0: position, 1: velocity
# Publish all joint states
# Creates the /joint_states topic necessary in ROS
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
controller_list:
- name: stretch_arm_controller
action_ns: follow_joint_trajectory
default: True
type: FollowJointTrajectory
controller_manager:
ros__parameters:
update_rate: 2 # Hz
stretch_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_controller:
type: joint_state_controller/JointStateController
gripper_controller:
type: joint_trajectory_controller/JointTrajectoryController
stretch_arm_controller:
ros__parameters:
joints:
- joint_lift
- joint_arm_l3
@ -40,10 +20,9 @@ controller_list:
- joint_arm_l1
- joint_arm_l0
- joint_wrist_yaw
- name: gripper_controller
action_ns: follow_joint_trajectory
default: True
type: FollowJointTrajectory
gripper_controller:
ros__parameters:
joints:
- joint_gripper_finger_left
- joint_gripper_finger_right
- joint_gripper_finger_right

+ 14
- 0
stretch_moveit_config/config/stretch.xacro View File

@ -0,0 +1,14 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_description">
<!-- Import stretch urdf file -->
<xacro:include filename="$(find stretch_description)/urdf/stretch_description.xacro" />
<!-- Import stretch ros2_control description -->
<xacro:include filename="stretch_arm.ros2_control.xacro" />
<xacro:include filename="gripper.ros2_control.xacro" />
<xacro:stretch_arm_ros2_control name="StretchFakeJointDriver" />
<xacro:gripper_ros2_control name="StretchGripperFakeJointDriver" />
</robot>

+ 44
- 0
stretch_moveit_config/config/stretch_arm.ros2_control.xacro View File

@ -0,0 +1,44 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="stretch_arm_ros2_control" params="name">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>fake_joint_driver/FakeJointDriver</plugin>
</hardware>
<joint name="joint_arm_l0">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
</joint>
<joint name="joint_arm_l1">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
</joint>
<joint name="joint_arm_l2">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
</joint>
<joint name="joint_arm_l3">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
</joint>
<joint name="joint_lift">
<param name="start_position">0.1033</param>
<command_interface name="position" />
<state_interface name="position"/>
</joint>
<joint name="joint_wrist_yaw">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>

+ 0
- 21
stretch_moveit_config/launch/chomp_planning_pipeline.launch.xml View File

@ -1,21 +0,0 @@
<launch>
<!-- CHOMP Plugin for MoveIt -->
<arg name="planning_plugin" value="chomp_interface/CHOMPPlanner" />
<arg name="start_state_max_bounds_error" value="0.1" />
<!-- The request adapters (plugins) used when planning.
ORDER MATTERS -->
<arg name="planning_adapters"
value="default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints"
/>
<param name="planning_plugin" value="$(arg planning_plugin)" />
<param name="request_adapters" value="$(arg planning_adapters)" />
<param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />
<rosparam command="load" file="$(find stretch_moveit_config)/config/chomp_planning.yaml" />
</launch>

+ 0
- 15
stretch_moveit_config/launch/default_warehouse_db.launch View File

@ -1,15 +0,0 @@
<launch>
<arg name="reset" default="false"/>
<!-- If not specified, we'll use a default database location -->
<arg name="moveit_warehouse_database_path" default="$(find stretch_moveit_config)/default_warehouse_mongo_db" />
<!-- Launch the warehouse with the configured database location -->
<include file="$(find stretch_moveit_config)/launch/warehouse.launch">
<arg name="moveit_warehouse_database_path" value="$(arg moveit_warehouse_database_path)" />
</include>
<!-- If we want to reset the database, run this node -->
<node if="$(arg reset)" name="$(anon moveit_default_db_reset)" type="moveit_init_demo_warehouse" pkg="moveit_ros_warehouse" respawn="false" output="screen" />
</launch>

+ 0
- 65
stretch_moveit_config/launch/demo.launch View File

@ -1,65 +0,0 @@
<launch>
<!-- specify the planning pipeline -->
<arg name="pipeline" default="ompl" />
<!-- 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 stretch_moveit_config)/default_warehouse_mongo_db" />
<!-- By default, we are not in debug mode -->
<arg name="debug" default="false" />
<!--
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="use_gui" default="false" />
<arg name="use_rviz" default="true" />
<!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
<include file="$(find stretch_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_0" args="0 0 0 0 0 0 map base_link" />
<!-- 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" unless="$(arg use_gui)">
<rosparam param="source_list">[move_group/fake_controller_joint_states]</rosparam>
</node>
<node name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" if="$(arg use_gui)">
<rosparam param="source_list">[move_group/fake_controller_joint_states]</rosparam>
</node>
<!-- 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 stretch_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 and load the default config to see the state of the move_group node -->
<include file="$(find stretch_moveit_config)/launch/moveit_rviz.launch" if="$(arg use_rviz)">
<arg name="rviz_config" value="$(find stretch_moveit_config)/launch/moveit.rviz"/>
<arg name="debug" value="$(arg debug)"/>
</include>
<!-- If database loading was enabled, start mongodb as well -->
<include file="$(find stretch_moveit_config)/launch/default_warehouse_db.launch" if="$(arg db)">
<arg name="moveit_warehouse_database_path" value="$(arg db_path)"/>
</include>
</launch>

+ 132
- 0
stretch_moveit_config/launch/demo.launch.py View File

@ -0,0 +1,132 @@
import os
import yaml
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import ExecuteProcess
from ament_index_python.packages import get_package_share_directory
import xacro
def load_file(package_name, file_path):
package_path = get_package_share_directory(package_name)
absolute_file_path = os.path.join(package_path, file_path)
try:
with open(absolute_file_path, 'r') as file:
return file.read()
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None
def load_yaml(package_name, file_path):
package_path = get_package_share_directory(package_name)
absolute_file_path = os.path.join(package_path, file_path)
try:
with open(absolute_file_path, 'r') as file:
return yaml.safe_load(file)
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None
def generate_launch_description():
# planning_context
robot_description_config = xacro.process_file(os.path.join(get_package_share_directory('stretch_moveit_config'),
'config',
'stretch.xacro'))
robot_description = {'robot_description' : robot_description_config.toxml()}
robot_description_semantic_config = load_file('stretch_moveit_config', 'config/stretch_description.srdf')
robot_description_semantic = {'robot_description_semantic' : robot_description_semantic_config}
kinematics_yaml = load_yaml('stretch_moveit_config', 'config/kinematics.yaml')
# Planning Functionality
ompl_planning_pipeline_config = { 'move_group' : {
'planning_plugin' : 'ompl_interface/OMPLPlanner',
'request_adapters' : """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""" ,
'start_state_max_bounds_error' : 0.1 } }
ompl_planning_yaml = load_yaml('stretch_moveit_config', 'config/ompl_planning.yaml')
ompl_planning_pipeline_config['move_group'].update(ompl_planning_yaml)
# Trajectory Execution Functionality
controllers_yaml = load_yaml('stretch_moveit_config', 'config/moveit_simple_controllers.yaml')
moveit_controllers = { 'moveit_simple_controller_manager' : controllers_yaml,
'moveit_controller_manager': 'moveit_simple_controller_manager/MoveItSimpleControllerManager'}
trajectory_execution = {'moveit_manage_controllers': True,
'trajectory_execution.allowed_execution_duration_scaling': 1.2,
'trajectory_execution.allowed_goal_duration_margin': 0.5,
'trajectory_execution.allowed_start_tolerance': 0.01}
planning_scene_monitor_parameters = {"publish_planning_scene": True,
"publish_geometry_updates": True,
"publish_state_updates": True,
"publish_transforms_updates": True}
# Start the actual move_group node/action server
run_move_group_node = Node(package='moveit_ros_move_group',
executable='move_group',
output='screen',
parameters=[robot_description,
robot_description_semantic,
kinematics_yaml,
ompl_planning_pipeline_config,
trajectory_execution,
moveit_controllers,
planning_scene_monitor_parameters])
# RViz
rviz_config_file = get_package_share_directory('stretch_moveit_config') + "/launch/moveit.rviz"
rviz_node = Node(package='rviz2',
executable='rviz2',
name='rviz2',
output='log',
arguments=['-d', rviz_config_file],
parameters=[robot_description,
robot_description_semantic,
ompl_planning_pipeline_config,
kinematics_yaml])
# TODO(JafarAbdi): We don't need this since the base is mobile
# Static TF
static_tf = Node(package='tf2_ros',
executable='static_transform_publisher',
name='static_transform_publisher',
output='log',
arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'map', 'base_link'])
# Publish TF
robot_state_publisher = Node(package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='both',
parameters=[robot_description])
# Fake joint driver
fake_joint_driver_node = Node(
package='controller_manager',
executable='ros2_control_node',
parameters=[robot_description, os.path.join(get_package_share_directory("stretch_moveit_config"), "config", "ros_controllers.yaml")],
output={
'stdout': 'screen',
'stderr': 'screen',
},
)
# load joint_state_controller
load_joint_state_controller = ExecuteProcess(cmd=['ros2 control load_start_controller joint_state_controller'], shell=True, output='screen')
load_controllers = [load_joint_state_controller]
for controller in ['stretch_arm_controller', 'gripper_controller']:
load_controllers += [ExecuteProcess(cmd=['ros2 control load_configure_controller', controller], shell=True, output='screen', on_exit=[ExecuteProcess(cmd=['ros2 control switch_controllers --start-controllers', controller], shell=True, output='screen')])]
# Warehouse mongodb server default_warehouse_db.launch + warehouse.launch + warehouse_settings.launch.xml
mongodb_server_node = Node(package='warehouse_ros_mongo',
executable='mongo_wrapper_ros.py',
parameters=[{'warehouse_port': 33829},
{'warehouse_host': 'localhost'},
{'warehouse_plugin': 'warehouse_ros_mongo::MongoDatabaseConnection'}],
output='screen')
return LaunchDescription([ rviz_node, static_tf, robot_state_publisher, run_move_group_node, fake_joint_driver_node, mongodb_server_node ] + load_controllers)

+ 0
- 9
stretch_moveit_config/launch/fake_moveit_controller_manager.launch.xml View File

@ -1,9 +0,0 @@
<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 stretch_moveit_config)/config/fake_controllers.yaml"/>
</launch>

+ 0
- 82
stretch_moveit_config/launch/move_group.launch View File

@ -1,82 +0,0 @@
<launch>
<!-- 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 stretch_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="pipeline" default="ompl" />
<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"/>
<arg name="capabilities" default=""/>
<arg name="disable_capabilities" default=""/>
<!-- load these non-default MoveGroup capabilities (space seperated) -->
<!--
<arg name="capabilities" value="
a_package/AwsomeMotionPlanningCapability
another_package/GraspPlanningPipeline
" />
-->
<!-- inhibit these default MoveGroup capabilities (space seperated) -->
<!--
<arg name="disable_capabilities" value="
move_group/MoveGroupKinematicsService
move_group/ClearOctomapService
" />
-->
<arg name="load_robot_description" default="true" />
<!-- load URDF, SRDF and joint_limits configuration -->
<include file="$(find stretch_moveit_config)/launch/planning_context.launch">
<arg name="load_robot_description" value="$(arg load_robot_description)" />
</include>
<!-- Planning Functionality -->
<include ns="move_group" file="$(find stretch_moveit_config)/launch/planning_pipeline.launch.xml">
<arg name="pipeline" value="$(arg pipeline)" />
</include>
<!-- Trajectory Execution Functionality -->
<include ns="move_group" file="$(find stretch_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="stretch_description" unless="$(arg fake_execution)"/>
<arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/>
</include>
<!-- Sensors Functionality -->
<include ns="move_group" file="$(find stretch_moveit_config)/launch/sensor_manager.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_sensor_manager" value="stretch_description" />
</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)" />
<param name="capabilities" value="$(arg capabilities)"/>
<param name="disable_capabilities" value="$(arg disable_capabilities)"/>
<!-- 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)" />
</node>
</launch>

+ 624
- 41
stretch_moveit_config/launch/moveit.rviz View File

@ -1,30 +1,34 @@
Panels:
- Class: rviz/Displays
Help Height: 84
- Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /MotionPlanning1
- /MotionPlanning1/Planning Request1
Splitter Ratio: 0.7425600290298462
Tree Height: 363
- Class: rviz/Help
Name: Help
- Class: rviz/Views
- /Global Options1
- /Status1
- /PlanningScene1
- /Trajectory1
Splitter Ratio: 0.5
Tree Height: 236
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
@ -40,6 +44,403 @@ Visualization Manager:
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Class: moveit_rviz_plugin/PlanningScene
Enabled: true
Move Group Namespace: ""
Name: PlanningScene
Planning Scene Topic: /monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 0.8999999761581421
Scene Color: 50; 230; 50
Scene Display Time: 0.20000000298023224
Show Scene Geometry: true
Voxel Coloring: Z-Axis
Voxel Rendering: Occupied Voxels
Scene Robot:
Attached Body Color: 150; 50; 150
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_bottom_screw_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_color_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_color_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_depth_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_depth_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra1_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra1_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra2_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra2_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
laser:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l0:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l2:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l3:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l4:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_inner_wrist:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_left_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_right_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_shoulder:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_top_wrist:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_grasp_center:
Alpha: 1
Show Axes: false
Show Trail: false
link_gripper:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_finger_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_finger_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_fingertip_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_fingertip_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_head:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_head_pan:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_head_tilt:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_left_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_lift:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_mast:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_right_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_wrist_yaw:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
respeaker_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Robot Alpha: 1
Show Robot Collision: false
Show Robot Visual: true
Value: true
- Class: moveit_rviz_plugin/Trajectory
Color Enabled: false
Enabled: true
Interrupt Display: false
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_bottom_screw_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_color_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_color_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_depth_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_depth_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra1_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra1_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra2_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra2_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
laser:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l0:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l2:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l3:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l4:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_inner_wrist:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_left_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_right_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_shoulder:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_top_wrist:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_grasp_center:
Alpha: 1
Show Axes: false
Show Trail: false
link_gripper:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_finger_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_finger_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_fingertip_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_fingertip_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_head:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_head_pan:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_head_tilt:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_left_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_lift:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_mast:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_right_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_wrist_yaw:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
respeaker_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Loop Animation: false
Name: Trajectory
Robot Alpha: 0.5
Robot Color: 150; 50; 150
Robot Description: robot_description
Show Robot Collision: false
Show Robot Visual: true
Show Trail: false
State Display Time: 0.05 s
Trail Step Size: 1
Trajectory Topic: /display_planned_path
Value: true
- Acceleration_Scaling_Factor: 0.1
Class: moveit_rviz_plugin/MotionPlanning
Enabled: true
@ -48,7 +449,6 @@ Visualization Manager:
MoveIt_Allow_External_Program: false
MoveIt_Allow_Replanning: false
MoveIt_Allow_Sensor_Positioning: false
MoveIt_Goal_Tolerance: 0
MoveIt_Planning_Attempts: 10
MoveIt_Planning_Time: 5
MoveIt_Use_Cartesian_Path: false
@ -79,6 +479,52 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
camera_bottom_screw_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_color_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_color_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_depth_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_depth_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra1_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra1_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra2_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra2_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
laser:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l0:
Alpha: 1
Show Axes: false
@ -104,6 +550,31 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
link_aruco_inner_wrist:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_left_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_right_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_shoulder:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_top_wrist:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_grasp_center:
Alpha: 1
Show Axes: false
@ -173,7 +644,12 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
Loop Animation: true
respeaker_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Loop Animation: false
Robot Alpha: 0.5
Robot Color: 150; 50; 150
Show Robot Collision: false
@ -181,7 +657,7 @@ Visualization Manager:
Show Trail: false
State Display Time: 0.05 s
Trail Step Size: 1
Trajectory Topic: move_group/display_planned_path
Trajectory Topic: /move_group/display_planned_path
Planning Metrics:
Payload: 1
Show Joint Torques: false
@ -201,12 +677,12 @@ Visualization Manager:
Show Workspace: false
Start State Alpha: 1
Start State Color: 0; 255; 0
Planning Scene Topic: move_group/monitored_planning_scene
Planning Scene Topic: /monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 1
Scene Alpha: 0.8999999761581421
Scene Color: 50; 230; 50
Scene Display Time: 0.20000000298023224
Scene Display Time: 0.009999999776482582
Show Scene Geometry: true
Voxel Coloring: Z-Axis
Voxel Rendering: Occupied Voxels
@ -223,6 +699,52 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
camera_bottom_screw_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_color_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_color_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_depth_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_depth_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra1_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra1_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra2_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_infra2_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
laser:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_arm_l0:
Alpha: 1
Show Axes: false
@ -248,6 +770,31 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
link_aruco_inner_wrist:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_left_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_right_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_shoulder:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_aruco_top_wrist:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_grasp_center:
Alpha: 1
Show Axes: false
@ -317,7 +864,12 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
Robot Alpha: 0.5
respeaker_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Robot Alpha: 1
Show Robot Collision: false
Show Robot Visual: true
Value: true
@ -325,54 +877,85 @@ Visualization Manager:
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz/XYOrbit
Distance: 2.0420308113098145
Class: rviz_default_plugins/Orbit
Distance: 2.223123073577881
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 0.7853981852531433
Focal Point:
X: 0.11356700211763382
Y: 0.10592000186443329
Z: 2.2351800055275817e-07
X: -0.37554749846458435
Y: 0.09499212354421616
Z: 0.6261870861053467
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.4647970497608185
Target Frame: base_link
Yaw: 5.0149431228637695
Pitch: 0.5603980422019958
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 6.018581867218018
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1008
Help:
collapsed: false
Height: 1043
Hide Left Dock: false
Hide Right Dock: false
MotionPlanning:
collapsed: false
MotionPlanning - Trajectory Slider:
collapsed: false
QMainWindow State: 000000ff00000000fd0000000100000000000002a200000396fc0200000007fb000000100044006900730070006c006100790073010000003d000001fc000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a0056006900650077007300000003b0000000b0000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e0067010000023f000001940000018900ffffff0000047c0000039600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 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
Selection:
collapsed: false
Tool Properties:
collapsed: false
Trajectory - Trajectory Slider:
collapsed: false
Views:
collapsed: false
Width: 1828
X: 92
Y: 633
Width: 1920
X: 0
Y: 0

+ 0
- 15
stretch_moveit_config/launch/moveit_rviz.launch View File

@ -1,15 +0,0 @@
<launch>
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
<arg name="rviz_config" default="" />
<arg if="$(eval rviz_config=='')" name="command_args" value="" />
<arg unless="$(eval rviz_config=='')" name="command_args" value="-d $(arg rviz_config)" />
<node name="$(anon rviz)" launch-prefix="$(arg launch_prefix)" pkg="rviz" type="rviz" respawn="false"
args="$(arg command_args)" output="screen">
</node>
</launch>

+ 0
- 25
stretch_moveit_config/launch/ompl_planning_pipeline.launch.xml View File

@ -1,25 +0,0 @@
<launch>
<!-- OMPL Plugin for MoveIt -->
<arg name="planning_plugin" value="ompl_interface/OMPLPlanner" />
<!-- The request adapters (plugins) used when planning with OMPL.
ORDER MATTERS -->
<arg name="planning_adapters"
value="default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints"
/>
<arg name="start_state_max_bounds_error" value="0.1" />
<param name="planning_plugin" value="$(arg planning_plugin)" />
<param name="request_adapters" value="$(arg planning_adapters)" />
<param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />
<rosparam command="load" file="$(find stretch_moveit_config)/config/ompl_planning.yaml"/>
</launch>

+ 0
- 25
stretch_moveit_config/launch/planning_context.launch View File

@ -1,25 +0,0 @@
<launch>
<!-- By default we do not overwrite the URDF. Change the following to true to change the default behavior -->
<arg name="load_robot_description" default="false"/>
<!-- The name of the parameter under which the URDF is loaded -->
<arg name="robot_description" default="robot_description"/>
<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find stretch_description)/urdf/stretch_description.xacro'"/>
<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find stretch_moveit_config)/config/stretch_description.srdf" />
<!-- Load updated joint limits (override information from URDF) -->
<group ns="$(arg robot_description)_planning">
<rosparam command="load" file="$(find stretch_moveit_config)/config/joint_limits.yaml"/>
</group>
<!-- Load default settings for kinematics; these settings are overridden by settings in a node's namespace -->
<group ns="$(arg robot_description)_kinematics">
<rosparam command="load" file="$(find stretch_moveit_config)/config/kinematics.yaml"/>
</group>
</launch>

+ 0
- 10
stretch_moveit_config/launch/planning_pipeline.launch.xml View File

@ -1,10 +0,0 @@
<launch>
<!-- This file makes it easy to include different planning pipelines;
It is assumed that all planning pipelines are named XXX_planning_pipeline.launch -->
<arg name="pipeline" default="ompl" />
<include file="$(find stretch_moveit_config)/launch/$(arg pipeline)_planning_pipeline.launch.xml" />
</launch>

+ 0
- 11
stretch_moveit_config/launch/ros_controllers.launch View File

@ -1,11 +0,0 @@
<?xml version="1.0"?>
<launch>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find stretch_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=""/>
</launch>

+ 0
- 10
stretch_moveit_config/launch/stretch_description_moveit_controller_manager.launch.xml View File

@ -1,10 +0,0 @@
<launch>
<!-- loads moveit_controller_manager on the parameter server which is taken as argument
if no argument is passed, moveit_simple_controller_manager will be set -->
<arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
<!-- loads ros_controllers to the param server -->
<rosparam file="$(find stretch_moveit_config)/config/ros_controllers.yaml"/>
</launch>

+ 0
- 3
stretch_moveit_config/launch/stretch_description_moveit_sensor_manager.launch.xml View File

@ -1,3 +0,0 @@
<launch>
</launch>

+ 0
- 20
stretch_moveit_config/launch/trajectory_execution.launch.xml View File

@ -1,20 +0,0 @@
<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="stretch_description" />
<include file="$(find stretch_moveit_config)/launch/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" />
</launch>

+ 0
- 15
stretch_moveit_config/launch/warehouse.launch View File

@ -1,15 +0,0 @@
<launch>
<!-- The path to the database must be specified -->
<arg name="moveit_warehouse_database_path" />
<!-- Load warehouse parameters -->
<include file="$(find stretch_moveit_config)/launch/warehouse_settings.launch.xml" />
<!-- Run the DB server -->
<node name="$(anon mongo_wrapper_ros)" cwd="ROS_HOME" type="mongo_wrapper_ros.py" pkg="warehouse_ros_mongo">
<param name="overwrite" value="false"/>
<param name="database_path" value="$(arg moveit_warehouse_database_path)" />
</node>
</launch>

+ 0
- 16
stretch_moveit_config/launch/warehouse_settings.launch.xml View File

@ -1,16 +0,0 @@
<launch>
<!-- Set the parameters for the warehouse and run the mongodb server. -->
<!-- The default DB port for moveit (not default MongoDB port to avoid potential conflicts) -->
<arg name="moveit_warehouse_port" default="33829" />
<!-- The default DB host for moveit -->
<arg name="moveit_warehouse_host" default="localhost" />
<!-- Set parameters for the warehouse -->
<param name="warehouse_port" value="$(arg moveit_warehouse_port)"/>
<param name="warehouse_host" value="$(arg moveit_warehouse_host)"/>
<param name="warehouse_exec" value="mongod" />
<param name="warehouse_plugin" value="warehouse_ros_mongo::MongoDatabaseConnection" />
</launch>

+ 6
- 2
stretch_moveit_config/package.xml View File

@ -14,7 +14,7 @@
<url type="bugtracker">https://github.com/ros-planning/moveit/issues</url>
<url type="repository">https://github.com/ros-planning/moveit</url>
<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend>ament_cmake</buildtool_depend>
<run_depend>joint_state_publisher</run_depend>
<run_depend>joint_state_publisher_gui</run_depend>
@ -23,11 +23,15 @@
<run_depend>moveit_planners_ompl</run_depend>
<run_depend>moveit_ros_move_group</run_depend>
<run_depend>moveit_ros_visualization</run_depend>
<run_depend>moveit_setup_assistant</run_depend>
<!-- TODO(JafarAbdi): uncomment once MSA is ported -->
<!-- run_depend>moveit_setup_assistant</run_depend -->
<run_depend>robot_state_publisher</run_depend>
<run_depend>stretch_description</run_depend>
<run_depend>tf2_ros</run_depend>
<run_depend>xacro</run_depend>
<!-- This package is referenced in the warehouse launch files, but does not build out of the box at the moment. Commented the dependency until this works. -->
<!-- <run_depend>warehouse_ros_mongo</run_depend> -->
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

Loading…
Cancel
Save