diff --git a/fanuc_moveit_config/config/chomp_planning.yaml b/fanuc_moveit_config/config/chomp_planning.yaml index f98e1c53..96950bc6 100644 --- a/fanuc_moveit_config/config/chomp_planning.yaml +++ b/fanuc_moveit_config/config/chomp_planning.yaml @@ -1,3 +1,11 @@ +planning_plugin: chomp_interface/CHOMPPlanner +request_adapters: >- + default_planner_request_adapters/AddTimeParameterization + default_planner_request_adapters/FixWorkspaceBounds + default_planner_request_adapters/FixStartStateBounds + default_planner_request_adapters/FixStartStateCollision + default_planner_request_adapters/FixStartStatePathConstraints +start_state_max_bounds_error: 0.1 planning_time_limit: 10.0 max_iterations: 200 max_iterations_after_collision_free: 5 diff --git a/fanuc_moveit_config/config/fake_controllers.yaml b/fanuc_moveit_config/config/fake_controllers.yaml deleted file mode 100644 index 19cd38ef..00000000 --- a/fanuc_moveit_config/config/fake_controllers.yaml +++ /dev/null @@ -1,12 +0,0 @@ -controller_list: - - name: fake_manipulator_controller - joints: - - joint_1 - - joint_2 - - joint_3 - - joint_4 - - joint_5 - - joint_6 -initial: # Define initial robot poses. - - group: manipulator - pose: all-zeros diff --git a/fanuc_moveit_config/config/fanuc.ros2_control.xacro b/fanuc_moveit_config/config/fanuc.ros2_control.xacro new file mode 100644 index 00000000..f9c2c58b --- /dev/null +++ b/fanuc_moveit_config/config/fanuc.ros2_control.xacro @@ -0,0 +1,55 @@ + + + + + + + + + fake_components/GenericSystem + + + + + ${initial_positions['joint_1']} + + + + + + + ${initial_positions['joint_2']} + + + + + + + ${initial_positions['joint_3']} + + + + + + + ${initial_positions['joint_4']} + + + + + + + ${initial_positions['joint_5']} + + + + + + + ${initial_positions['joint_6']} + + + + + + diff --git a/fanuc_moveit_config/config/fanuc.urdf.xacro b/fanuc_moveit_config/config/fanuc.urdf.xacro new file mode 100644 index 00000000..c2077df3 --- /dev/null +++ b/fanuc_moveit_config/config/fanuc.urdf.xacro @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/fanuc_moveit_config/config/initial_positions.yaml b/fanuc_moveit_config/config/initial_positions.yaml new file mode 100644 index 00000000..842abde6 --- /dev/null +++ b/fanuc_moveit_config/config/initial_positions.yaml @@ -0,0 +1,8 @@ +# Default initial positions for the FANUC arm's ros2_control fake system +initial_positions: + joint_1: 0.0 + joint_2: 0.0 + joint_3: 0.0 + joint_4: 0.0 + joint_5: 0.0 + joint_6: 0.0 diff --git a/fanuc_moveit_config/config/moveit_controllers.yaml b/fanuc_moveit_config/config/moveit_controllers.yaml new file mode 100644 index 00000000..96e83ac3 --- /dev/null +++ b/fanuc_moveit_config/config/moveit_controllers.yaml @@ -0,0 +1,23 @@ +# MoveIt uses this configuration for controller management +trajectory_execution: + allowed_execution_duration_scaling: 1.2 + allowed_goal_duration_margin: 0.5 + allowed_start_tolerance: 0.01 + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - fanuc_controller + + fanuc_controller: + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: true + joints: + - joint_1 + - joint_2 + - joint_3 + - joint_4 + - joint_5 + - joint_6 diff --git a/fanuc_moveit_config/config/ompl_planning.yaml b/fanuc_moveit_config/config/ompl_planning.yaml index 96d846b6..9076dd64 100644 --- a/fanuc_moveit_config/config/ompl_planning.yaml +++ b/fanuc_moveit_config/config/ompl_planning.yaml @@ -1,3 +1,12 @@ +planning_plugin: ompl_interface/OMPLPlanner +request_adapters: >- + default_planner_request_adapters/AddTimeOptimalParameterization + default_planner_request_adapters/ResolveConstraintFrames + default_planner_request_adapters/FixWorkspaceBounds + default_planner_request_adapters/FixStartStateBounds + default_planner_request_adapters/FixStartStateCollision + default_planner_request_adapters/FixStartStatePathConstraints +start_state_max_bounds_error: 0.1 planner_configs: AnytimePathShortening: type: geometric::AnytimePathShortening diff --git a/fanuc_moveit_config/config/ros2_controllers.yaml b/fanuc_moveit_config/config/ros2_controllers.yaml new file mode 100644 index 00000000..f70562e6 --- /dev/null +++ b/fanuc_moveit_config/config/ros2_controllers.yaml @@ -0,0 +1,26 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + fanuc_controller: + type: joint_trajectory_controller/JointTrajectoryController + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + +fanuc_controller: + ros__parameters: + command_interfaces: + - position + state_interfaces: + - position + - velocity + joints: + - joint_1 + - joint_2 + - joint_3 + - joint_4 + - joint_5 + - joint_6 diff --git a/fanuc_moveit_config/config/ros_controllers.yaml b/fanuc_moveit_config/config/ros_controllers.yaml deleted file mode 100644 index 1806f48d..00000000 --- a/fanuc_moveit_config/config/ros_controllers.yaml +++ /dev/null @@ -1,35 +0,0 @@ -# Simulation settings for using moveit_sim_controllers -moveit_sim_hw_interface: - joint_model_group: manipulator - joint_model_group_pose: all-zeros -# Settings for ros_control_boilerplate control loop -generic_hw_control_loop: - loop_hz: 300 - cycle_time_error_threshold: 0.01 -# Settings for ros_control hardware interface -hardware_interface: - joints: - - joint_1 - - joint_2 - - joint_3 - - joint_4 - - joint_5 - - joint_6 - sim_control_mode: 1 # 0: position, 1: velocity -# Publish all joint states -# Creates the /joint_states topic necessary in ROS -joint_state_broadcaster: - type: joint_state_broadcaster/JointStateBroadcaster - publish_rate: 50 -controller_list: - - name: manipulator_controller - action_ns: follow_joint_trajectory - default: True - type: FollowJointTrajectory - joints: - - joint_1 - - joint_2 - - joint_3 - - joint_4 - - joint_5 - - joint_6 diff --git a/fanuc_moveit_config/launch/chomp_planning_pipeline.launch.xml b/fanuc_moveit_config/launch/chomp_planning_pipeline.launch.xml deleted file mode 100644 index d0e8dd37..00000000 --- a/fanuc_moveit_config/launch/chomp_planning_pipeline.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/default_warehouse_db.launch b/fanuc_moveit_config/launch/default_warehouse_db.launch deleted file mode 100644 index e588849e..00000000 --- a/fanuc_moveit_config/launch/default_warehouse_db.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/demo.launch b/fanuc_moveit_config/launch/demo.launch deleted file mode 100644 index d577b415..00000000 --- a/fanuc_moveit_config/launch/demo.launch +++ /dev/null @@ -1,62 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [move_group/fake_controller_joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/demo.launch.py b/fanuc_moveit_config/launch/demo.launch.py new file mode 100644 index 00000000..e17d51bb --- /dev/null +++ b/fanuc_moveit_config/launch/demo.launch.py @@ -0,0 +1,122 @@ +import os +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition +from launch_ros.actions import Node +from launch.actions import ExecuteProcess +from ament_index_python.packages import get_package_share_directory +from moveit_configs_utils import MoveItConfigsBuilder + + +def generate_launch_description(): + + # Command-line arguments + db_arg = DeclareLaunchArgument( + "db", default_value="False", description="Database flag" + ) + + moveit_config = ( + MoveItConfigsBuilder("moveit_resources_fanuc") + .robot_description(file_path="config/fanuc.urdf.xacro") + .robot_description_semantic(file_path="config/fanuc.srdf") + .trajectory_execution(file_path="config/moveit_controllers.yaml") + .to_moveit_configs() + ) + + # Start the actual move_group node/action server + run_move_group_node = Node( + package="moveit_ros_move_group", + executable="move_group", + output="screen", + parameters=[moveit_config.to_dict()], + ) + + # RViz + rviz_base = os.path.join( + get_package_share_directory("moveit_resources_fanuc_moveit_config"), "launch" + ) + rviz_full_config = os.path.join(rviz_base, "moveit.rviz") + + rviz_node = Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output="log", + arguments=["-d", rviz_full_config], + parameters=[ + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ], + ) + + # Static TF + static_tf = Node( + package="tf2_ros", + executable="static_transform_publisher", + name="static_transform_publisher", + output="log", + arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "world", "base_link"], + ) + + # Publish TF + robot_state_publisher = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + name="robot_state_publisher", + output="both", + parameters=[moveit_config.robot_description], + ) + + # ros2_control using FakeSystem as hardware + ros2_controllers_path = os.path.join( + get_package_share_directory("moveit_resources_fanuc_moveit_config"), + "config", + "ros2_controllers.yaml", + ) + ros2_control_node = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[moveit_config.robot_description, ros2_controllers_path], + output="both", + ) + + # Load controllers + load_controllers = [] + for controller in ["fanuc_controller", "joint_state_broadcaster"]: + load_controllers += [ + ExecuteProcess( + cmd=["ros2 run controller_manager spawner {}".format(controller)], + shell=True, + output="screen", + ) + ] + + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + mongodb_server_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + + return LaunchDescription( + [ + db_arg, + rviz_node, + static_tf, + robot_state_publisher, + run_move_group_node, + ros2_control_node, + mongodb_server_node, + ] + + load_controllers + ) diff --git a/fanuc_moveit_config/launch/demo_chomp.launch b/fanuc_moveit_config/launch/demo_chomp.launch deleted file mode 100644 index 797d3225..00000000 --- a/fanuc_moveit_config/launch/demo_chomp.launch +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - [/move_group/fake_controller_joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/demo_gazebo.launch b/fanuc_moveit_config/launch/demo_gazebo.launch deleted file mode 100644 index f9d704d1..00000000 --- a/fanuc_moveit_config/launch/demo_gazebo.launch +++ /dev/null @@ -1,70 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [/joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/fanuc_moveit_config/launch/fake_moveit_controller_manager.launch.xml deleted file mode 100644 index 8a44cf5e..00000000 --- a/fanuc_moveit_config/launch/fake_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/fanuc_moveit_config/launch/fanuc_moveit_controller_manager.launch.xml b/fanuc_moveit_config/launch/fanuc_moveit_controller_manager.launch.xml deleted file mode 100644 index ac5e62be..00000000 --- a/fanuc_moveit_config/launch/fanuc_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - diff --git a/fanuc_moveit_config/launch/fanuc_moveit_sensor_manager.launch.xml b/fanuc_moveit_config/launch/fanuc_moveit_sensor_manager.launch.xml deleted file mode 100644 index 5d02698d..00000000 --- a/fanuc_moveit_config/launch/fanuc_moveit_sensor_manager.launch.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/fanuc_moveit_config/launch/gazebo.launch b/fanuc_moveit_config/launch/gazebo.launch deleted file mode 100644 index 85f9ff9f..00000000 --- a/fanuc_moveit_config/launch/gazebo.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/joystick_control.launch b/fanuc_moveit_config/launch/joystick_control.launch deleted file mode 100644 index 9411f6e6..00000000 --- a/fanuc_moveit_config/launch/joystick_control.launch +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/move_group.launch b/fanuc_moveit_config/launch/move_group.launch deleted file mode 100644 index b6b02dcd..00000000 --- a/fanuc_moveit_config/launch/move_group.launch +++ /dev/null @@ -1,82 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/moveit.rviz b/fanuc_moveit_config/launch/moveit.rviz index d411f27b..f1f2802c 100644 --- a/fanuc_moveit_config/launch/moveit.rviz +++ b/fanuc_moveit_config/launch/moveit.rviz @@ -1,15 +1,20 @@ Panels: - - Class: rviz/Displays - Help Height: 84 + - Class: rviz_common/Displays + Help Height: 78 Name: Displays Property Tree Widget: - Expanded: - - /MotionPlanning1 - Splitter Ratio: 0.74256 - Tree Height: 664 - - Class: rviz/Help - Name: Help - - Class: rviz/Views + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 423 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views Expanded: - /Current View1 Name: Views @@ -19,11 +24,11 @@ Visualization Manager: Displays: - Alpha: 0.5 Cell Size: 1 - Class: rviz/Grid + Class: rviz_default_plugins/Grid Color: 160; 160; 164 Enabled: true Line Style: - Line Width: 0.03 + Line Width: 0.029999999329447746 Value: Lines Name: Grid Normal Cell Count: 0 @@ -35,302 +40,233 @@ Visualization Manager: Plane Cell Count: 10 Reference Frame: Value: true - - Class: moveit_rviz_plugin/MotionPlanning + - Class: rviz_default_plugins/MarkerArray Enabled: true - MoveIt_Goal_Tolerance: 0 - MoveIt_Planning_Time: 5 - MoveIt_Use_Constraint_Aware_IK: true - MoveIt_Warehouse_Host: 127.0.0.1 - MoveIt_Warehouse_Port: 33829 - Name: MotionPlanning - Planned Path: + Name: MarkerArray + Namespaces: + {} + Topic: + Depth: 100 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /rviz_visual_tools + Value: true + - Class: moveit_rviz_plugin/Trajectory + Color Enabled: false + Enabled: true + Interrupt Display: false + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + Loop Animation: false + Name: Trajectory + Robot Alpha: 0.5 + Robot Color: 150; 50; 150 + Robot Description: robot_description + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trail Step Size: 1 + Trajectory Topic: /display_planned_path + Value: true + - Class: moveit_rviz_plugin/PlanningScene + Enabled: true + Move Group Namespace: "" + Name: PlanningScene + Planning Scene Topic: /monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 0.8999999761581421 + Scene Color: 50; 230; 50 + Scene Display Time: 0.009999999776482582 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 Links: - base_bellow_link: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base: Alpha: 1 Show Axes: false Show Trail: false - Value: true - base_footprint: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true base_link: Alpha: 1 Show Axes: false Show Trail: false Value: true - bl_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bl_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bl_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - br_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - br_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - br_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - double_stereo_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fl_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fl_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fl_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_kinect_ir_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_kinect_rgb_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_prosilica_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_plate_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_tilt_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_elbow_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_forearm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_l_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_l_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_motor_accelerometer_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_palm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_r_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_r_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_shoulder_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_shoulder_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_upper_arm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_wrist_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_wrist_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - laser_tilt_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_elbow_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_forearm_link: + link_1: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_forearm_roll_link: + link_2: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_gripper_l_finger_link: + link_3: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_gripper_l_finger_tip_link: + link_4: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_gripper_motor_accelerometer_link: + link_5: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_gripper_palm_link: + link_6: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_gripper_r_finger_link: + tool0: Alpha: 1 Show Axes: false Show Trail: false - Value: true - r_gripper_r_finger_tip_link: + Robot Alpha: 1 + Show Robot Collision: false + Show Robot Visual: true + Value: true + - Acceleration_Scaling_Factor: 0.1 + Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + Move Group Namespace: "" + MoveIt_Allow_Approximate_IK: false + 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: false + 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: Alpha: 1 Show Axes: false Show Trail: false - Value: true - r_shoulder_lift_link: + base_link: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_shoulder_pan_link: + link_1: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_upper_arm_link: + link_2: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_upper_arm_roll_link: + link_3: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_wrist_flex_link: + link_4: Alpha: 1 Show Axes: false Show Trail: false Value: true - r_wrist_roll_link: + link_5: Alpha: 1 Show Axes: false Show Trail: false Value: true - sensor_mount_link: + link_6: Alpha: 1 Show Axes: false Show Trail: false Value: true - torso_lift_link: + tool0: Alpha: 1 Show Axes: false Show Trail: false - Value: true - Loop Animation: 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 + State Display Time: 3x + Trail Step Size: 1 Trajectory Topic: /display_planned_path Planning Metrics: Payload: 1 @@ -338,13 +274,14 @@ Visualization Manager: 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: left_arm + Planning Group: manipulator Query Goal State: true Query Start State: false Show Workspace: false @@ -353,337 +290,153 @@ Visualization Manager: Planning Scene Topic: /monitored_planning_scene Robot Description: robot_description Scene Geometry: - Scene Alpha: 1 + Scene Alpha: 0.8999999761581421 Scene Color: 50; 230; 50 - Scene Display Time: 0.2 + Scene Display Time: 0.009999999776482582 Show Scene Geometry: true Voxel Coloring: Z-Axis Voxel Rendering: Occupied Voxels Scene Robot: Attached Body Color: 150; 50; 150 Links: - base_bellow_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - base_footprint: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base: Alpha: 1 Show Axes: false Show Trail: false - Value: true base_link: Alpha: 1 Show Axes: false Show Trail: false Value: true - bl_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bl_caster_r_wheel_link: + link_1: Alpha: 1 Show Axes: false Show Trail: false Value: true - bl_caster_rotation_link: + link_2: Alpha: 1 Show Axes: false Show Trail: false Value: true - br_caster_l_wheel_link: + link_3: Alpha: 1 Show Axes: false Show Trail: false Value: true - br_caster_r_wheel_link: + link_4: Alpha: 1 Show Axes: false Show Trail: false Value: true - br_caster_rotation_link: + link_5: Alpha: 1 Show Axes: false Show Trail: false Value: true - double_stereo_link: + link_6: Alpha: 1 Show Axes: false Show Trail: false Value: true - fl_caster_l_wheel_link: + tool0: Alpha: 1 Show Axes: false Show Trail: false - Value: true - fl_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fl_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_kinect_ir_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_kinect_rgb_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_prosilica_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_plate_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_tilt_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_elbow_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_forearm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_l_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_l_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_motor_accelerometer_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_palm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_r_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_r_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_shoulder_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_shoulder_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_upper_arm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_wrist_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_wrist_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - laser_tilt_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_elbow_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_forearm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_l_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_l_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_motor_accelerometer_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_palm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_r_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_r_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_shoulder_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_shoulder_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_upper_arm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_wrist_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_wrist_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - sensor_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - torso_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Robot Alpha: 0.5 - Show Scene Robot: true + Robot Alpha: 1 + Show Robot Collision: false + Show Robot Visual: true Value: true + Velocity_Scaling_Factor: 0.1 Enabled: true Global Options: Background Color: 48; 48; 48 Fixed Frame: base_link + Frame Rate: 30 Name: root Tools: - - Class: rviz/Interact + - Class: rviz_default_plugins/Interact Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF Value: true Views: Current: - Class: rviz/XYOrbit - Distance: 2.9965 + Class: rviz_default_plugins/Orbit + Distance: 3.119211196899414 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false Focal Point: - X: 0.113567 - Y: 0.10592 - Z: 2.23518e-07 + X: 0.02386285550892353 + Y: 0.15478567779064178 + Z: 0.039489321410655975 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false Name: Current View - Near Clip Distance: 0.01 - Pitch: 0.509797 - Target Frame: /base_link - Value: XYOrbit (rviz) - Yaw: 5.65995 + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5953981876373291 + Target Frame: + Value: Orbit (rviz) + Yaw: 5.958578109741211 Saved: ~ Window Geometry: - Displays: + "": collapsed: false - Height: 1337 - Help: + " - Trajectory Slider": collapsed: false + Displays: + collapsed: false + Height: 1024 Hide Left Dock: false - Hide Right Dock: false - Motion Planning: + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd0000000400000000000001ca000003aafc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000230000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000003c005400720061006a006500630074006f007200790020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000003f00fffffffb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000003f00fffffffbffffffff0100000271000001740000016900ffffff000000010000010f000003abfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000003ab000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000574000003aa00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: collapsed: false - QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Views: + Tool Properties: collapsed: false - Width: 1828 - X: 459 - Y: -243 + Trajectory - Trajectory Slider: + collapsed: false + Views: + collapsed: true + Width: 1860 + X: 2620 + Y: 27 diff --git a/fanuc_moveit_config/launch/moveit_rviz.launch b/fanuc_moveit_config/launch/moveit_rviz.launch deleted file mode 100644 index 615b2f12..00000000 --- a/fanuc_moveit_config/launch/moveit_rviz.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/ompl_planning_pipeline.launch.xml b/fanuc_moveit_config/launch/ompl_planning_pipeline.launch.xml deleted file mode 100644 index f1ffcc22..00000000 --- a/fanuc_moveit_config/launch/ompl_planning_pipeline.launch.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/planning_context.launch b/fanuc_moveit_config/launch/planning_context.launch deleted file mode 100644 index 6fa31b63..00000000 --- a/fanuc_moveit_config/launch/planning_context.launch +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/planning_pipeline.launch.xml b/fanuc_moveit_config/launch/planning_pipeline.launch.xml deleted file mode 100644 index 00a08b59..00000000 --- a/fanuc_moveit_config/launch/planning_pipeline.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - diff --git a/fanuc_moveit_config/launch/ros_controllers.launch b/fanuc_moveit_config/launch/ros_controllers.launch deleted file mode 100644 index 46bf5ea4..00000000 --- a/fanuc_moveit_config/launch/ros_controllers.launch +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/run_benchmark_ompl.launch b/fanuc_moveit_config/launch/run_benchmark_ompl.launch deleted file mode 100644 index ff71d3d8..00000000 --- a/fanuc_moveit_config/launch/run_benchmark_ompl.launch +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/sensor_manager.launch.xml b/fanuc_moveit_config/launch/sensor_manager.launch.xml deleted file mode 100644 index efd02218..00000000 --- a/fanuc_moveit_config/launch/sensor_manager.launch.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/setup_assistant.launch b/fanuc_moveit_config/launch/setup_assistant.launch deleted file mode 100644 index dcda2688..00000000 --- a/fanuc_moveit_config/launch/setup_assistant.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/test_environment.launch b/fanuc_moveit_config/launch/test_environment.launch deleted file mode 100644 index d1ca70d7..00000000 --- a/fanuc_moveit_config/launch/test_environment.launch +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/fanuc_moveit_config/launch/trajectory_execution.launch.xml b/fanuc_moveit_config/launch/trajectory_execution.launch.xml deleted file mode 100644 index 287bc75e..00000000 --- a/fanuc_moveit_config/launch/trajectory_execution.launch.xml +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/warehouse.launch b/fanuc_moveit_config/launch/warehouse.launch deleted file mode 100644 index c4320522..00000000 --- a/fanuc_moveit_config/launch/warehouse.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/fanuc_moveit_config/launch/warehouse_settings.launch.xml b/fanuc_moveit_config/launch/warehouse_settings.launch.xml deleted file mode 100644 index e473b083..00000000 --- a/fanuc_moveit_config/launch/warehouse_settings.launch.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - -