diff --git a/stretch_moveit_config/.setup_assistant b/stretch_moveit_config/.setup_assistant deleted file mode 100644 index 7bf96f7..0000000 --- a/stretch_moveit_config/.setup_assistant +++ /dev/null @@ -1,11 +0,0 @@ -moveit_setup_assistant_config: - URDF: - package: stretch_description - relative_path: urdf/stretch_description.xacro - xacro_args: "" - SRDF: - relative_path: config/stretch_description.srdf - CONFIG: - author_name: David V. Lu!! - author_email: davidvlu@gmail.com - generated_timestamp: 1602791794 \ No newline at end of file diff --git a/stretch_moveit_config/CMakeLists.txt b/stretch_moveit_config/CMakeLists.txt deleted file mode 100644 index d981bb3..0000000 --- a/stretch_moveit_config/CMakeLists.txt +++ /dev/null @@ -1,10 +0,0 @@ -cmake_minimum_required(VERSION 3.1.3) -project(stretch_moveit_config) - -find_package(catkin REQUIRED) - -catkin_package() - -install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - PATTERN "setup_assistant.launch" EXCLUDE) -install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/stretch_moveit_config/LICENSE.md b/stretch_moveit_config/LICENSE.md deleted file mode 100644 index c45b1e2..0000000 --- a/stretch_moveit_config/LICENSE.md +++ /dev/null @@ -1,11 +0,0 @@ -The following license applies to the entire contents of this directory (the "Contents"), which contains software for use with the Stretch RE1 mobile manipulator, which is a robot produced and sold by Hello Robot Inc. - -Copyright 2020 Hello Robot Inc. - -The Contents are licensed under the Apache License, Version 2.0 (the "License"). You may not use the Contents except in compliance with the License. You may obtain a copy of the License at - -http://www.apache.org/licenses/LICENSE-2.0 - -Unless required by applicable law or agreed to in writing, the Contents are distributed under the License are distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License. - -For further information about the Contents including inquiries about dual licensing, please contact Hello Robot Inc. diff --git a/stretch_moveit_config/README.md b/stretch_moveit_config/README.md deleted file mode 100644 index d6d8f25..0000000 --- a/stretch_moveit_config/README.md +++ /dev/null @@ -1,23 +0,0 @@ -![](../images/banner.png) - -## Stretch & MoveIt! -MoveIt is the standard ROS manipulation platform, and this package is the configuration for working with Stretch with the MoveIt framework. - - -### Offline Demo - -To experiment with the planning capabilities of MoveIt on Stretch, you can run a demo _without_ Stretch hardware. - - roslaunch stretch_moveit_config demo.launch - -This will allow you to move the robot around using interactive markers and create plans between poses. - -### Hardware Integration - -There is no planned support to run MoveIt on Stretch hardware. Instead, support for running MoveIt 2 (the successor to MoveIt) on Stretch hardware is being developed in [Stretch's ROS2 packages](https://github.com/hello-robot/stretch_ros2/). The primary reason to support MoveIt 2 instead of MoveIt 1 is because MoveIt 2 introduces planning for differential drive bases, whereas MoveIt 1 does not have this ability. Manipulation with Stretch is more capable when the mobile base is included. - -Please keep an eye on [Stretch's ROS2 packages](https://github.com/hello-robot/stretch_ros2/) and our [forum](https://forum.hello-robot.com/) to track the state of Stretch + MoveIt 2 support. - -## License - -For license information, please see the LICENSE files. diff --git a/stretch_moveit_config/config/chomp_planning.yaml b/stretch_moveit_config/config/chomp_planning.yaml deleted file mode 100644 index 75258e5..0000000 --- a/stretch_moveit_config/config/chomp_planning.yaml +++ /dev/null @@ -1,18 +0,0 @@ -planning_time_limit: 10.0 -max_iterations: 200 -max_iterations_after_collision_free: 5 -smoothness_cost_weight: 0.1 -obstacle_cost_weight: 1.0 -learning_rate: 0.01 -smoothness_cost_velocity: 0.0 -smoothness_cost_acceleration: 1.0 -smoothness_cost_jerk: 0.0 -ridge_factor: 0.01 -use_pseudo_inverse: false -pseudo_inverse_ridge_factor: 1e-4 -joint_update_limit: 0.1 -collision_clearence: 0.2 -collision_threshold: 0.07 -use_stochastic_descent: true -enable_failure_recovery: true -max_recovery_attempts: 5 \ No newline at end of file diff --git a/stretch_moveit_config/config/fake_controllers.yaml b/stretch_moveit_config/config/fake_controllers.yaml deleted file mode 100644 index e16ec64..0000000 --- a/stretch_moveit_config/config/fake_controllers.yaml +++ /dev/null @@ -1,16 +0,0 @@ -controller_list: - - name: fake_stretch_arm_controller - joints: - - joint_lift - - joint_arm_l3 - - joint_arm_l2 - - joint_arm_l1 - - joint_arm_l0 - - joint_wrist_yaw - - name: fake_gripper_controller - joints: - - joint_gripper_finger_left - - joint_gripper_finger_right -initial: # Define initial robot poses. - - group: stretch_arm - pose: home \ No newline at end of file diff --git a/stretch_moveit_config/config/joint_limits.yaml b/stretch_moveit_config/config/joint_limits.yaml deleted file mode 100644 index c666ced..0000000 --- a/stretch_moveit_config/config/joint_limits.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed - -# For beginners, we downscale velocity and acceleration limits. -# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. -default_velocity_scaling_factor: 0.1 -default_acceleration_scaling_factor: 0.1 - -# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] -# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] -joint_limits: - joint_arm_l0: - has_velocity_limits: true - max_velocity: 1 - has_acceleration_limits: false - max_acceleration: 0 - joint_arm_l1: - has_velocity_limits: true - max_velocity: 1 - has_acceleration_limits: false - max_acceleration: 0 - joint_arm_l2: - has_velocity_limits: true - max_velocity: 1 - has_acceleration_limits: false - max_acceleration: 0 - joint_arm_l3: - has_velocity_limits: true - max_velocity: 1 - has_acceleration_limits: false - max_acceleration: 0 - joint_gripper_finger_left: - has_velocity_limits: true - max_velocity: 1 - has_acceleration_limits: false - max_acceleration: 0 - joint_gripper_finger_right: - has_velocity_limits: true - max_velocity: 1 - has_acceleration_limits: false - max_acceleration: 0 - joint_lift: - has_velocity_limits: true - max_velocity: 1 - has_acceleration_limits: false - max_acceleration: 0 - joint_wrist_yaw: - has_velocity_limits: true - max_velocity: 1 - has_acceleration_limits: false - max_acceleration: 0 \ No newline at end of file diff --git a/stretch_moveit_config/config/kinematics.yaml b/stretch_moveit_config/config/kinematics.yaml deleted file mode 100644 index 5928c35..0000000 --- a/stretch_moveit_config/config/kinematics.yaml +++ /dev/null @@ -1,8 +0,0 @@ -stretch_arm: - kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin - kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.005 -stretch_head: - kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin - kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.1 diff --git a/stretch_moveit_config/config/ompl_planning.yaml b/stretch_moveit_config/config/ompl_planning.yaml deleted file mode 100644 index e59094e..0000000 --- a/stretch_moveit_config/config/ompl_planning.yaml +++ /dev/null @@ -1,210 +0,0 @@ -planner_configs: - AnytimePathShortening: - type: geometric::AnytimePathShortening - shortcut: true # Attempt to shortcut all new solution paths - hybridize: true # Compute hybrid solution trajectories - max_hybrid_paths: 24 # Number of hybrid paths generated per iteration - num_planners: 4 # The number of default planners to use for planning - planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" - SBL: - type: geometric::SBL - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - EST: - type: geometric::EST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LBKPIECE: - type: geometric::LBKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - BKPIECE: - type: geometric::BKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - KPIECE: - type: geometric::KPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - RRT: - type: geometric::RRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - RRTConnect: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - RRTstar: - type: geometric::RRTstar - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 - TRRT: - type: geometric::TRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - max_states_failed: 10 # when to start increasing temp. default: 10 - temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 - min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 - init_temperature: 10e-6 # initial temperature. default: 10e-6 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() - PRM: - type: geometric::PRM - max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 - PRMstar: - type: geometric::PRMstar - FMT: - type: geometric::FMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 - nearest_k: 1 # use Knearest strategy. default: 1 - cache_cc: 1 # use collision checking cache. default: 1 - heuristics: 0 # activate cost to go heuristics. default: 0 - extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - BFMT: - type: geometric::BFMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 - nearest_k: 1 # use the Knearest strategy. default: 1 - balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 - optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 - heuristics: 1 # activates cost to go heuristics. default: 1 - cache_cc: 1 # use the collision checking cache. default: 1 - extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - PDST: - type: geometric::PDST - STRIDE: - type: geometric::STRIDE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 - degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 - max_degree: 18 # max degree of a node in the GNAT. default: 12 - min_degree: 12 # min degree of a node in the GNAT. default: 12 - max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 - estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 - min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 - BiTRRT: - type: geometric::BiTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 - init_temperature: 100 # initial temperature. default: 100 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf - LBTRRT: - type: geometric::LBTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - epsilon: 0.4 # optimality approximation factor. default: 0.4 - BiEST: - type: geometric::BiEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - ProjEST: - type: geometric::ProjEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LazyPRM: - type: geometric::LazyPRM - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - LazyPRMstar: - type: geometric::LazyPRMstar - SPARS: - type: geometric::SPARS - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 1000 # maximum consecutive failure limit. default: 1000 - SPARStwo: - type: geometric::SPARStwo - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 5000 # maximum consecutive failure limit. default: 5000 -stretch_arm: - default_planner_config: RRTConnect - planner_configs: - - AnytimePathShortening - - SBL - - EST - - LBKPIECE - - BKPIECE - - KPIECE - - RRT - - RRTConnect - - RRTstar - - TRRT - - PRM - - PRMstar - - FMT - - BFMT - - PDST - - STRIDE - - BiTRRT - - LBTRRT - - BiEST - - ProjEST - - LazyPRM - - LazyPRMstar - - SPARS - - SPARStwo -stretch_gripper: - default_planner_config: RRTConnect - planner_configs: - - AnytimePathShortening - - SBL - - EST - - LBKPIECE - - BKPIECE - - KPIECE - - RRT - - RRTConnect - - RRTstar - - TRRT - - PRM - - PRMstar - - FMT - - BFMT - - PDST - - STRIDE - - BiTRRT - - LBTRRT - - BiEST - - ProjEST - - LazyPRM - - LazyPRMstar - - SPARS - - SPARStwo -stretch_head: - default_planner_config: RRTConnect - planner_configs: - - AnytimePathShortening - - SBL - - EST - - LBKPIECE - - BKPIECE - - KPIECE - - RRT - - RRTConnect - - RRTstar - - TRRT - - PRM - - PRMstar - - FMT - - BFMT - - PDST - - STRIDE - - BiTRRT - - LBTRRT - - BiEST - - ProjEST - - LazyPRM - - LazyPRMstar - - SPARS - - SPARStwo \ No newline at end of file diff --git a/stretch_moveit_config/config/ros_controllers.yaml b/stretch_moveit_config/config/ros_controllers.yaml deleted file mode 100644 index 03882df..0000000 --- a/stretch_moveit_config/config/ros_controllers.yaml +++ /dev/null @@ -1,31 +0,0 @@ -# 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 - joints: - - joint_lift - - joint_arm_l3 - - joint_arm_l2 - - joint_arm_l1 - - joint_arm_l0 - - joint_wrist_yaw - - name: stretch_head_controller - action_ns: follow_joint_trajectory - default: True - type: FollowJointTrajectory - joints: - - joint_head_pan - - joint_head_tilt - - name: stretch_gripper_controller - action_ns: follow_joint_trajectory - default: True - type: FollowJointTrajectory - joints: - - joint_gripper_finger_left - - joint_gripper_finger_right diff --git a/stretch_moveit_config/config/sensors_3d.yaml b/stretch_moveit_config/config/sensors_3d.yaml deleted file mode 100644 index a4bb13e..0000000 --- a/stretch_moveit_config/config/sensors_3d.yaml +++ /dev/null @@ -1,10 +0,0 @@ -# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it -sensors: - - filtered_cloud_topic: filtered_cloud - max_range: 5.0 - max_update_rate: 1.0 - padding_offset: 0.1 - padding_scale: 1.0 - point_cloud_topic: /head_mount_kinect/depth_registered/points - point_subsample: 1 - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater \ No newline at end of file diff --git a/stretch_moveit_config/config/stretch_description.srdf b/stretch_moveit_config/config/stretch_description.srdf deleted file mode 100644 index 319bcec..0000000 --- a/stretch_moveit_config/config/stretch_description.srdf +++ /dev/null @@ -1,408 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/chomp_planning_pipeline.launch.xml b/stretch_moveit_config/launch/chomp_planning_pipeline.launch.xml deleted file mode 100644 index 90e0b96..0000000 --- a/stretch_moveit_config/launch/chomp_planning_pipeline.launch.xml +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/default_warehouse_db.launch b/stretch_moveit_config/launch/default_warehouse_db.launch deleted file mode 100644 index d21274e..0000000 --- a/stretch_moveit_config/launch/default_warehouse_db.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/demo.launch b/stretch_moveit_config/launch/demo.launch deleted file mode 100644 index 5c485b3..0000000 --- a/stretch_moveit_config/launch/demo.launch +++ /dev/null @@ -1,65 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [move_group/fake_controller_joint_states] - - - [move_group/fake_controller_joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/demo_gazebo.launch b/stretch_moveit_config/launch/demo_gazebo.launch deleted file mode 100644 index 0c9f8c7..0000000 --- a/stretch_moveit_config/launch/demo_gazebo.launch +++ /dev/null @@ -1,61 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/stretch_moveit_config/launch/fake_moveit_controller_manager.launch.xml deleted file mode 100644 index d422edf..0000000 --- a/stretch_moveit_config/launch/fake_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/stretch_moveit_config/launch/gazebo.launch b/stretch_moveit_config/launch/gazebo.launch deleted file mode 100644 index d7368f0..0000000 --- a/stretch_moveit_config/launch/gazebo.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/joystick_control.launch b/stretch_moveit_config/launch/joystick_control.launch deleted file mode 100644 index 9411f6e..0000000 --- a/stretch_moveit_config/launch/joystick_control.launch +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/move_group.launch b/stretch_moveit_config/launch/move_group.launch deleted file mode 100644 index 56eeb57..0000000 --- a/stretch_moveit_config/launch/move_group.launch +++ /dev/null @@ -1,82 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/moveit.rviz b/stretch_moveit_config/launch/moveit.rviz deleted file mode 100644 index be3ffcf..0000000 --- a/stretch_moveit_config/launch/moveit.rviz +++ /dev/null @@ -1,570 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 84 - Name: Displays - Property Tree Widget: - Expanded: - - /MotionPlanning1 - Splitter Ratio: 0.7425600290298462 - Tree Height: 351 - - Class: rviz/Help - Name: Help - - Class: rviz/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 - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Acceleration_Scaling_Factor: 1 - Class: moveit_rviz_plugin/MotionPlanning - Enabled: true - Move Group Namespace: "" - MoveIt_Allow_Approximate_IK: true - MoveIt_Allow_External_Program: false - MoveIt_Allow_Replanning: false - MoveIt_Allow_Sensor_Positioning: false - MoveIt_Planning_Attempts: 10 - MoveIt_Planning_Time: 5 - MoveIt_Use_Cartesian_Path: false - MoveIt_Use_Constraint_Aware_IK: true - MoveIt_Warehouse_Host: 127.0.0.1 - MoveIt_Warehouse_Port: 33829 - MoveIt_Workspace: - Center: - X: 0 - Y: 0 - Z: 0 - Size: - X: 2 - Y: 2 - Z: 2 - Name: MotionPlanning - Planned Path: - Color Enabled: false - 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_accel_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - camera_accel_optical_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - 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_gyro_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - camera_gyro_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 - caster_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 - Robot Alpha: 0.5 - Robot Color: 150; 50; 150 - Show Robot Collision: false - Show Robot Visual: true - Show Trail: false - State Display Time: 0.05 s - Trail Step Size: 1 - Trajectory Topic: move_group/display_planned_path - Planning Metrics: - Payload: 1 - Show Joint Torques: false - Show Manipulability: false - Show Manipulability Index: false - Show Weight Limit: false - TextHeight: 0.07999999821186066 - Planning Request: - Colliding Link Color: 255; 0; 0 - Goal State Alpha: 1 - Goal State Color: 250; 128; 0 - Interactive Marker Size: 0 - Joint Violation Color: 255; 0; 255 - Planning Group: stretch_arm - Query Goal State: true - Query Start State: false - Show Workspace: false - Start State Alpha: 1 - Start State Color: 0; 255; 0 - Planning Scene Topic: move_group/monitored_planning_scene - Robot Description: robot_description - Scene Geometry: - Scene Alpha: 1 - 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_accel_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - camera_accel_optical_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - 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_gyro_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - camera_gyro_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 - caster_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: 0.5 - Show Robot Collision: false - Show Robot Visual: true - Value: true - Velocity_Scaling_Factor: 1 - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: base_link - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - Value: true - Views: - Current: - Class: rviz/XYOrbit - Distance: 2.5615234375 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0.11356700211763382 - Y: 0.10592000186443329 - Z: 2.2351800055275817e-7 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.5697969794273376 - Target Frame: base_link - Value: XYOrbit (rviz) - Yaw: 5.364950656890869 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 1052 - Help: - collapsed: false - Hide Left Dock: false - Hide Right Dock: false - MotionPlanning: - collapsed: false - MotionPlanning - Trajectory Slider: - collapsed: false - QMainWindow State: 000000ff00000000fd0000000100000000000002a2000003c2fc0200000007fb000000100044006900730070006c006100790073010000003d000001f0000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a0056006900650077007300000003b0000000b0000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000233000001cc0000017d00ffffff000004d8000003c200000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Views: - collapsed: false - Width: 1920 - X: 1920 - Y: 0 diff --git a/stretch_moveit_config/launch/moveit_rviz.launch b/stretch_moveit_config/launch/moveit_rviz.launch deleted file mode 100644 index fa149ad..0000000 --- a/stretch_moveit_config/launch/moveit_rviz.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/ompl_planning_pipeline.launch.xml b/stretch_moveit_config/launch/ompl_planning_pipeline.launch.xml deleted file mode 100644 index 230e9d9..0000000 --- a/stretch_moveit_config/launch/ompl_planning_pipeline.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/planning_context.launch b/stretch_moveit_config/launch/planning_context.launch deleted file mode 100644 index 97dd61c..0000000 --- a/stretch_moveit_config/launch/planning_context.launch +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/planning_pipeline.launch.xml b/stretch_moveit_config/launch/planning_pipeline.launch.xml deleted file mode 100644 index 87cbbfe..0000000 --- a/stretch_moveit_config/launch/planning_pipeline.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - diff --git a/stretch_moveit_config/launch/ros_controllers.launch b/stretch_moveit_config/launch/ros_controllers.launch deleted file mode 100644 index 7a60150..0000000 --- a/stretch_moveit_config/launch/ros_controllers.launch +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - diff --git a/stretch_moveit_config/launch/run_benchmark_ompl.launch b/stretch_moveit_config/launch/run_benchmark_ompl.launch deleted file mode 100644 index 6b2e57c..0000000 --- a/stretch_moveit_config/launch/run_benchmark_ompl.launch +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/sensor_manager.launch.xml b/stretch_moveit_config/launch/sensor_manager.launch.xml deleted file mode 100644 index 2345471..0000000 --- a/stretch_moveit_config/launch/sensor_manager.launch.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/setup_assistant.launch b/stretch_moveit_config/launch/setup_assistant.launch deleted file mode 100644 index 8b7ca6a..0000000 --- a/stretch_moveit_config/launch/setup_assistant.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/stretch_description_moveit_controller_manager.launch.xml b/stretch_moveit_config/launch/stretch_description_moveit_controller_manager.launch.xml deleted file mode 100644 index 3931bd4..0000000 --- a/stretch_moveit_config/launch/stretch_description_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - diff --git a/stretch_moveit_config/launch/stretch_description_moveit_sensor_manager.launch.xml b/stretch_moveit_config/launch/stretch_description_moveit_sensor_manager.launch.xml deleted file mode 100644 index 5d02698..0000000 --- a/stretch_moveit_config/launch/stretch_description_moveit_sensor_manager.launch.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/stretch_moveit_config/launch/trajectory_execution.launch.xml b/stretch_moveit_config/launch/trajectory_execution.launch.xml deleted file mode 100644 index 5851abb..0000000 --- a/stretch_moveit_config/launch/trajectory_execution.launch.xml +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/warehouse.launch b/stretch_moveit_config/launch/warehouse.launch deleted file mode 100644 index d4ea8ac..0000000 --- a/stretch_moveit_config/launch/warehouse.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/launch/warehouse_settings.launch.xml b/stretch_moveit_config/launch/warehouse_settings.launch.xml deleted file mode 100644 index e473b08..0000000 --- a/stretch_moveit_config/launch/warehouse_settings.launch.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/stretch_moveit_config/package.xml b/stretch_moveit_config/package.xml deleted file mode 100644 index 99d1fb3..0000000 --- a/stretch_moveit_config/package.xml +++ /dev/null @@ -1,34 +0,0 @@ - - - stretch_moveit_config - 0.3.0 - - An automatically generated package with all the configuration and launch files for using the stretch_description with the MoveIt Motion Planning Framework - - David V. Lu!! - David V. Lu!! - - Apache License 2.0 - - http://moveit.ros.org/ - https://github.com/ros-planning/moveit/issues - https://github.com/ros-planning/moveit - - catkin - - joint_state_publisher - joint_state_publisher_gui - moveit_fake_controller_manager - moveit_kinematics - moveit_planners_ompl - moveit_ros_move_group - moveit_ros_visualization - moveit_setup_assistant - moveit_simple_controller_manager - robot_state_publisher - stretch_description - tf2_ros - xacro - - -