diff --git a/CMakeLists.txt b/CMakeLists.txt
index f79c668431..7037b32124 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -59,6 +59,7 @@ include_directories(${THIS_PACKAGE_INCLUDE_DIRS})
add_subdirectory(doc/tutorials/quickstart_in_rviz)
add_subdirectory(doc/tutorials/pick_and_place_with_moveit_task_constructor)
# add_subdirectory(doc/examples/controller_configuration)
+add_subdirectory(doc/examples/hand_eye_calibration)
# add_subdirectory(doc/examples/interactivity)
# add_subdirectory(doc/examples/kinematics)
add_subdirectory(doc/examples/motion_planning_api)
diff --git a/doc/examples/hand_eye_calibration/CMakeLists.txt b/doc/examples/hand_eye_calibration/CMakeLists.txt
new file mode 100644
index 0000000000..ceec3708bc
--- /dev/null
+++ b/doc/examples/hand_eye_calibration/CMakeLists.txt
@@ -0,0 +1,3 @@
+install(DIRECTORY launch rviz
+ DESTINATION share/${PROJECT_NAME}
+)
diff --git a/doc/examples/hand_eye_calibration/hand_eye_calibration_tutorial.rst b/doc/examples/hand_eye_calibration/hand_eye_calibration_tutorial.rst
index 8bf46926e3..60c3c9ee0e 100644
--- a/doc/examples/hand_eye_calibration/hand_eye_calibration_tutorial.rst
+++ b/doc/examples/hand_eye_calibration/hand_eye_calibration_tutorial.rst
@@ -14,9 +14,6 @@ eye-in-hand case.
Getting Started
---------------
-While it is possible to go through most of this tutorial using just a simulation, to actually complete a calibration you
-will need a robotic arm and a camera.
-
If you haven't already done so, be sure to complete the steps in :doc:`Getting Started `.
Also, set your arm up to work with MoveIt (as described in the :doc:`Setup Assistant Tutorial `).
@@ -28,17 +25,28 @@ Clone and Build the MoveIt Calibration Repo
-------------------------------------------
In your workspace ``src`` directory, clone MoveIt Calibration::
- git clone git@github.com:ros-planning/moveit_calibration.git
+ git clone https://github.com/ros-planning/moveit_calibration.git -b ros2
Then, make sure you have the appropriate dependencies and build the package::
- rosdep install -y --from-paths . --ignore-src --rosdistro melodic
- catkin build
- source devel/setup.sh
+ vcs import src < src/moveit_calibration/moveit_calibration.repos --skip-existing
+ rosdep install -r --from-paths src --ignore-src --rosdistro ${ROS_DISTRO} -y
+ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release
+ source install/local_setup.sh
+
+Option A) Simulation: Test MoveIt Calibration inside Gazebo
+---------------------------------------
+Launch one of the following scripts that are configured for Gazebo with a virtual robot, camera and calibration pattern. These scripts
+also initialise a pre-configured RViz instance with all required plugins.
+
+ ros2 launch moveit2_tutorials moveit_calibration_sim_eye_to_hand.launch.py
+ ros2 launch moveit2_tutorials moveit_calibration_sim_eye_in_hand.launch.py
+
+Once started, you can follow the rest of this tutorial just like on the real robot.
-Launch RViz and Load Calibration Plugin
+Option B) Real Robot: Launch RViz and Load Calibration Plugin
---------------------------------------
-Launch the appropriate MoveIt demo for your robot. For instance, ``roslaunch panda_moveit_config demo.launch``.
+Launch the appropriate MoveIt demo for your robot. For instance, ``ros2 launch panda_moveit_config demo.launch.py``.
In the RViz "Panels" menu, choose "Add New Panel":
.. image:: images/choose_new_panel.png
diff --git a/doc/examples/hand_eye_calibration/launch/moveit_calibration_sim_eye_in_hand.launch.py b/doc/examples/hand_eye_calibration/launch/moveit_calibration_sim_eye_in_hand.launch.py
new file mode 100755
index 0000000000..7a70a68542
--- /dev/null
+++ b/doc/examples/hand_eye_calibration/launch/moveit_calibration_sim_eye_in_hand.launch.py
@@ -0,0 +1,11 @@
+#!/usr/bin/env -S ros2 launch
+"""MoveIt2 hand-eye calibration example inside Gazebo simulation (eye-in-hand variant)"""
+
+from launch import LaunchDescription
+
+
+def generate_launch_description() -> LaunchDescription:
+
+ raise NotImplementedError(
+ "Example for eye-in-hand scenario is not yet implemented."
+ )
diff --git a/doc/examples/hand_eye_calibration/launch/moveit_calibration_sim_eye_to_hand.launch.py b/doc/examples/hand_eye_calibration/launch/moveit_calibration_sim_eye_to_hand.launch.py
new file mode 100755
index 0000000000..c676be84f9
--- /dev/null
+++ b/doc/examples/hand_eye_calibration/launch/moveit_calibration_sim_eye_to_hand.launch.py
@@ -0,0 +1,328 @@
+#!/usr/bin/env -S ros2 launch
+"""MoveIt2 hand-eye calibration example inside Gazebo simulation (eye-to-hand variant)"""
+
+import inspect
+from math import pi, radians
+from os import path
+from typing import List
+
+from ament_index_python.packages import get_package_share_directory
+from launch import LaunchDescription
+from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
+from launch_ros.actions import Node
+from launch_ros.substitutions import FindPackageShare
+
+CAMERA_NAME: str = "camera"
+CALIBRATION_PATTERN: str = "charuco" # "aruco" or "charuco"
+
+
+def generate_camera_sdf(
+ static: bool = True,
+ update_rate: float = 15.0,
+ width: int = 1280,
+ height: int = 720,
+ horizontal_fov: float = 0.5 * pi,
+ vertical_fov: float = 0.5 * pi,
+ noise_mean: float = 0.0,
+ noise_stddev: float = 0.025,
+ clip_near: float = 0.01,
+ clip_far: float = 1000.0,
+) -> str:
+ """
+ Generate SDF description for a camera model.
+ """
+
+ return inspect.cleandoc(
+ f"""
+
+
+ {static}
+
+
+ {CAMERA_NAME}
+ true
+ {update_rate}
+
+
+ {width}
+ {height}
+ R8G8B8
+
+ {horizontal_fov}
+ {vertical_fov}
+
+ {clip_near}
+ {clip_far}
+
+
+ gaussian
+ {noise_mean}
+ {noise_stddev}
+
+
+ true
+
+
+ -0.01 0 0 0 1.5707963 0
+
+
+ 0.02
+ 0.02
+
+
+
+ 0.0 0.0 0.8
+ 0.2 0.2 0.2
+
+
+
+ -0.05 0 0 0 0 0
+
+
+ 0.06 0.05 0.05
+
+
+
+ 0.0 0.0 0.8
+ 0.2 0.2 0.2
+
+
+
+
+ """
+ )
+
+
+def generate_launch_description() -> LaunchDescription:
+
+ # Declare all launch arguments
+ declared_arguments = generate_declared_arguments()
+
+ # Get substitution for all arguments
+ world = LaunchConfiguration("world")
+ robot = LaunchConfiguration("robot")
+ rviz_config = LaunchConfiguration("rviz_config")
+ use_sim_time = LaunchConfiguration("use_sim_time")
+ ign_verbosity = LaunchConfiguration("ign_verbosity")
+ log_level = LaunchConfiguration("log_level")
+
+ # List of included launch descriptions
+ launch_descriptions = [
+ # Launch Ignition Gazebo
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ PathJoinSubstitution(
+ [
+ FindPackageShare("ros_ign_gazebo"),
+ "launch",
+ "ign_gazebo.launch.py",
+ ]
+ )
+ ),
+ launch_arguments=[("ign_args", [world, " -r -v ", ign_verbosity])],
+ ),
+ # TODO: Update launch include of move group once implemented for MoveIt 2 + Gazebo under moveit repositories
+ # Note: https://github.com/AndrejOrsula/panda_ign_moveit2 is currently required
+ # Launch move_group of MoveIt 2
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ PathJoinSubstitution(
+ [
+ FindPackageShare([robot, "_moveit_config"]),
+ "launch",
+ "move_group.launch.py",
+ ]
+ )
+ ),
+ launch_arguments=[
+ ("ros2_control_plugin", "ign"),
+ ("ros2_control_command_interface", "effort"),
+ ("rviz_config", rviz_config),
+ ("use_sim_time", use_sim_time),
+ ("log_level", log_level),
+ ],
+ ),
+ ]
+
+ # List of nodes to be launched
+ nodes = [
+ # TODO: Update robot model/path once compable with MoveIt 2 + Gazebo under moveit repositories
+ # Note: https://github.com/AndrejOrsula/panda_ign_moveit2 is currently required
+ # ros_ign_gazebo_create (robot)
+ Node(
+ package="ros_ign_gazebo",
+ executable="create",
+ output="log",
+ arguments=["-file", robot, "--ros-args", "--log-level", log_level],
+ parameters=[{"use_sim_time": use_sim_time}],
+ ),
+ # ros_ign_gazebo_create (calibration pattern)
+ Node(
+ package="ros_ign_gazebo",
+ executable="create",
+ output="log",
+ arguments=[
+ "-file",
+ "https://fuel.ignitionrobotics.org/1.0/AndrejOrsula/models/aruco_default"
+ if "aruco" == CALIBRATION_PATTERN
+ else "https://fuel.ignitionrobotics.org/1.0/AndrejOrsula/models/charuco_default",
+ "-x",
+ "0.125",
+ "-y",
+ "0.05",
+ "-z",
+ "1.0",
+ "-R",
+ "0.0",
+ "-P",
+ f"{pi/2}",
+ "-Y",
+ f"{pi/4}",
+ "--ros-args",
+ "--log-level",
+ log_level,
+ ],
+ parameters=[{"use_sim_time": use_sim_time}],
+ ),
+ # ros_ign_gazebo_create (camera)
+ Node(
+ package="ros_ign_gazebo",
+ executable="create",
+ output="log",
+ arguments=[
+ "-string",
+ generate_camera_sdf(),
+ "-x",
+ LaunchConfiguration("camera_x"),
+ "-y",
+ LaunchConfiguration("camera_y"),
+ "-z",
+ LaunchConfiguration("camera_z"),
+ "-R",
+ LaunchConfiguration("camera_roll"),
+ "-P",
+ LaunchConfiguration("camera_pitch"),
+ "-Y",
+ LaunchConfiguration("camera_yaw"),
+ "--ros-args",
+ "--log-level",
+ log_level,
+ ],
+ parameters=[{"use_sim_time": use_sim_time}],
+ ),
+ # static_transform_publisher (identity; camera link -> camera sensor)
+ Node(
+ package="tf2_ros",
+ executable="static_transform_publisher",
+ output="log",
+ arguments=[
+ "--frame-id",
+ [CAMERA_NAME, "/", CAMERA_NAME, "_link"],
+ "--child-frame-id",
+ [CAMERA_NAME, "/", CAMERA_NAME, "_link/", CAMERA_NAME, "_sensor"],
+ "--ros-args",
+ "--log-level",
+ log_level,
+ ],
+ parameters=[{"use_sim_time": use_sim_time}],
+ ),
+ # ros_ign_bridge (clock -> ROS 2; image -> ROS 2; camera info -> ROS 2)
+ Node(
+ package="ros_ign_bridge",
+ executable="parameter_bridge",
+ output="log",
+ arguments=[
+ "/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock",
+ ["/", CAMERA_NAME, "@sensor_msgs/msg/Image[ignition.msgs.Image"],
+ [
+ "/",
+ CAMERA_NAME,
+ "_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
+ ],
+ "--ros-args",
+ "--log-level",
+ log_level,
+ ],
+ parameters=[{"use_sim_time": use_sim_time}],
+ ),
+ ]
+
+ return LaunchDescription(declared_arguments + launch_descriptions + nodes)
+
+
+def generate_declared_arguments() -> List[DeclareLaunchArgument]:
+ """
+ Generate list of all launch arguments that are declared for this launch script.
+ """
+
+ return [
+ # World and model for Ignition Gazebo
+ DeclareLaunchArgument(
+ "world",
+ default_value="https://fuel.ignitionrobotics.org/1.0/AndrejOrsula/worlds/default_with_world_plugins_ogre",
+ description="Name or filepath of world to load.",
+ ),
+ DeclareLaunchArgument(
+ "robot",
+ default_value="panda",
+ description="Name or filepath of model to load.",
+ ),
+ # Camera properties
+ DeclareLaunchArgument(
+ "camera_x",
+ default_value="1.0",
+ description="Position of the camera along x.",
+ ),
+ DeclareLaunchArgument(
+ "camera_y",
+ default_value="-0.5",
+ description="Position of the camera along y.",
+ ),
+ DeclareLaunchArgument(
+ "camera_z",
+ default_value="0.5",
+ description="Position of the camera along z.",
+ ),
+ DeclareLaunchArgument(
+ "camera_roll",
+ default_value="0.0",
+ description="Orientation of the camera (roll).",
+ ),
+ DeclareLaunchArgument(
+ "camera_pitch",
+ default_value=f"{radians(5.0)}",
+ description="Orientation of the camera (pitch).",
+ ),
+ DeclareLaunchArgument(
+ "camera_yaw",
+ default_value=f"{radians(150.0)}",
+ description="Orientation of the camera (yaw).",
+ ),
+ # Miscellaneous
+ DeclareLaunchArgument(
+ "rviz_config",
+ default_value=path.join(
+ get_package_share_directory("moveit2_tutorials"),
+ "rviz",
+ "moveit_calibration_eye_to_hand.rviz",
+ ),
+ description="Path to configuration for RViz2.",
+ ),
+ DeclareLaunchArgument(
+ "use_sim_time",
+ default_value="true",
+ description="If true, use simulated clock.",
+ ),
+ DeclareLaunchArgument(
+ "ign_verbosity",
+ default_value="3",
+ description="Verbosity level for Ignition Gazebo (0~4).",
+ ),
+ DeclareLaunchArgument(
+ "log_level",
+ default_value="warn",
+ description="The level of logging that is applied to all ROS 2 nodes launched by this script.",
+ ),
+ ]
diff --git a/doc/examples/hand_eye_calibration/rviz/moveit_calibration_eye_in_hand.rviz b/doc/examples/hand_eye_calibration/rviz/moveit_calibration_eye_in_hand.rviz
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/doc/examples/hand_eye_calibration/rviz/moveit_calibration_eye_to_hand.rviz b/doc/examples/hand_eye_calibration/rviz/moveit_calibration_eye_to_hand.rviz
new file mode 100644
index 0000000000..f6e7ca1e00
--- /dev/null
+++ b/doc/examples/hand_eye_calibration/rviz/moveit_calibration_eye_to_hand.rviz
@@ -0,0 +1,403 @@
+Panels:
+ - Class: rviz_common/Displays
+ Help Height: 0
+ Name: Displays
+ Property Tree Widget:
+ Expanded:
+ - /Global Options1
+ - /HandEyeCalibration1
+ Splitter Ratio: 0.41654980182647705
+ Tree Height: 415
+ - 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
+ - /Current View1/Focal Point1
+ Name: Views
+ Splitter Ratio: 0.5
+ - Class: rviz_common/Time
+ Experimental: false
+ Name: Time
+ SyncMode: 0
+ SyncSource: ""
+Visualization Manager:
+ Class: ""
+ Displays:
+ - Class: rviz_default_plugins/TF
+ Enabled: false
+ Frame Timeout: 15
+ Frames:
+ All Enabled: true
+ Marker Scale: 0.5
+ Name: TF
+ Show Arrows: false
+ Show Axes: true
+ Show Names: true
+ Tree:
+ {}
+ Update Interval: 0
+ Value: false
+ - Acceleration_Scaling_Factor: 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_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
+ panda_hand:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_hand_tcp:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ panda_leftfinger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link1:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link3:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link4:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link5:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link6:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link7:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link8:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ panda_rightfinger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ world:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Loop Animation: false
+ Robot Alpha: 0.25
+ Robot Color: 150; 50; 150
+ Show Robot Collision: false
+ Show Robot Visual: false
+ Show Trail: false
+ State Display Time: 0.1s
+ Trail Step Size: 1
+ Trajectory Topic: /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: 0.5
+ Goal State Color: 250; 128; 0
+ Interactive Marker Size: 0.10000000149011612
+ Joint Violation Color: 255; 0; 255
+ Planning Group: arm
+ Query Goal State: true
+ Query Start State: false
+ Show Workspace: false
+ Start State Alpha: 0.5
+ Start State Color: 0; 255; 0
+ 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:
+ All Links Enabled: true
+ Expand Joint Details: false
+ Expand Link Details: false
+ Expand Tree: false
+ Link Tree Style: Links in Alphabetic Order
+ panda_hand:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_hand_tcp:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ panda_leftfinger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link1:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link3:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link4:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link5:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link6:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link7:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ panda_link8:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ panda_rightfinger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ world:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Robot Alpha: 1
+ Show Robot Collision: false
+ Show Robot Visual: true
+ Value: true
+ Velocity_Scaling_Factor: 1
+ - ArUco dictionary: DICT_5X5_250
+ Camera FOV Marker:
+ Marker Alpha: 0.30000001192092896
+ Marker Size: 1.5
+ Value: true
+ Class: moveit_rviz_plugin/HandEyeCalibration
+ Enabled: true
+ Move Group Namespace: ""
+ Name: HandEyeCalibration
+ Planning Scene Topic: /monitored_planning_scene
+ Rx: 0
+ Ry: 0
+ Rz: 0
+ Tx: 0
+ Ty: 0
+ Tz: 0
+ Value: true
+ base: panda_link0
+ eef: panda_hand_tcp
+ group: arm
+ image_topic: /camera
+ longest board side (m): 0.560000
+ margin size (px): 2
+ marker border (bits): 1
+ marker size (px): 50
+ measured marker size (m): 0.060000
+ object: handeye_target
+ sensor: camera/camera_link
+ sensor_mount_type: 0
+ solver: crigroup/Daniilidis1999
+ square size (px): 80
+ squares, X: 5
+ squares, Y: 7
+ target_type: HandEyeTarget/Charuco
+ - Class: rviz_default_plugins/Image
+ Enabled: true
+ Max Value: 1
+ Median window: 5
+ Min Value: 0
+ Name: Image
+ Normalize Range: true
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /handeye_calibration/target_detection
+ Value: true
+ Enabled: true
+ Global Options:
+ Background Color: 48; 48; 48
+ Fixed Frame: panda_link0
+ Frame Rate: 30
+ Name: root
+ Tools:
+ - Class: rviz_default_plugins/Interact
+ Hide Inactive Objects: true
+ - 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_default_plugins/Orbit
+ Distance: 1.6323726177215576
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.05999999865889549
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Focal Point:
+ X: 0
+ Y: 0
+ Z: 0.5
+ Focal Shape Fixed Size: false
+ Focal Shape Size: 0.05000000074505806
+ Invert Z Axis: false
+ Name: Current View
+ Near Clip Distance: 0.009999999776482582
+ Pitch: 0.5476992130279541
+ Target Frame:
+ Value: Orbit (rviz)
+ Yaw: 5.503579616546631
+ Saved: ~
+Window Geometry:
+ Displays:
+ collapsed: false
+ HandEye Calibration:
+ collapsed: false
+ Height: 1411
+ Hide Left Dock: false
+ Hide Right Dock: true
+ Image:
+ collapsed: false
+ MotionPlanning:
+ collapsed: false
+ MotionPlanning - Trajectory Slider:
+ collapsed: false
+ QMainWindow State: 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
+ Selection:
+ collapsed: false
+ Time:
+ collapsed: false
+ Tool Properties:
+ collapsed: false
+ Views:
+ collapsed: true
+ Width: 2560
+ X: 0
+ Y: 0