├── config ├── ros_controllers.yaml ├── lerp_planning.yaml ├── cartesian_limits.yaml ├── gazebo_controllers.yaml ├── kinematics.yaml ├── sensors_kinect_pointcloud.yaml ├── sensors_kinect_depthmap.yaml ├── chomp_planning.yaml ├── simple_moveit_controllers.yaml ├── fake_controllers.yaml ├── stomp_planning.yaml ├── panda.srdf.xacro ├── joint_limits.yaml ├── hand.xacro ├── trajopt_planning.yaml ├── arm.xacro └── ompl_planning.yaml ├── launch ├── panda_moveit_sensor_manager.launch.xml ├── demo_lerp.launch ├── demo_chomp.launch ├── demo_stomp.launch ├── ros_control_moveit_controller_manager.launch.xml ├── simple_moveit_controller_manager.launch.xml ├── planning_pipeline.launch.xml ├── ros_controllers.launch ├── warehouse.launch ├── fake_moveit_controller_manager.launch.xml ├── setup_assistant.launch ├── joystick_control.launch ├── warehouse_settings.launch.xml ├── default_warehouse_db.launch ├── pilz_industrial_motion_planner_planning_pipeline.launch.xml ├── run_benchmark_ompl.launch ├── moveit_rviz.launch ├── franka_control.launch ├── run_benchmark_trajopt.launch ├── ompl_chomp_planning_pipeline.launch.xml ├── sensor_manager.launch.xml ├── lerp_planning_pipeline.launch.xml ├── chomp_planning_pipeline.launch.xml ├── demo_gazebo.launch ├── ompl_planning_pipeline.launch.xml ├── planning_context.launch ├── trajectory_execution.launch.xml ├── trajopt_planning_pipeline.launch.xml ├── stomp_planning_pipeline.launch.xml ├── demo.launch ├── moveit_empty.rviz ├── moveit.rviz ├── moveit_scene.rviz └── move_group.launch ├── README.md ├── CMakeLists.txt ├── .setup_assistant ├── CHANGELOG.rst └── package.xml /config/ros_controllers.yaml: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /config/lerp_planning.yaml: -------------------------------------------------------------------------------- 1 | num_steps: 40 2 | -------------------------------------------------------------------------------- /launch/panda_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /config/cartesian_limits.yaml: -------------------------------------------------------------------------------- 1 | cartesian_limits: 2 | max_trans_vel: 1 3 | max_trans_acc: 2.25 4 | max_trans_dec: -5 5 | max_rot_vel: 1.57 6 | -------------------------------------------------------------------------------- /launch/demo_lerp.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /launch/demo_chomp.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /launch/demo_stomp.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /config/gazebo_controllers.yaml: -------------------------------------------------------------------------------- 1 | # Publish joint_states 2 | joint_state_controller: 3 | type: joint_state_controller/JointStateController 4 | publish_rate: 50 5 | -------------------------------------------------------------------------------- /launch/ros_control_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | -------------------------------------------------------------------------------- /config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | $(arg arm_id)_arm: &arm_config 2 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin 3 | kinematics_solver_search_resolution: 0.005 4 | kinematics_solver_timeout: 0.05 5 | 6 | $(arg arm_id)_manipulator: *arm_config 7 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Franka Emika Panda MoveIt Config Package 2 | 3 | The Panda robot is the flagship MoveIt integration robot used in the MoveIt tutorials. 4 | Any changes to MoveIt need to be propagated into this config fast, so this package 5 | is co-located under the ``ros-planning`` Github organization here. 6 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.10) 2 | project(panda_moveit_config) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 9 | PATTERN "setup_assistant.launch" EXCLUDE) 10 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 11 | -------------------------------------------------------------------------------- /config/sensors_kinect_pointcloud.yaml: -------------------------------------------------------------------------------- 1 | sensors: 2 | - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater 3 | point_cloud_topic: /camera/depth_registered/points 4 | max_range: 5.0 5 | point_subsample: 1 6 | padding_offset: 0.1 7 | padding_scale: 1.0 8 | max_update_rate: 1.0 9 | filtered_cloud_topic: filtered_cloud 10 | ns: kinect 11 | -------------------------------------------------------------------------------- /.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: franka_description 4 | relative_path: robots/panda/panda.urdf.xacro 5 | xacro_args: hand:=true 6 | SRDF: 7 | relative_path: config/panda.srdf.xacro 8 | CONFIG: 9 | author_name: MoveIt maintainer team 10 | author_email: moveit_releasers@googlegroups.com 11 | generated_timestamp: 1636310680 12 | -------------------------------------------------------------------------------- /launch/simple_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /config/sensors_kinect_depthmap.yaml: -------------------------------------------------------------------------------- 1 | sensors: 2 | - sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater 3 | image_topic: /camera/depth_registered/image_raw 4 | queue_size: 5 5 | near_clipping_plane_distance: 0.3 6 | far_clipping_plane_distance: 5.0 7 | shadow_threshold: 0.2 8 | padding_scale: 4.0 9 | padding_offset: 0.03 10 | max_update_rate: 1.0 11 | filtered_cloud_topic: filtered_cloud 12 | ns: kinect 13 | -------------------------------------------------------------------------------- /launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /launch/ros_controllers.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 10 | 11 | -------------------------------------------------------------------------------- /launch/warehouse.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /config/chomp_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_time_limit: 10.0 2 | max_iterations: 200 3 | max_iterations_after_collision_free: 5 4 | smoothness_cost_weight: 0.1 5 | obstacle_cost_weight: 1.0 6 | learning_rate: 0.01 7 | smoothness_cost_velocity: 0.0 8 | smoothness_cost_acceleration: 1.0 9 | smoothness_cost_jerk: 0.0 10 | ridge_factor: 0.0 11 | use_pseudo_inverse: false 12 | pseudo_inverse_ridge_factor: 1e-4 13 | joint_update_limit: 0.1 14 | collision_clearance: 0.2 15 | collision_threshold: 0.07 16 | use_stochastic_descent: true 17 | enable_failure_recovery: false 18 | max_recovery_attempts: 5 19 | -------------------------------------------------------------------------------- /config/simple_moveit_controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_list: 2 | - name: $(arg transmission)_joint_trajectory_controller 3 | action_ns: follow_joint_trajectory 4 | type: FollowJointTrajectory 5 | default: True 6 | joints: 7 | - $(arg arm_id)_joint1 8 | - $(arg arm_id)_joint2 9 | - $(arg arm_id)_joint3 10 | - $(arg arm_id)_joint4 11 | - $(arg arm_id)_joint5 12 | - $(arg arm_id)_joint6 13 | - $(arg arm_id)_joint7 14 | - name: franka_gripper 15 | action_ns: gripper_action 16 | type: GripperCommand 17 | default: True 18 | joints: 19 | - $(arg arm_id)_finger_joint1 20 | -------------------------------------------------------------------------------- /launch/fake_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /launch/setup_assistant.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /config/fake_controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_list: 2 | - name: fake_$(arg arm_id)_arm_controller 3 | type: $(arg fake_execution_type) 4 | joints: 5 | - $(arg arm_id)_joint1 6 | - $(arg arm_id)_joint2 7 | - $(arg arm_id)_joint3 8 | - $(arg arm_id)_joint4 9 | - $(arg arm_id)_joint5 10 | - $(arg arm_id)_joint6 11 | - $(arg arm_id)_joint7 12 | 13 | - name: fake_$(arg arm_id)_hand_controller 14 | type: $(arg fake_execution_type) 15 | joints: 16 | - $(arg arm_id)_finger_joint1 17 | 18 | initial: # Define initial robot poses per group 19 | - group: $(arg arm_id)_arm 20 | pose: ready 21 | - group: $(arg arm_id)_hand 22 | pose: open 23 | -------------------------------------------------------------------------------- /launch/joystick_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 15 | 16 | -------------------------------------------------------------------------------- /launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launch/moveit_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /launch/franka_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launch/run_benchmark_trajopt.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launch/ompl_chomp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /launch/lerp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 8 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package panda_moveit_config 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.8.1 (2022-09-11) 6 | ------------------ 7 | * Update to franka_description 0.10.0 (`#119 `_) 8 | * Example use of ns parameter in sensors.yaml (`#88 `_) 9 | * Drop link8 from ACM as this link doesn't have any collision model anymore 10 | * srdf: Use loop macros to reduce code redundancy 11 | * Unify calls to xacro 12 | * Contributors: Matt Droter, Robert Haschke, Tim Redick 13 | 14 | 0.8.0 (2022-09-01) 15 | ------------------ 16 | * Thorough rework based on franka_description 0.9.1 (using fine and coarse collision models) 17 | The internal robot controller uses coarse collision models for self-collision checking. 18 | In MoveIt, these coarse models should be used for self-collision checking only as well. 19 | Particularly, these coarse models should not be used for collision checking with the environment. 20 | -------------------------------------------------------------------------------- /launch/chomp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /config/stomp_planning.yaml: -------------------------------------------------------------------------------- 1 | optimization: 2 | num_timesteps: 60 3 | num_iterations: 40 4 | num_iterations_after_valid: 0 5 | num_rollouts: 30 6 | max_rollouts: 30 7 | initialization_method: 1 #[1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST] 8 | control_cost_weight: 0.0 9 | task: 10 | noise_generator: 11 | - class: stomp_moveit/NormalDistributionSampling 12 | stddev: [0.05, 0.8, 1.0, 0.8, 0.4, 0.4, 0.4] 13 | cost_functions: 14 | - class: stomp_moveit/CollisionCheck 15 | collision_penalty: 1.0 16 | cost_weight: 1.0 17 | kernel_window_percentage: 0.2 18 | longest_valid_joint_move: 0.05 19 | noisy_filters: 20 | - class: stomp_moveit/JointLimits 21 | lock_start: True 22 | lock_goal: True 23 | - class: stomp_moveit/MultiTrajectoryVisualization 24 | line_width: 0.02 25 | rgb: [255, 255, 0] 26 | marker_array_topic: stomp_trajectories 27 | marker_namespace: noisy 28 | update_filters: 29 | - class: stomp_moveit/PolynomialSmoother 30 | poly_order: 6 31 | - class: stomp_moveit/TrajectoryVisualization 32 | line_width: 0.05 33 | rgb: [0, 191, 255] 34 | error_rgb: [255, 0, 0] 35 | publish_intermediate: True 36 | marker_topic: stomp_trajectory 37 | marker_namespace: optimized 38 | -------------------------------------------------------------------------------- /launch/demo_gazebo.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 27 | 28 | 29 | 30 | -------------------------------------------------------------------------------- /launch/ompl_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /config/panda.srdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /launch/planning_context.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | -------------------------------------------------------------------------------- /launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /launch/trajopt_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 14 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | -------------------------------------------------------------------------------- /launch/stomp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 9 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | panda_moveit_config 4 | 0.8.1 5 | 6 | An automatically generated package with all the configuration and launch files for using the panda with the MoveIt Motion Planning Framework 7 | 8 | MoveIt maintainer team 9 | MoveIt maintainer team 10 | 11 | BSD 12 | 13 | http://moveit.ros.org/ 14 | https://github.com/ros-planning/moveit/issues 15 | https://github.com/ros-planning/moveit 16 | 17 | catkin 18 | 19 | moveit_ros_move_group 20 | moveit_fake_controller_manager 21 | moveit_kinematics 22 | moveit_planners 23 | moveit_ros_visualization 24 | moveit_setup_assistant 25 | moveit_simple_controller_manager 26 | joint_state_publisher 27 | joint_state_publisher_gui 28 | robot_state_publisher 29 | rviz 30 | tf2_ros 31 | xacro 32 | 34 | 35 | 36 | 37 | 38 | franka_description 39 | 40 | 41 | -------------------------------------------------------------------------------- /config/joint_limits.yaml: -------------------------------------------------------------------------------- 1 | # joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed 2 | 3 | # For beginners, we downscale velocity and acceleration limits. 4 | # 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. 5 | default_velocity_scaling_factor: 0.1 6 | default_acceleration_scaling_factor: 0.1 7 | 8 | # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] 9 | # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] 10 | 11 | # As MoveIt! does not support jerk limits, the acceleration limits provided here are the highest values that guarantee 12 | # that no jerk limits will be violated. More precisely, applying Euler differentiation in the worst case (from min accel 13 | # to max accel in 1 ms) the acceleration limits are the ones that satisfy 14 | # max_jerk = (max_acceleration - min_acceleration) / 0.001 15 | 16 | joint_limits: 17 | $(arg arm_id)_finger_joint1: 18 | has_velocity_limits: true 19 | max_velocity: 0.1 20 | has_acceleration_limits: false 21 | max_acceleration: 0 22 | $(arg arm_id)_finger_joint2: 23 | has_velocity_limits: true 24 | max_velocity: 0.1 25 | has_acceleration_limits: false 26 | max_acceleration: 0 27 | $(arg arm_id)_joint1: 28 | has_velocity_limits: true 29 | max_velocity: 2.1750 30 | has_acceleration_limits: true 31 | max_acceleration: 3.75 32 | $(arg arm_id)_joint2: 33 | has_velocity_limits: true 34 | max_velocity: 2.1750 35 | has_acceleration_limits: true 36 | max_acceleration: 1.875 37 | $(arg arm_id)_joint3: 38 | has_velocity_limits: true 39 | max_velocity: 2.1750 40 | has_acceleration_limits: true 41 | max_acceleration: 2.5 42 | $(arg arm_id)_joint4: 43 | has_velocity_limits: true 44 | max_velocity: 2.1750 45 | has_acceleration_limits: true 46 | max_acceleration: 3.125 47 | $(arg arm_id)_joint5: 48 | has_velocity_limits: true 49 | max_velocity: 2.6100 50 | has_acceleration_limits: true 51 | max_acceleration: 3.75 52 | $(arg arm_id)_joint6: 53 | has_velocity_limits: true 54 | max_velocity: 2.6100 55 | has_acceleration_limits: true 56 | max_acceleration: 5 57 | $(arg arm_id)_joint7: 58 | has_velocity_limits: true 59 | max_velocity: 2.6100 60 | has_acceleration_limits: true 61 | max_acceleration: 5 62 | 63 | -------------------------------------------------------------------------------- /config/hand.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /launch/demo.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 42 | 43 | [move_group/fake_controller_joint_states] 44 | 45 | 47 | 48 | [move_group/fake_controller_joint_states] 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | -------------------------------------------------------------------------------- /config/trajopt_planning.yaml: -------------------------------------------------------------------------------- 1 | trajopt_param: 2 | improve_ratio_threshold: 0.25 # minimum ratio true_improve/approx_improve to accept step. [Research Paper] TrueImprove/ModelImprove > c 3 | min_trust_box_size: 1e-4 # if trust region gets any smaller, exit and report convergence. [Research Paper] xtol 4 | min_approx_improve: 1e-4 # if model improves less than this, exit and report convergence 5 | min_approx_improve_frac: -.Inf # if model improves less than this, exit and report convergence 6 | max_iter: 100 # The max number of iterations 7 | trust_shrink_ratio: 0.1 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio. [Research Paper] tao- 8 | trust_expand_ratio: 1.5 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio. [Research Paper] tao+ 9 | cnt_tolerance: 1e-4 # after convergence of penalty subproblem, if constraint violation is less than this, we're done. [Research Paper] ctol 10 | max_merit_coeff_increases: 5 # number of times that we jack up penalty coefficient. [Reasearch Paper] Max iteration in PenaltyIteration loop 11 | merit_coeff_increase_ratio: 10 # ratio that we increate coeff each time. [Researcy Paper] Penalty scaling factory (italic kappa) 12 | max_time: .inf # not yet implemented 13 | merit_error_coeff: 10 # initial penalty coefficient. [Research Paper] mu_0 14 | trust_box_size: 1e-1 # current size of trust region (component-wise). [Research Paper] s 15 | 16 | problem_info: 17 | basic_info: 18 | n_steps: 20 # 2 * steps_per_phase 19 | dt_upper_lim: 2.0 # The upper limit of 1/dt values allowed in the optimization 20 | dt_lower_lim: 100.0 # The lower limit of 1/dt values allowed in the optimization 21 | start_fixed: true # if true, start pose is the current pose at timestep = 0 22 | # if false, the start pose is the one given by req.start_state 23 | use_time: false # if false, it means the timestep is unit, meaning x1-x0 is the velocity for example 24 | # if true, then cost_infos ro cnt_infos should have TT_USE_TIME for their term_type 25 | convex_solver: 1 # which convex solver to use 26 | # 1 = AUTO_SOLVER, 2 = BPMPD, 3 = OSQP, 4 = QPOASES, 5 = GUROBI 27 | 28 | init_info: 29 | type: 3 # 1 = STATIONARY, 2 = JOINT_INTERPOLATED, 3 = GIVEN_TRAJ 30 | # request.start_state should be provided for JOINT_INTERPOLATED and GIVEN_TRAJ 31 | dt: 0.5 32 | 33 | joint_pos_term_info: 34 | start_pos: # from req.start_state 35 | name: start_pos 36 | first_timestep: 10 # First time step to which the term is applied. 37 | last_timestep: 10 # Last time step to which the term is applied. 38 | # if start_fixed is trure then we can not set the first_timestep to 0 for start_pos as it is going 39 | # to be ignored and only the current pose would be the constraint at timestep = 0. 40 | term_type: 2 # 1 = TT_COST, 2 = TT_CNT, 3 = TT_USE_TIME 41 | middle_pos: 42 | name: middle_pos 43 | first_timestep: 15 44 | last_timestep: 15 45 | term_type: 2 46 | goal_pos: 47 | name: goal_pos 48 | first_timestep: 19 49 | last_timestep: 19 50 | term_type: 2 51 | goal_tmp: # If the constraint from request does not have any name, for example when using MotionPlanning Display in Rviz, 52 | # goal_tmp is assigned as the name of the constraint. 53 | # In this case: start_fixed = false and start_pos should be applied at timestep 0 54 | # OR: start_fixed = true and start_pos can be applies at any timestep 55 | name: goal_tmp 56 | first_timestep: 19 # n_steps - 1 57 | last_timestep: 19 # n_steps - 1 58 | term_type: 2 59 | -------------------------------------------------------------------------------- /launch/moveit_empty.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 84 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: ~ 7 | Splitter Ratio: 0.5 8 | Tree Height: 613 9 | - Class: rviz/Help 10 | Name: Help 11 | - Class: rviz/Views 12 | Expanded: 13 | - /Current View1 14 | Name: Views 15 | Splitter Ratio: 0.5 16 | Preferences: 17 | PromptSaveOnExit: true 18 | Toolbars: 19 | toolButtonStyle: 2 20 | Visualization Manager: 21 | Class: "" 22 | Displays: 23 | - Alpha: 0.5 24 | Cell Size: 1 25 | Class: rviz/Grid 26 | Color: 160; 160; 164 27 | Enabled: true 28 | Line Style: 29 | Line Width: 0.029999999329447746 30 | Value: Lines 31 | Name: Grid 32 | Normal Cell Count: 0 33 | Offset: 34 | X: 0 35 | Y: 0 36 | Z: 0 37 | Plane: XY 38 | Plane Cell Count: 10 39 | Reference Frame: 40 | Value: true 41 | - Class: rviz/MarkerArray 42 | Enabled: true 43 | Marker Topic: rviz_visual_tools 44 | Name: MarkerArray 45 | Namespaces: 46 | {} 47 | Queue Size: 100 48 | Value: true 49 | Enabled: true 50 | Global Options: 51 | Background Color: 48; 48; 48 52 | Default Light: true 53 | Fixed Frame: panda_link0 54 | Frame Rate: 30 55 | Name: root 56 | Tools: 57 | - Class: rviz/Interact 58 | Hide Inactive Objects: true 59 | - Class: rviz/MoveCamera 60 | - Class: rviz/Select 61 | - Class: rviz_visual_tools/KeyTool 62 | Value: true 63 | Views: 64 | Current: 65 | Class: rviz/Orbit 66 | Distance: 2 67 | Enable Stereo Rendering: 68 | Stereo Eye Separation: 0.05999999865889549 69 | Stereo Focal Distance: 1 70 | Swap Stereo Eyes: false 71 | Value: false 72 | Field of View: 0.75 73 | Focal Point: 74 | X: -0.10000000149011612 75 | Y: 0.25 76 | Z: 0.30000001192092896 77 | Focal Shape Fixed Size: true 78 | Focal Shape Size: 0.05000000074505806 79 | Invert Z Axis: false 80 | Name: Current View 81 | Near Clip Distance: 0.009999999776482582 82 | Pitch: 0.5 83 | Target Frame: panda_link0 84 | Yaw: -0.6232355833053589 85 | Saved: ~ 86 | Window Geometry: 87 | Displays: 88 | collapsed: false 89 | Height: 848 90 | Help: 91 | collapsed: false 92 | Hide Left Dock: false 93 | Hide Right Dock: false 94 | QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc020000000afb000000100044006900730070006c006100790073010000003d000002f6000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006700000001ab000001880000000000000000fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb00000024005200760069007a00560069007300750061006c0054006f006f006c007300470075006900000002f2000000410000000000000000fb0000003c005400720061006a006500630074006f007200790020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff000000000000000000000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 95 | Views: 96 | collapsed: false 97 | Width: 1291 98 | X: 444 99 | Y: 25 100 | -------------------------------------------------------------------------------- /launch/moveit.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 84 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: 7 | - /MotionPlanning1 8 | Splitter Ratio: 0.5 9 | Tree Height: 226 10 | - Class: rviz/Help 11 | Name: Help 12 | - Class: rviz/Views 13 | Expanded: 14 | - /Current View1 15 | Name: Views 16 | Splitter Ratio: 0.5 17 | Visualization Manager: 18 | Class: "" 19 | Displays: 20 | - Alpha: 0.5 21 | Cell Size: 1 22 | Class: rviz/Grid 23 | Color: 160; 160; 164 24 | Enabled: true 25 | Line Style: 26 | Line Width: 0.03 27 | Value: Lines 28 | Name: Grid 29 | Normal Cell Count: 0 30 | Offset: 31 | X: 0 32 | Y: 0 33 | Z: 0 34 | Plane: XY 35 | Plane Cell Count: 10 36 | Reference Frame: 37 | Value: true 38 | - Class: moveit_rviz_plugin/MotionPlanning 39 | Enabled: true 40 | Name: MotionPlanning 41 | Planned Path: 42 | Links: ~ 43 | Loop Animation: true 44 | Robot Alpha: 0.5 45 | Show Robot Collision: false 46 | Show Robot Visual: true 47 | Show Trail: false 48 | State Display Time: 0.05 s 49 | Trajectory Topic: move_group/display_planned_path 50 | Planning Metrics: 51 | Payload: 1 52 | Show Joint Torques: false 53 | Show Manipulability: false 54 | Show Manipulability Index: false 55 | Show Weight Limit: false 56 | Planning Request: 57 | Colliding Link Color: 255; 0; 0 58 | Goal State Alpha: 1 59 | Goal State Color: 250; 128; 0 60 | Interactive Marker Size: 0 61 | Joint Violation Color: 255; 0; 255 62 | Query Goal State: true 63 | Query Start State: false 64 | Show Workspace: false 65 | Start State Alpha: 1 66 | Start State Color: 0; 255; 0 67 | Planning Scene Topic: move_group/monitored_planning_scene 68 | Robot Description: robot_description 69 | Scene Geometry: 70 | Scene Alpha: 1 71 | Show Scene Geometry: true 72 | Voxel Coloring: Z-Axis 73 | Voxel Rendering: Occupied Voxels 74 | Scene Robot: 75 | Attached Body Color: 150; 50; 150 76 | Links: ~ 77 | Robot Alpha: 0.5 78 | Show Scene Robot: true 79 | Value: true 80 | Enabled: true 81 | Global Options: 82 | Background Color: 48; 48; 48 83 | Fixed Frame: panda_link0 84 | Name: root 85 | Tools: 86 | - Class: rviz/Interact 87 | Hide Inactive Objects: true 88 | - Class: rviz/MoveCamera 89 | - Class: rviz/Select 90 | Value: true 91 | Views: 92 | Current: 93 | Class: rviz/Orbit 94 | Distance: 2.0 95 | Enable Stereo Rendering: 96 | Stereo Eye Separation: 0.06 97 | Stereo Focal Distance: 1 98 | Swap Stereo Eyes: false 99 | Value: false 100 | Field of View: 0.75 101 | Focal Point: 102 | X: -0.1 103 | Y: 0.25 104 | Z: 0.30 105 | Focal Shape Fixed Size: true 106 | Focal Shape Size: 0.05 107 | Invert Z Axis: false 108 | Name: Current View 109 | Near Clip Distance: 0.01 110 | Pitch: 0.5 111 | Target Frame: panda_link0 112 | Yaw: -0.6232355833053589 113 | Saved: ~ 114 | Window Geometry: 115 | Displays: 116 | collapsed: false 117 | Height: 848 118 | Help: 119 | collapsed: false 120 | Hide Left Dock: false 121 | Hide Right Dock: false 122 | MotionPlanning: 123 | collapsed: false 124 | MotionPlanning - Trajectory Slider: 125 | collapsed: false 126 | QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc0200000007fb000000100044006900730070006c006100790073010000003d00000173000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001b60000017d0000017d00ffffff00000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 127 | Views: 128 | collapsed: false 129 | Width: 1291 130 | X: 454 131 | Y: 25 132 | -------------------------------------------------------------------------------- /config/arm.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | -------------------------------------------------------------------------------- /launch/moveit_scene.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 84 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: ~ 7 | Splitter Ratio: 0.5 8 | Tree Height: 542 9 | - Class: rviz/Help 10 | Name: Help 11 | - Class: rviz/Views 12 | Expanded: 13 | - /Current View1 14 | Name: Views 15 | Splitter Ratio: 0.5 16 | - Class: rviz_visual_tools/RvizVisualToolsGui 17 | Name: RvizVisualToolsGui 18 | Preferences: 19 | PromptSaveOnExit: true 20 | Toolbars: 21 | toolButtonStyle: 2 22 | Visualization Manager: 23 | Class: "" 24 | Displays: 25 | - Alpha: 0.5 26 | Cell Size: 1 27 | Class: rviz/Grid 28 | Color: 160; 160; 164 29 | Enabled: true 30 | Line Style: 31 | Line Width: 0.03 32 | Value: Lines 33 | Name: Grid 34 | Normal Cell Count: 0 35 | Offset: 36 | X: 0 37 | Y: 0 38 | Z: 0 39 | Plane: XY 40 | Plane Cell Count: 10 41 | Reference Frame: 42 | Value: true 43 | - Class: rviz/MarkerArray 44 | Enabled: true 45 | Marker Topic: rviz_visual_tools 46 | Name: MarkerArray 47 | Namespaces: 48 | {} 49 | Queue Size: 100 50 | Value: true 51 | - Class: moveit_rviz_plugin/Trajectory 52 | Color Enabled: false 53 | Enabled: true 54 | Interrupt Display: false 55 | Links: ~ 56 | Loop Animation: false 57 | Name: Trajectory 58 | Robot Alpha: 0.5 59 | Show Robot Collision: false 60 | Show Robot Visual: true 61 | Show Trail: false 62 | State Display Time: 3x 63 | Trail Step Size: 1 64 | Trajectory Topic: move_group/display_planned_path 65 | Value: true 66 | - Class: moveit_rviz_plugin/PlanningScene 67 | Enabled: true 68 | Move Group Namespace: "" 69 | Name: PlanningScene 70 | Planning Scene Topic: move_group/monitored_planning_scene 71 | Robot Description: robot_description 72 | Scene Geometry: 73 | Scene Alpha: 0.9 74 | Show Scene Geometry: true 75 | Voxel Coloring: Z-Axis 76 | Voxel Rendering: Occupied Voxels 77 | Scene Robot: 78 | Attached Body Color: 150; 50; 150 79 | Links: ~ 80 | Robot Alpha: 1 81 | Show Robot Collision: false 82 | Show Robot Visual: true 83 | Value: true 84 | Enabled: true 85 | Global Options: 86 | Background Color: 48; 48; 48 87 | Default Light: true 88 | Fixed Frame: panda_link0 89 | Frame Rate: 30 90 | Name: root 91 | Tools: 92 | - Class: rviz/Interact 93 | Hide Inactive Objects: true 94 | - Class: rviz/MoveCamera 95 | - Class: rviz/Select 96 | - Class: rviz_visual_tools/KeyTool 97 | Value: true 98 | Views: 99 | Current: 100 | Class: rviz/Orbit 101 | Distance: 2.0 102 | Enable Stereo Rendering: 103 | Stereo Eye Separation: 0.06 104 | Stereo Focal Distance: 1 105 | Swap Stereo Eyes: false 106 | Value: false 107 | Field of View: 0.75 108 | Focal Point: 109 | X: -0.1 110 | Y: 0.25 111 | Z: 0.30 112 | Focal Shape Fixed Size: true 113 | Focal Shape Size: 0.05 114 | Invert Z Axis: false 115 | Name: Current View 116 | Near Clip Distance: 0.01 117 | Pitch: 0.5 118 | Target Frame: panda_link0 119 | Yaw: -0.6232355833053589 120 | Saved: ~ 121 | Window Geometry: 122 | Displays: 123 | collapsed: false 124 | Height: 848 125 | Help: 126 | collapsed: false 127 | Hide Left Dock: false 128 | Hide Right Dock: false 129 | QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc0200000009fb000000100044006900730070006c006100790073010000003d000002af000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006700000001ab000001880000000000000000fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb00000024005200760069007a00560069007300750061006c0054006f006f006c007300470075006901000002f2000000410000004100ffffff00000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 130 | RvizVisualToolsGui: 131 | collapsed: false 132 | Trajectory - Slider: 133 | collapsed: false 134 | Views: 135 | collapsed: false 136 | Width: 1291 137 | X: 449 138 | Y: 25 139 | -------------------------------------------------------------------------------- /launch/move_group.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 37 | 38 | 39 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | -------------------------------------------------------------------------------- /config/ompl_planning.yaml: -------------------------------------------------------------------------------- 1 | planner_configs: 2 | AnytimePathShortening: 3 | type: geometric::AnytimePathShortening 4 | shortcut: true # Attempt to shortcut all new solution paths 5 | hybridize: true # Compute hybrid solution trajectories 6 | max_hybrid_paths: 24 # Number of hybrid paths generated per iteration 7 | num_planners: 4 # The number of default planners to use for planning 8 | 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]" 9 | SBL: 10 | type: geometric::SBL 11 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 12 | EST: 13 | type: geometric::EST 14 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() 15 | goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 16 | LBKPIECE: 17 | type: geometric::LBKPIECE 18 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 19 | border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 20 | min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 21 | BKPIECE: 22 | type: geometric::BKPIECE 23 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 24 | border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 25 | failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 26 | min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 27 | KPIECE: 28 | type: geometric::KPIECE 29 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 30 | goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 31 | border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] 32 | failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 33 | min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 34 | RRT: 35 | type: geometric::RRT 36 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 37 | goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 38 | RRTConnect: 39 | type: geometric::RRTConnect 40 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 41 | RRTstar: 42 | type: geometric::RRTstar 43 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 44 | goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 45 | delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 46 | TRRT: 47 | type: geometric::TRRT 48 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 49 | goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 50 | max_states_failed: 10 # when to start increasing temp. default: 10 51 | temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 52 | min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 53 | init_temperature: 10e-6 # initial temperature. default: 10e-6 54 | frontier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() 55 | frontier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 56 | k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() 57 | PRM: 58 | type: geometric::PRM 59 | max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 60 | PRMstar: 61 | type: geometric::PRMstar 62 | FMT: 63 | type: geometric::FMT 64 | num_samples: 1000 # number of states that the planner should sample. default: 1000 65 | radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 66 | nearest_k: 1 # use Knearest strategy. default: 1 67 | cache_cc: 1 # use collision checking cache. default: 1 68 | heuristics: 0 # activate cost to go heuristics. default: 0 69 | extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 70 | BFMT: 71 | type: geometric::BFMT 72 | num_samples: 1000 # number of states that the planner should sample. default: 1000 73 | radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 74 | nearest_k: 1 # use the Knearest strategy. default: 1 75 | balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 76 | 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 77 | heuristics: 1 # activates cost to go heuristics. default: 1 78 | cache_cc: 1 # use the collision checking cache. default: 1 79 | extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 80 | PDST: 81 | type: geometric::PDST 82 | STRIDE: 83 | type: geometric::STRIDE 84 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 85 | goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 86 | 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 87 | degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 88 | max_degree: 18 # max degree of a node in the GNAT. default: 12 89 | min_degree: 12 # min degree of a node in the GNAT. default: 12 90 | max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 91 | estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 92 | min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 93 | BiTRRT: 94 | type: geometric::BiTRRT 95 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 96 | temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 97 | init_temperature: 100 # initial temperature. default: 100 98 | frontier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() 99 | frontier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 100 | cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf 101 | LBTRRT: 102 | type: geometric::LBTRRT 103 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 104 | goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 105 | epsilon: 0.4 # optimality approximation factor. default: 0.4 106 | BiEST: 107 | type: geometric::BiEST 108 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 109 | ProjEST: 110 | type: geometric::ProjEST 111 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 112 | goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 113 | LazyPRM: 114 | type: geometric::LazyPRM 115 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 116 | LazyPRMstar: 117 | type: geometric::LazyPRMstar 118 | SPARS: 119 | type: geometric::SPARS 120 | 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 121 | sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 122 | dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 123 | max_failures: 1000 # maximum consecutive failure limit. default: 1000 124 | SPARStwo: 125 | type: geometric::SPARStwo 126 | 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 127 | sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 128 | dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 129 | max_failures: 5000 # maximum consecutive failure limit. default: 5000 130 | AITstar: 131 | type: geometric::AITstar 132 | use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1 133 | rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001 134 | samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100 135 | use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1 136 | find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0 137 | set_max_num_goals: 1 # maximum number of goals sampled from sampleable goal regions. Valid values: [1:1:1000]. Default: 1 138 | ABITstar: 139 | type: geometric::ABITstar 140 | use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1 141 | rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001 142 | samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100 143 | use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1 144 | prune_threshold_as_fractional_cost_change: 0.1 # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1 145 | delay_rewiring_to_first_solution: 0 # delay (1) or not (0) rewiring until a solution is found. Default: 0 146 | use_just_in_time_sampling: 0 # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0 147 | drop_unconnected_samples_on_prune: 0 # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0 148 | stop_on_each_solution_improvement: 0 # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0 149 | use_strict_queue_ordering: 0 # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0 150 | find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0 151 | initial_inflation_factor: 1000000 # inflation factor for the initial search. Valid values: [1.0:0.01:1000000.0]. Default: 1000000 152 | inflation_scaling_parameter: 10 # scaling parameter for the inflation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0 153 | truncation_scaling_parameter: 5.0 # scaling parameter for the truncation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0 154 | BITstar: 155 | type: geometric::BITstar 156 | use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1 157 | rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001 158 | samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100 159 | use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1 160 | prune_threshold_as_fractional_cost_change: 0.1 # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1 161 | delay_rewiring_to_first_solution: 0 # delay (1) or not (0) rewiring until a solution is found. Default: 0 162 | use_just_in_time_sampling: 0 # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0 163 | drop_unconnected_samples_on_prune: 0 # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0 164 | stop_on_each_solution_improvement: 0 # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0 165 | use_strict_queue_ordering: 0 # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0 166 | find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0 167 | $(arg arm_id)_arm: &arm_config 168 | planner_configs: 169 | - AnytimePathShortening 170 | - SBL 171 | - EST 172 | - LBKPIECE 173 | - BKPIECE 174 | - KPIECE 175 | - RRT 176 | - RRTConnect 177 | - RRTstar 178 | - TRRT 179 | - PRM 180 | - PRMstar 181 | - FMT 182 | - BFMT 183 | - PDST 184 | - STRIDE 185 | - BiTRRT 186 | - LBTRRT 187 | - BiEST 188 | - ProjEST 189 | - LazyPRM 190 | - LazyPRMstar 191 | - SPARS 192 | - SPARStwo 193 | - AITstar 194 | - ABITstar 195 | - BITstar 196 | projection_evaluator: joints($(arg arm_id)_joint1,$(arg arm_id)_joint2) 197 | longest_valid_segment_fraction: 0.005 198 | $(arg arm_id)_manipulator: *arm_config 199 | $(arg arm_id)_hand: 200 | planner_configs: 201 | - AnytimePathShortening 202 | - SBL 203 | - EST 204 | - LBKPIECE 205 | - BKPIECE 206 | - KPIECE 207 | - RRT 208 | - RRTConnect 209 | - RRTstar 210 | - TRRT 211 | - PRM 212 | - PRMstar 213 | - FMT 214 | - BFMT 215 | - PDST 216 | - STRIDE 217 | - BiTRRT 218 | - LBTRRT 219 | - BiEST 220 | - ProjEST 221 | - LazyPRM 222 | - LazyPRMstar 223 | - SPARS 224 | - SPARStwo 225 | - AITstar 226 | - ABITstar 227 | - BITstar 228 | --------------------------------------------------------------------------------