├── youbot_moveit_config
├── launch
│ ├── youbot_moveit_sensor_manager.launch.xml
│ ├── planning_pipeline.launch.xml
│ ├── fake_moveit_controller_manager.launch.xml
│ ├── youbot_moveit_controller_manager.launch.xml
│ ├── warehouse.launch
│ ├── default_warehouse_db.launch
│ ├── setup_assistant.launch
│ ├── warehouse_settings.launch.xml
│ ├── joystick_control.launch
│ ├── sensor_manager.launch.xml
│ ├── moveit_rviz.launch
│ ├── run_benchmark_ompl.launch
│ ├── ompl_planning_pipeline.launch.xml
│ ├── trajectory_execution.launch.xml
│ ├── planning_context.launch
│ ├── demo.launch
│ ├── move_group.launch
│ └── moveit.rviz
├── config
│ ├── kinematics.yaml
│ ├── fake_controllers.yaml
│ ├── youbot_controllers.yaml
│ ├── joint_limits.yaml
│ ├── ompl_planning.yaml
│ └── youbot.srdf
├── .setup_assistant
├── CMakeLists.txt
└── package.xml
├── youbot_navigation
├── config
│ ├── global_costmap_params.yaml
│ ├── base_local_planner_params.yaml
│ ├── local_costmap_params.yaml
│ └── costmap_common_params.yaml
├── launch
│ └── navigation_no_map.launch
├── package.xml
└── CMakeLists.txt
├── youbot_launch
├── launch
│ └── youbot_simulation.launch
├── package.xml
├── CMakeLists.txt
└── config
│ └── motion_planning.rviz
└── README.md
/youbot_moveit_config/launch/youbot_moveit_sensor_manager.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/youbot_navigation/config/global_costmap_params.yaml:
--------------------------------------------------------------------------------
1 | global_costmap:
2 | global_frame: /odom
3 | robot_base_frame: base_link
4 | update_frequency: 5.0
5 | static_map: false
6 |
--------------------------------------------------------------------------------
/youbot_moveit_config/config/kinematics.yaml:
--------------------------------------------------------------------------------
1 | arm:
2 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
3 | kinematics_solver_search_resolution: 0.005
4 | kinematics_solver_timeout: 0.005
5 | kinematics_solver_attempts: 3
--------------------------------------------------------------------------------
/youbot_moveit_config/.setup_assistant:
--------------------------------------------------------------------------------
1 | moveit_setup_assistant_config:
2 | URDF:
3 | package: youbot_description
4 | relative_path: robots/youbot.urdf.xacro
5 | SRDF:
6 | relative_path: config/youbot.srdf
7 | CONFIG:
8 | generated_timestamp: 1447104013
--------------------------------------------------------------------------------
/youbot_navigation/config/base_local_planner_params.yaml:
--------------------------------------------------------------------------------
1 | TrajectoryPlannerROS:
2 | max_vel_x: 0.45
3 | min_vel_x: 0.1
4 | max_vel_theta: 1.0
5 | min_in_place_vel_theta: 0.4
6 |
7 | acc_lim_theta: 3.2
8 | acc_lim_x: 2.5
9 | acc_lim_y: 2.5
10 |
11 | holonomic_robot: true
12 |
--------------------------------------------------------------------------------
/youbot_navigation/config/local_costmap_params.yaml:
--------------------------------------------------------------------------------
1 | local_costmap:
2 | global_frame: odom
3 | robot_base_frame: base_link
4 | update_frequency: 5.0
5 | publish_frequency: 2.0
6 | static_map: false
7 | rolling_window: true
8 | width: 6.0
9 | height: 6.0
10 | resolution: 0.05
11 |
--------------------------------------------------------------------------------
/youbot_moveit_config/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(youbot_moveit_config)
3 |
4 | find_package(catkin REQUIRED)
5 |
6 | catkin_package()
7 |
8 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
9 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
10 |
--------------------------------------------------------------------------------
/youbot_moveit_config/config/fake_controllers.yaml:
--------------------------------------------------------------------------------
1 | controller_list:
2 | - name: fake_arm_controller
3 | joints:
4 | - arm_joint_1
5 | - arm_joint_2
6 | - arm_joint_3
7 | - arm_joint_4
8 | - arm_joint_5
9 | - name: fake_gripper_controller
10 | joints:
11 | - gripper_finger_joint_l
12 | - gripper_finger_joint_r
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/planning_pipeline.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/fake_moveit_controller_manager.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/youbot_moveit_controller_manager.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
--------------------------------------------------------------------------------
/youbot_moveit_config/config/youbot_controllers.yaml:
--------------------------------------------------------------------------------
1 | controller_list:
2 | - name: /arm_1/arm_controller
3 | action_ns: follow_joint_trajectory
4 | type: FollowJointTrajectory
5 | default: true
6 | joints:
7 | - arm_joint_1
8 | - arm_joint_2
9 | - arm_joint_3
10 | - arm_joint_4
11 | - arm_joint_5
12 | - name: /arm_1/gripper_controller
13 | action_ns: follow_joint_trajectory
14 | type: FollowJointTrajectory
15 | default: true
16 | joints:
17 | - gripper_finger_joint_l
18 | - gripper_finger_joint_r
19 |
--------------------------------------------------------------------------------
/youbot_launch/launch/youbot_simulation.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # YouBot Integration
2 | Collection of ROS packages to enable MoveIt!, move_base, FlexBE, etc. for the Kuka YouBot.
3 |
4 | ### Additionally required repos
5 |
6 | * [youbot_description](https://github.com/mas-group/youbot_description)
7 | * [youbot_simulation](https://github.com/mas-group/youbot_simulation)
8 | * [flexbe_behavior_engine](https://github.com/team-vigir/flexbe_behavior_engine)
9 |
10 | ### Further recommended repos
11 |
12 | * [youbot_behaviors](https://github.com/FlexBE/youbot_behaviors)
13 |
14 | ### Usage
15 |
16 | roslaunch youbot_launch youbot_simulation.launch
17 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/warehouse.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/default_warehouse_db.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/setup_assistant.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/warehouse_settings.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/joystick_control.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
--------------------------------------------------------------------------------
/youbot_navigation/launch/navigation_no_map.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/sensor_manager.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/moveit_rviz.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
13 |
14 |
15 |
16 |
17 |
--------------------------------------------------------------------------------
/youbot_navigation/config/costmap_common_params.yaml:
--------------------------------------------------------------------------------
1 | global_frame: odom
2 | robot_base_frame: base_link
3 | update_frequency: 20.0
4 | publish_frequency: 20.0
5 | publish_voxel_map: true
6 | static_map: false
7 | rolling_window: true
8 | width: 6.0
9 | height: 6.0
10 | resolution: 0.025
11 |
12 | map_type: voxel
13 | origin_z: 0.0
14 | z_resolution: 1
15 | z_voxels: 32
16 | unknown_threshold: 10
17 | mark_threshold: 1
18 |
19 | transform_tolerance: 0.3
20 | obstacle_range: 2.5
21 | max_obstacle_height: 1.0
22 | min_obstacle_height: -0.2 # front laser is at approx. -0.03
23 | raytrace_range: 3.0
24 | cost_scaling_factor: 10.0
25 | lethal_cost_threshold: 100
26 |
27 | obstacle_range: 2.5
28 | raytrace_range: 3.0
29 | footprint: [[0.25, 0.18], [-0.25, 0.18], [-0.25,-0.18], [0.25,-0.18]]
30 | inflation_radius: 0.1
31 |
32 | observation_sources: laser_scan_sensor
33 |
34 | laser_scan_sensor: {sensor_frame: base_laser_front_link, data_type: LaserScan, topic: scan_front, marking: true, clearing: true}
35 |
--------------------------------------------------------------------------------
/youbot_moveit_config/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 |
23 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/ompl_planning_pipeline.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
8 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/trajectory_execution.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
--------------------------------------------------------------------------------
/youbot_moveit_config/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | youbot_moveit_config
4 | 0.2.0
5 |
6 | An automatically generated package with all the configuration and launch files for using the youbot with the MoveIt Motion Planning Framework
7 |
8 | MoveIt Setup Assistant
9 | MoveIt Setup Assistant
10 |
11 | BSD
12 |
13 | http://moveit.ros.org/
14 | https://github.com/ros-planning/moveit_setup_assistant/issues
15 | https://github.com/ros-planning/moveit_setup_assistant
16 |
17 | moveit_ros_move_group
18 | moveit_planners_ompl
19 | moveit_ros_visualization
20 | joint_state_publisher
21 | robot_state_publisher
22 | xacro
23 | youbot_description
24 | youbot_description
25 |
26 |
27 | catkin
28 |
29 |
30 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/planning_context.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 |
--------------------------------------------------------------------------------
/youbot_moveit_config/config/joint_limits.yaml:
--------------------------------------------------------------------------------
1 | # joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
2 | # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
3 | # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
4 | joint_limits:
5 | arm_joint_1:
6 | has_velocity_limits: true
7 | max_velocity: 1.57079632679
8 | has_acceleration_limits: false
9 | max_acceleration: 0
10 | arm_joint_2:
11 | has_velocity_limits: true
12 | max_velocity: 1.57079632679
13 | has_acceleration_limits: false
14 | max_acceleration: 0
15 | arm_joint_3:
16 | has_velocity_limits: true
17 | max_velocity: 1.57079632679
18 | has_acceleration_limits: false
19 | max_acceleration: 0
20 | arm_joint_4:
21 | has_velocity_limits: true
22 | max_velocity: 1.57079632679
23 | has_acceleration_limits: false
24 | max_acceleration: 0
25 | arm_joint_5:
26 | has_velocity_limits: true
27 | max_velocity: 1.57079632679
28 | has_acceleration_limits: false
29 | max_acceleration: 0
30 | gripper_finger_joint_l:
31 | has_velocity_limits: true
32 | max_velocity: 0.1
33 | has_acceleration_limits: false
34 | max_acceleration: 0
35 | gripper_finger_joint_r:
36 | has_velocity_limits: true
37 | max_velocity: 0.1
38 | has_acceleration_limits: false
39 | max_acceleration: 0
--------------------------------------------------------------------------------
/youbot_launch/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | youbot_launch
4 | 0.0.0
5 | The youbot_launch package
6 |
7 |
8 |
9 |
10 | Philipp Schillinger
11 |
12 |
13 |
14 |
15 |
16 | BSD
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 | catkin
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
--------------------------------------------------------------------------------
/youbot_navigation/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | youbot_navigation
4 | 0.0.0
5 | The youbot_navigation package
6 |
7 |
8 |
9 |
10 | Philipp Schillinger
11 |
12 |
13 |
14 |
15 |
16 | BSD
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 | catkin
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/demo.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 | [/move_group/fake_controller_joint_states]
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
--------------------------------------------------------------------------------
/youbot_moveit_config/launch/move_group.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
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 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
--------------------------------------------------------------------------------
/youbot_moveit_config/config/ompl_planning.yaml:
--------------------------------------------------------------------------------
1 | planner_configs:
2 | SBLkConfigDefault:
3 | type: geometric::SBL
4 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
5 | ESTkConfigDefault:
6 | type: geometric::EST
7 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
8 | goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
9 | LBKPIECEkConfigDefault:
10 | type: geometric::LBKPIECE
11 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
12 | border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
13 | min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
14 | BKPIECEkConfigDefault:
15 | type: geometric::BKPIECE
16 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
17 | border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
18 | failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
19 | min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
20 | KPIECEkConfigDefault:
21 | type: geometric::KPIECE
22 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
23 | goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
24 | border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
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 | RRTkConfigDefault:
28 | type: geometric::RRT
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 | RRTConnectkConfigDefault:
32 | type: geometric::RRTConnect
33 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
34 | RRTstarkConfigDefault:
35 | type: geometric::RRTstar
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 | delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
39 | TRRTkConfigDefault:
40 | type: geometric::TRRT
41 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
42 | goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
43 | max_states_failed: 10 # when to start increasing temp. default: 10
44 | temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
45 | min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
46 | init_temperature: 10e-6 # initial temperature. default: 10e-6
47 | frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
48 | frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
49 | k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
50 | PRMkConfigDefault:
51 | type: geometric::PRM
52 | max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
53 | PRMstarkConfigDefault:
54 | type: geometric::PRMstar
55 | arm:
56 | planner_configs:
57 | - SBLkConfigDefault
58 | - ESTkConfigDefault
59 | - LBKPIECEkConfigDefault
60 | - BKPIECEkConfigDefault
61 | - KPIECEkConfigDefault
62 | - RRTkConfigDefault
63 | - RRTConnectkConfigDefault
64 | - RRTstarkConfigDefault
65 | - TRRTkConfigDefault
66 | - PRMkConfigDefault
67 | - PRMstarkConfigDefault
68 | gripper:
69 | planner_configs:
70 | - SBLkConfigDefault
71 | - ESTkConfigDefault
72 | - LBKPIECEkConfigDefault
73 | - BKPIECEkConfigDefault
74 | - KPIECEkConfigDefault
75 | - RRTkConfigDefault
76 | - RRTConnectkConfigDefault
77 | - RRTstarkConfigDefault
78 | - TRRTkConfigDefault
79 | - PRMkConfigDefault
80 | - PRMstarkConfigDefault
--------------------------------------------------------------------------------
/youbot_launch/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(youbot_launch)
3 |
4 | ## Find catkin macros and libraries
5 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
6 | ## is used, also find other catkin packages
7 | find_package(catkin REQUIRED)
8 |
9 | ## System dependencies are found with CMake's conventions
10 | # find_package(Boost REQUIRED COMPONENTS system)
11 |
12 |
13 | ## Uncomment this if the package has a setup.py. This macro ensures
14 | ## modules and global scripts declared therein get installed
15 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
16 | # catkin_python_setup()
17 |
18 | ################################################
19 | ## Declare ROS messages, services and actions ##
20 | ################################################
21 |
22 | ## To declare and build messages, services or actions from within this
23 | ## package, follow these steps:
24 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
25 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
26 | ## * In the file package.xml:
27 | ## * add a build_depend tag for "message_generation"
28 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
29 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
30 | ## but can be declared for certainty nonetheless:
31 | ## * add a run_depend tag for "message_runtime"
32 | ## * In this file (CMakeLists.txt):
33 | ## * add "message_generation" and every package in MSG_DEP_SET to
34 | ## find_package(catkin REQUIRED COMPONENTS ...)
35 | ## * add "message_runtime" and every package in MSG_DEP_SET to
36 | ## catkin_package(CATKIN_DEPENDS ...)
37 | ## * uncomment the add_*_files sections below as needed
38 | ## and list every .msg/.srv/.action file to be processed
39 | ## * uncomment the generate_messages entry below
40 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
41 |
42 | ## Generate messages in the 'msg' folder
43 | # add_message_files(
44 | # FILES
45 | # Message1.msg
46 | # Message2.msg
47 | # )
48 |
49 | ## Generate services in the 'srv' folder
50 | # add_service_files(
51 | # FILES
52 | # Service1.srv
53 | # Service2.srv
54 | # )
55 |
56 | ## Generate actions in the 'action' folder
57 | # add_action_files(
58 | # FILES
59 | # Action1.action
60 | # Action2.action
61 | # )
62 |
63 | ## Generate added messages and services with any dependencies listed here
64 | # generate_messages(
65 | # DEPENDENCIES
66 | # std_msgs # Or other packages containing msgs
67 | # )
68 |
69 | ################################################
70 | ## Declare ROS dynamic reconfigure parameters ##
71 | ################################################
72 |
73 | ## To declare and build dynamic reconfigure parameters within this
74 | ## package, follow these steps:
75 | ## * In the file package.xml:
76 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
77 | ## * In this file (CMakeLists.txt):
78 | ## * add "dynamic_reconfigure" to
79 | ## find_package(catkin REQUIRED COMPONENTS ...)
80 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
81 | ## and list every .cfg file to be processed
82 |
83 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
84 | # generate_dynamic_reconfigure_options(
85 | # cfg/DynReconf1.cfg
86 | # cfg/DynReconf2.cfg
87 | # )
88 |
89 | ###################################
90 | ## catkin specific configuration ##
91 | ###################################
92 | ## The catkin_package macro generates cmake config files for your package
93 | ## Declare things to be passed to dependent projects
94 | ## INCLUDE_DIRS: uncomment this if you package contains header files
95 | ## LIBRARIES: libraries you create in this project that dependent projects also need
96 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
97 | ## DEPENDS: system dependencies of this project that dependent projects also need
98 | catkin_package(
99 | # INCLUDE_DIRS include
100 | # LIBRARIES youbot_launch
101 | # CATKIN_DEPENDS other_catkin_pkg
102 | # DEPENDS system_lib
103 | )
104 |
105 | ###########
106 | ## Build ##
107 | ###########
108 |
109 | ## Specify additional locations of header files
110 | ## Your package locations should be listed before other locations
111 | # include_directories(include)
112 |
113 | ## Declare a C++ library
114 | # add_library(youbot_launch
115 | # src/${PROJECT_NAME}/youbot_launch.cpp
116 | # )
117 |
118 | ## Add cmake target dependencies of the library
119 | ## as an example, code may need to be generated before libraries
120 | ## either from message generation or dynamic reconfigure
121 | # add_dependencies(youbot_launch ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
122 |
123 | ## Declare a C++ executable
124 | # add_executable(youbot_launch_node src/youbot_launch_node.cpp)
125 |
126 | ## Add cmake target dependencies of the executable
127 | ## same as for the library above
128 | # add_dependencies(youbot_launch_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
129 |
130 | ## Specify libraries to link a library or executable target against
131 | # target_link_libraries(youbot_launch_node
132 | # ${catkin_LIBRARIES}
133 | # )
134 |
135 | #############
136 | ## Install ##
137 | #############
138 |
139 | # all install targets should use catkin DESTINATION variables
140 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
141 |
142 | ## Mark executable scripts (Python etc.) for installation
143 | ## in contrast to setup.py, you can choose the destination
144 | # install(PROGRAMS
145 | # scripts/my_python_script
146 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
147 | # )
148 |
149 | ## Mark executables and/or libraries for installation
150 | # install(TARGETS youbot_launch youbot_launch_node
151 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
152 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
153 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
154 | # )
155 |
156 | ## Mark cpp header files for installation
157 | # install(DIRECTORY include/${PROJECT_NAME}/
158 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
159 | # FILES_MATCHING PATTERN "*.h"
160 | # PATTERN ".svn" EXCLUDE
161 | # )
162 |
163 | ## Mark other files for installation (e.g. launch and bag files, etc.)
164 | # install(FILES
165 | # # myfile1
166 | # # myfile2
167 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
168 | # )
169 |
170 | #############
171 | ## Testing ##
172 | #############
173 |
174 | ## Add gtest based cpp test target and link libraries
175 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_youbot_launch.cpp)
176 | # if(TARGET ${PROJECT_NAME}-test)
177 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
178 | # endif()
179 |
180 | ## Add folders to be run by python nosetests
181 | # catkin_add_nosetests(test)
182 |
--------------------------------------------------------------------------------
/youbot_navigation/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(youbot_navigation)
3 |
4 | ## Find catkin macros and libraries
5 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
6 | ## is used, also find other catkin packages
7 | find_package(catkin REQUIRED)
8 |
9 | ## System dependencies are found with CMake's conventions
10 | # find_package(Boost REQUIRED COMPONENTS system)
11 |
12 |
13 | ## Uncomment this if the package has a setup.py. This macro ensures
14 | ## modules and global scripts declared therein get installed
15 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
16 | # catkin_python_setup()
17 |
18 | ################################################
19 | ## Declare ROS messages, services and actions ##
20 | ################################################
21 |
22 | ## To declare and build messages, services or actions from within this
23 | ## package, follow these steps:
24 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
25 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
26 | ## * In the file package.xml:
27 | ## * add a build_depend tag for "message_generation"
28 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
29 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
30 | ## but can be declared for certainty nonetheless:
31 | ## * add a run_depend tag for "message_runtime"
32 | ## * In this file (CMakeLists.txt):
33 | ## * add "message_generation" and every package in MSG_DEP_SET to
34 | ## find_package(catkin REQUIRED COMPONENTS ...)
35 | ## * add "message_runtime" and every package in MSG_DEP_SET to
36 | ## catkin_package(CATKIN_DEPENDS ...)
37 | ## * uncomment the add_*_files sections below as needed
38 | ## and list every .msg/.srv/.action file to be processed
39 | ## * uncomment the generate_messages entry below
40 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
41 |
42 | ## Generate messages in the 'msg' folder
43 | # add_message_files(
44 | # FILES
45 | # Message1.msg
46 | # Message2.msg
47 | # )
48 |
49 | ## Generate services in the 'srv' folder
50 | # add_service_files(
51 | # FILES
52 | # Service1.srv
53 | # Service2.srv
54 | # )
55 |
56 | ## Generate actions in the 'action' folder
57 | # add_action_files(
58 | # FILES
59 | # Action1.action
60 | # Action2.action
61 | # )
62 |
63 | ## Generate added messages and services with any dependencies listed here
64 | # generate_messages(
65 | # DEPENDENCIES
66 | # std_msgs # Or other packages containing msgs
67 | # )
68 |
69 | ################################################
70 | ## Declare ROS dynamic reconfigure parameters ##
71 | ################################################
72 |
73 | ## To declare and build dynamic reconfigure parameters within this
74 | ## package, follow these steps:
75 | ## * In the file package.xml:
76 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
77 | ## * In this file (CMakeLists.txt):
78 | ## * add "dynamic_reconfigure" to
79 | ## find_package(catkin REQUIRED COMPONENTS ...)
80 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
81 | ## and list every .cfg file to be processed
82 |
83 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
84 | # generate_dynamic_reconfigure_options(
85 | # cfg/DynReconf1.cfg
86 | # cfg/DynReconf2.cfg
87 | # )
88 |
89 | ###################################
90 | ## catkin specific configuration ##
91 | ###################################
92 | ## The catkin_package macro generates cmake config files for your package
93 | ## Declare things to be passed to dependent projects
94 | ## INCLUDE_DIRS: uncomment this if you package contains header files
95 | ## LIBRARIES: libraries you create in this project that dependent projects also need
96 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
97 | ## DEPENDS: system dependencies of this project that dependent projects also need
98 | catkin_package(
99 | # INCLUDE_DIRS include
100 | # LIBRARIES youbot_navigation
101 | # CATKIN_DEPENDS other_catkin_pkg
102 | # DEPENDS system_lib
103 | )
104 |
105 | ###########
106 | ## Build ##
107 | ###########
108 |
109 | ## Specify additional locations of header files
110 | ## Your package locations should be listed before other locations
111 | # include_directories(include)
112 |
113 | ## Declare a C++ library
114 | # add_library(youbot_navigation
115 | # src/${PROJECT_NAME}/youbot_navigation.cpp
116 | # )
117 |
118 | ## Add cmake target dependencies of the library
119 | ## as an example, code may need to be generated before libraries
120 | ## either from message generation or dynamic reconfigure
121 | # add_dependencies(youbot_navigation ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
122 |
123 | ## Declare a C++ executable
124 | # add_executable(youbot_navigation_node src/youbot_navigation_node.cpp)
125 |
126 | ## Add cmake target dependencies of the executable
127 | ## same as for the library above
128 | # add_dependencies(youbot_navigation_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
129 |
130 | ## Specify libraries to link a library or executable target against
131 | # target_link_libraries(youbot_navigation_node
132 | # ${catkin_LIBRARIES}
133 | # )
134 |
135 | #############
136 | ## Install ##
137 | #############
138 |
139 | # all install targets should use catkin DESTINATION variables
140 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
141 |
142 | ## Mark executable scripts (Python etc.) for installation
143 | ## in contrast to setup.py, you can choose the destination
144 | # install(PROGRAMS
145 | # scripts/my_python_script
146 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
147 | # )
148 |
149 | ## Mark executables and/or libraries for installation
150 | # install(TARGETS youbot_navigation youbot_navigation_node
151 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
152 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
153 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
154 | # )
155 |
156 | ## Mark cpp header files for installation
157 | # install(DIRECTORY include/${PROJECT_NAME}/
158 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
159 | # FILES_MATCHING PATTERN "*.h"
160 | # PATTERN ".svn" EXCLUDE
161 | # )
162 |
163 | ## Mark other files for installation (e.g. launch and bag files, etc.)
164 | # install(FILES
165 | # # myfile1
166 | # # myfile2
167 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
168 | # )
169 |
170 | #############
171 | ## Testing ##
172 | #############
173 |
174 | ## Add gtest based cpp test target and link libraries
175 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_youbot_navigation.cpp)
176 | # if(TARGET ${PROJECT_NAME}-test)
177 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
178 | # endif()
179 |
180 | ## Add folders to be run by python nosetests
181 | # catkin_add_nosetests(test)
182 |
--------------------------------------------------------------------------------
/youbot_moveit_config/config/youbot.srdf:
--------------------------------------------------------------------------------
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 |
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 |
75 |
76 |
77 |
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 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 |
151 |
152 |
--------------------------------------------------------------------------------
/youbot_launch/config/motion_planning.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /TF1/Frames1
8 | - /MotionPlanning1
9 | Splitter Ratio: 0.5
10 | Tree Height: 121
11 | - Class: rviz/Selection
12 | Name: Selection
13 | - Class: rviz/Tool Properties
14 | Expanded:
15 | - /2D Pose Estimate1
16 | - /2D Nav Goal1
17 | - /Publish Point1
18 | Name: Tool Properties
19 | Splitter Ratio: 0.588679
20 | - Class: rviz/Views
21 | Expanded:
22 | - /Current View1
23 | Name: Views
24 | Splitter Ratio: 0.5
25 | - Class: rviz/Time
26 | Experimental: false
27 | Name: Time
28 | SyncMode: 0
29 | SyncSource: LaserScan
30 | Visualization Manager:
31 | Class: ""
32 | Displays:
33 | - Alpha: 0.5
34 | Cell Size: 1
35 | Class: rviz/Grid
36 | Color: 160; 160; 164
37 | Enabled: true
38 | Line Style:
39 | Line Width: 0.03
40 | Value: Lines
41 | Name: Grid
42 | Normal Cell Count: 0
43 | Offset:
44 | X: 0
45 | Y: 0
46 | Z: 0
47 | Plane: XY
48 | Plane Cell Count: 10
49 | Reference Frame:
50 | Value: true
51 | - Alpha: 0.2
52 | Class: rviz/RobotModel
53 | Collision Enabled: false
54 | Enabled: true
55 | Links:
56 | All Links Enabled: true
57 | Expand Joint Details: false
58 | Expand Link Details: false
59 | Expand Tree: false
60 | Link Tree Style: Links in Alphabetic Order
61 | arm_link_0:
62 | Alpha: 1
63 | Show Axes: false
64 | Show Trail: false
65 | Value: true
66 | arm_link_1:
67 | Alpha: 1
68 | Show Axes: false
69 | Show Trail: false
70 | Value: true
71 | arm_link_2:
72 | Alpha: 1
73 | Show Axes: false
74 | Show Trail: false
75 | Value: true
76 | arm_link_3:
77 | Alpha: 1
78 | Show Axes: false
79 | Show Trail: false
80 | Value: true
81 | arm_link_4:
82 | Alpha: 1
83 | Show Axes: false
84 | Show Trail: false
85 | Value: true
86 | arm_link_5:
87 | Alpha: 1
88 | Show Axes: false
89 | Show Trail: false
90 | Value: true
91 | base_footprint:
92 | Alpha: 1
93 | Show Axes: false
94 | Show Trail: false
95 | Value: true
96 | base_laser_front_link:
97 | Alpha: 1
98 | Show Axes: false
99 | Show Trail: false
100 | Value: true
101 | base_link:
102 | Alpha: 1
103 | Show Axes: false
104 | Show Trail: false
105 | Value: true
106 | caster_link_bl:
107 | Alpha: 1
108 | Show Axes: false
109 | Show Trail: false
110 | caster_link_br:
111 | Alpha: 1
112 | Show Axes: false
113 | Show Trail: false
114 | caster_link_fl:
115 | Alpha: 1
116 | Show Axes: false
117 | Show Trail: false
118 | caster_link_fr:
119 | Alpha: 1
120 | Show Axes: false
121 | Show Trail: false
122 | gripper_finger_link_l:
123 | Alpha: 1
124 | Show Axes: false
125 | Show Trail: false
126 | Value: true
127 | gripper_finger_link_r:
128 | Alpha: 1
129 | Show Axes: false
130 | Show Trail: false
131 | Value: true
132 | gripper_palm_link:
133 | Alpha: 1
134 | Show Axes: false
135 | Show Trail: false
136 | Value: true
137 | plate_link:
138 | Alpha: 1
139 | Show Axes: false
140 | Show Trail: false
141 | Value: true
142 | wheel_link_bl:
143 | Alpha: 1
144 | Show Axes: false
145 | Show Trail: false
146 | Value: true
147 | wheel_link_br:
148 | Alpha: 1
149 | Show Axes: false
150 | Show Trail: false
151 | Value: true
152 | wheel_link_fl:
153 | Alpha: 1
154 | Show Axes: false
155 | Show Trail: false
156 | Value: true
157 | wheel_link_fr:
158 | Alpha: 1
159 | Show Axes: false
160 | Show Trail: false
161 | Value: true
162 | Name: RobotModel
163 | Robot Description: robot_description
164 | TF Prefix: ""
165 | Update Interval: 0
166 | Value: true
167 | Visual Enabled: true
168 | - Class: rviz/TF
169 | Enabled: true
170 | Frame Timeout: 15
171 | Frames:
172 | All Enabled: true
173 | arm_link_0:
174 | Value: true
175 | arm_link_1:
176 | Value: true
177 | arm_link_2:
178 | Value: true
179 | arm_link_3:
180 | Value: true
181 | arm_link_4:
182 | Value: true
183 | arm_link_5:
184 | Value: true
185 | base_footprint:
186 | Value: true
187 | base_laser_front_link:
188 | Value: true
189 | base_link:
190 | Value: true
191 | caster_link_bl:
192 | Value: true
193 | caster_link_br:
194 | Value: true
195 | caster_link_fl:
196 | Value: true
197 | caster_link_fr:
198 | Value: true
199 | gripper_finger_link_l:
200 | Value: true
201 | gripper_finger_link_r:
202 | Value: true
203 | gripper_palm_link:
204 | Value: true
205 | odom:
206 | Value: true
207 | plate_link:
208 | Value: true
209 | wheel_link_bl:
210 | Value: true
211 | wheel_link_br:
212 | Value: true
213 | wheel_link_fl:
214 | Value: true
215 | wheel_link_fr:
216 | Value: true
217 | Marker Scale: 0.2
218 | Name: TF
219 | Show Arrows: true
220 | Show Axes: true
221 | Show Names: true
222 | Tree:
223 | odom:
224 | base_footprint:
225 | base_link:
226 | arm_link_0:
227 | arm_link_1:
228 | arm_link_2:
229 | arm_link_3:
230 | arm_link_4:
231 | arm_link_5:
232 | gripper_palm_link:
233 | gripper_finger_link_l:
234 | {}
235 | gripper_finger_link_r:
236 | {}
237 | base_laser_front_link:
238 | {}
239 | caster_link_bl:
240 | wheel_link_bl:
241 | {}
242 | caster_link_br:
243 | wheel_link_br:
244 | {}
245 | caster_link_fl:
246 | wheel_link_fl:
247 | {}
248 | caster_link_fr:
249 | wheel_link_fr:
250 | {}
251 | plate_link:
252 | {}
253 | Update Interval: 0
254 | Value: true
255 | - Alpha: 0.7
256 | Class: rviz/Map
257 | Color Scheme: costmap
258 | Draw Behind: true
259 | Enabled: true
260 | Name: Local Costmap
261 | Topic: /move_base/local_costmap/costmap
262 | Value: true
263 | - Alpha: 1
264 | Autocompute Intensity Bounds: true
265 | Autocompute Value Bounds:
266 | Max Value: 10
267 | Min Value: -10
268 | Value: true
269 | Axis: Z
270 | Channel Name: intensity
271 | Class: rviz/LaserScan
272 | Color: 255; 255; 255
273 | Color Transformer: Intensity
274 | Decay Time: 0
275 | Enabled: true
276 | Invert Rainbow: false
277 | Max Color: 255; 255; 255
278 | Max Intensity: 999999
279 | Min Color: 0; 0; 0
280 | Min Intensity: 5.60519e-45
281 | Name: LaserScan
282 | Position Transformer: XYZ
283 | Queue Size: 10
284 | Selectable: true
285 | Size (Pixels): 3
286 | Size (m): 0.01
287 | Style: Flat Squares
288 | Topic: /scan_front
289 | Use Fixed Frame: true
290 | Use rainbow: true
291 | Value: true
292 | - Class: moveit_rviz_plugin/MotionPlanning
293 | Enabled: true
294 | Move Group Namespace: ""
295 | MoveIt_Goal_Tolerance: 0
296 | MoveIt_Planning_Attempts: 10
297 | MoveIt_Planning_Time: 5
298 | MoveIt_Use_Constraint_Aware_IK: true
299 | MoveIt_Warehouse_Host: 127.0.0.1
300 | MoveIt_Warehouse_Port: 33829
301 | Name: MotionPlanning
302 | Planned Path:
303 | Links:
304 | All Links Enabled: true
305 | Expand Joint Details: false
306 | Expand Link Details: false
307 | Expand Tree: false
308 | Link Tree Style: Links in Alphabetic Order
309 | arm_link_0:
310 | Alpha: 1
311 | Show Axes: false
312 | Show Trail: false
313 | Value: true
314 | arm_link_1:
315 | Alpha: 1
316 | Show Axes: false
317 | Show Trail: false
318 | Value: true
319 | arm_link_2:
320 | Alpha: 1
321 | Show Axes: false
322 | Show Trail: false
323 | Value: true
324 | arm_link_3:
325 | Alpha: 1
326 | Show Axes: false
327 | Show Trail: false
328 | Value: true
329 | arm_link_4:
330 | Alpha: 1
331 | Show Axes: false
332 | Show Trail: false
333 | Value: true
334 | arm_link_5:
335 | Alpha: 1
336 | Show Axes: false
337 | Show Trail: false
338 | Value: true
339 | base_footprint:
340 | Alpha: 1
341 | Show Axes: false
342 | Show Trail: false
343 | Value: true
344 | base_laser_front_link:
345 | Alpha: 1
346 | Show Axes: false
347 | Show Trail: false
348 | Value: true
349 | base_link:
350 | Alpha: 1
351 | Show Axes: false
352 | Show Trail: false
353 | Value: true
354 | caster_link_bl:
355 | Alpha: 1
356 | Show Axes: false
357 | Show Trail: false
358 | caster_link_br:
359 | Alpha: 1
360 | Show Axes: false
361 | Show Trail: false
362 | caster_link_fl:
363 | Alpha: 1
364 | Show Axes: false
365 | Show Trail: false
366 | caster_link_fr:
367 | Alpha: 1
368 | Show Axes: false
369 | Show Trail: false
370 | gripper_finger_link_l:
371 | Alpha: 1
372 | Show Axes: false
373 | Show Trail: false
374 | Value: true
375 | gripper_finger_link_r:
376 | Alpha: 1
377 | Show Axes: false
378 | Show Trail: false
379 | Value: true
380 | gripper_palm_link:
381 | Alpha: 1
382 | Show Axes: false
383 | Show Trail: false
384 | Value: true
385 | plate_link:
386 | Alpha: 1
387 | Show Axes: false
388 | Show Trail: false
389 | Value: true
390 | wheel_link_bl:
391 | Alpha: 1
392 | Show Axes: false
393 | Show Trail: false
394 | Value: true
395 | wheel_link_br:
396 | Alpha: 1
397 | Show Axes: false
398 | Show Trail: false
399 | Value: true
400 | wheel_link_fl:
401 | Alpha: 1
402 | Show Axes: false
403 | Show Trail: false
404 | Value: true
405 | wheel_link_fr:
406 | Alpha: 1
407 | Show Axes: false
408 | Show Trail: false
409 | Value: true
410 | Loop Animation: false
411 | Robot Alpha: 0.5
412 | Show Robot Collision: false
413 | Show Robot Visual: true
414 | Show Trail: false
415 | State Display Time: 0.05 s
416 | Trajectory Topic: /move_group/display_planned_path
417 | Planning Metrics:
418 | Payload: 1
419 | Show Joint Torques: false
420 | Show Manipulability: false
421 | Show Manipulability Index: false
422 | Show Weight Limit: false
423 | TextHeight: 0.08
424 | Planning Request:
425 | Colliding Link Color: 255; 0; 0
426 | Goal State Alpha: 1
427 | Goal State Color: 250; 128; 0
428 | Interactive Marker Size: 0
429 | Joint Violation Color: 255; 0; 255
430 | Planning Group: arm
431 | Query Goal State: true
432 | Query Start State: false
433 | Show Workspace: false
434 | Start State Alpha: 1
435 | Start State Color: 0; 255; 0
436 | Planning Scene Topic: planning_scene
437 | Robot Description: robot_description
438 | Scene Geometry:
439 | Scene Alpha: 0.9
440 | Scene Color: 50; 230; 50
441 | Scene Display Time: 0.2
442 | Show Scene Geometry: true
443 | Voxel Coloring: Z-Axis
444 | Voxel Rendering: Occupied Voxels
445 | Scene Robot:
446 | Attached Body Color: 150; 50; 150
447 | Links:
448 | All Links Enabled: true
449 | Expand Joint Details: false
450 | Expand Link Details: false
451 | Expand Tree: false
452 | Link Tree Style: Links in Alphabetic Order
453 | arm_link_0:
454 | Alpha: 1
455 | Show Axes: false
456 | Show Trail: false
457 | Value: true
458 | arm_link_1:
459 | Alpha: 1
460 | Show Axes: false
461 | Show Trail: false
462 | Value: true
463 | arm_link_2:
464 | Alpha: 1
465 | Show Axes: false
466 | Show Trail: false
467 | Value: true
468 | arm_link_3:
469 | Alpha: 1
470 | Show Axes: false
471 | Show Trail: false
472 | Value: true
473 | arm_link_4:
474 | Alpha: 1
475 | Show Axes: false
476 | Show Trail: false
477 | Value: true
478 | arm_link_5:
479 | Alpha: 1
480 | Show Axes: false
481 | Show Trail: false
482 | Value: true
483 | base_footprint:
484 | Alpha: 1
485 | Show Axes: false
486 | Show Trail: false
487 | Value: true
488 | base_laser_front_link:
489 | Alpha: 1
490 | Show Axes: false
491 | Show Trail: false
492 | Value: true
493 | base_link:
494 | Alpha: 1
495 | Show Axes: false
496 | Show Trail: false
497 | Value: true
498 | caster_link_bl:
499 | Alpha: 1
500 | Show Axes: false
501 | Show Trail: false
502 | caster_link_br:
503 | Alpha: 1
504 | Show Axes: false
505 | Show Trail: false
506 | caster_link_fl:
507 | Alpha: 1
508 | Show Axes: false
509 | Show Trail: false
510 | caster_link_fr:
511 | Alpha: 1
512 | Show Axes: false
513 | Show Trail: false
514 | gripper_finger_link_l:
515 | Alpha: 1
516 | Show Axes: false
517 | Show Trail: false
518 | Value: true
519 | gripper_finger_link_r:
520 | Alpha: 1
521 | Show Axes: false
522 | Show Trail: false
523 | Value: true
524 | gripper_palm_link:
525 | Alpha: 1
526 | Show Axes: false
527 | Show Trail: false
528 | Value: true
529 | plate_link:
530 | Alpha: 1
531 | Show Axes: false
532 | Show Trail: false
533 | Value: true
534 | wheel_link_bl:
535 | Alpha: 1
536 | Show Axes: false
537 | Show Trail: false
538 | Value: true
539 | wheel_link_br:
540 | Alpha: 1
541 | Show Axes: false
542 | Show Trail: false
543 | Value: true
544 | wheel_link_fl:
545 | Alpha: 1
546 | Show Axes: false
547 | Show Trail: false
548 | Value: true
549 | wheel_link_fr:
550 | Alpha: 1
551 | Show Axes: false
552 | Show Trail: false
553 | Value: true
554 | Robot Alpha: 0.5
555 | Show Robot Collision: false
556 | Show Robot Visual: false
557 | Value: true
558 | Enabled: true
559 | Global Options:
560 | Background Color: 48; 48; 48
561 | Fixed Frame: odom
562 | Frame Rate: 30
563 | Name: root
564 | Tools:
565 | - Class: rviz/Interact
566 | Hide Inactive Objects: true
567 | - Class: rviz/MoveCamera
568 | - Class: rviz/Select
569 | - Class: rviz/FocusCamera
570 | - Class: rviz/Measure
571 | - Class: rviz/SetInitialPose
572 | Topic: /initialpose
573 | - Class: rviz/SetGoal
574 | Topic: /move_base_simple/goal
575 | - Class: rviz/PublishPoint
576 | Single click: true
577 | Topic: /clicked_point
578 | Value: true
579 | Views:
580 | Current:
581 | Class: rviz/Orbit
582 | Distance: 2.37657
583 | Enable Stereo Rendering:
584 | Stereo Eye Separation: 0.06
585 | Stereo Focal Distance: 1
586 | Swap Stereo Eyes: false
587 | Value: false
588 | Focal Point:
589 | X: 0.054302
590 | Y: 0.187393
591 | Z: 0.33855
592 | Name: Current View
593 | Near Clip Distance: 0.01
594 | Pitch: 0.460399
595 | Target Frame:
596 | Value: Orbit (rviz)
597 | Yaw: 2.18039
598 | Saved: ~
599 | Window Geometry:
600 | Displays:
601 | collapsed: false
602 | Height: 846
603 | Hide Left Dock: false
604 | Hide Right Dock: true
605 | Motion Planning:
606 | collapsed: false
607 | QMainWindow State: 000000ff00000000fd0000000400000000000002b1000002c4fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000108000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000136000001b6000001ab00ffffff000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002c4000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004eb0000003efc0100000002fb0000000800540069006d00650100000000000004eb000002f600fffffffb0000000800540069006d0065010000000000000450000000000000000000000234000002c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
608 | Selection:
609 | collapsed: false
610 | Time:
611 | collapsed: false
612 | Tool Properties:
613 | collapsed: false
614 | Views:
615 | collapsed: true
616 | Width: 1259
617 | X: 436
618 | Y: 106
619 |
--------------------------------------------------------------------------------
/youbot_moveit_config/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.74256
9 | Tree Height: 664
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 | MoveIt_Goal_Tolerance: 0
41 | MoveIt_Planning_Time: 5
42 | MoveIt_Use_Constraint_Aware_IK: true
43 | MoveIt_Warehouse_Host: 127.0.0.1
44 | MoveIt_Warehouse_Port: 33829
45 | Name: MotionPlanning
46 | Planned Path:
47 | Links:
48 | base_bellow_link:
49 | Alpha: 1
50 | Show Axes: false
51 | Show Trail: false
52 | Value: true
53 | base_footprint:
54 | Alpha: 1
55 | Show Axes: false
56 | Show Trail: false
57 | Value: true
58 | base_link:
59 | Alpha: 1
60 | Show Axes: false
61 | Show Trail: false
62 | Value: true
63 | bl_caster_l_wheel_link:
64 | Alpha: 1
65 | Show Axes: false
66 | Show Trail: false
67 | Value: true
68 | bl_caster_r_wheel_link:
69 | Alpha: 1
70 | Show Axes: false
71 | Show Trail: false
72 | Value: true
73 | bl_caster_rotation_link:
74 | Alpha: 1
75 | Show Axes: false
76 | Show Trail: false
77 | Value: true
78 | br_caster_l_wheel_link:
79 | Alpha: 1
80 | Show Axes: false
81 | Show Trail: false
82 | Value: true
83 | br_caster_r_wheel_link:
84 | Alpha: 1
85 | Show Axes: false
86 | Show Trail: false
87 | Value: true
88 | br_caster_rotation_link:
89 | Alpha: 1
90 | Show Axes: false
91 | Show Trail: false
92 | Value: true
93 | double_stereo_link:
94 | Alpha: 1
95 | Show Axes: false
96 | Show Trail: false
97 | Value: true
98 | fl_caster_l_wheel_link:
99 | Alpha: 1
100 | Show Axes: false
101 | Show Trail: false
102 | Value: true
103 | fl_caster_r_wheel_link:
104 | Alpha: 1
105 | Show Axes: false
106 | Show Trail: false
107 | Value: true
108 | fl_caster_rotation_link:
109 | Alpha: 1
110 | Show Axes: false
111 | Show Trail: false
112 | Value: true
113 | fr_caster_l_wheel_link:
114 | Alpha: 1
115 | Show Axes: false
116 | Show Trail: false
117 | Value: true
118 | fr_caster_r_wheel_link:
119 | Alpha: 1
120 | Show Axes: false
121 | Show Trail: false
122 | Value: true
123 | fr_caster_rotation_link:
124 | Alpha: 1
125 | Show Axes: false
126 | Show Trail: false
127 | Value: true
128 | head_mount_kinect_ir_link:
129 | Alpha: 1
130 | Show Axes: false
131 | Show Trail: false
132 | Value: true
133 | head_mount_kinect_rgb_link:
134 | Alpha: 1
135 | Show Axes: false
136 | Show Trail: false
137 | Value: true
138 | head_mount_link:
139 | Alpha: 1
140 | Show Axes: false
141 | Show Trail: false
142 | Value: true
143 | head_mount_prosilica_link:
144 | Alpha: 1
145 | Show Axes: false
146 | Show Trail: false
147 | Value: true
148 | head_pan_link:
149 | Alpha: 1
150 | Show Axes: false
151 | Show Trail: false
152 | Value: true
153 | head_plate_frame:
154 | Alpha: 1
155 | Show Axes: false
156 | Show Trail: false
157 | Value: true
158 | head_tilt_link:
159 | Alpha: 1
160 | Show Axes: false
161 | Show Trail: false
162 | Value: true
163 | l_elbow_flex_link:
164 | Alpha: 1
165 | Show Axes: false
166 | Show Trail: false
167 | Value: true
168 | l_forearm_link:
169 | Alpha: 1
170 | Show Axes: false
171 | Show Trail: false
172 | Value: true
173 | l_forearm_roll_link:
174 | Alpha: 1
175 | Show Axes: false
176 | Show Trail: false
177 | Value: true
178 | l_gripper_l_finger_link:
179 | Alpha: 1
180 | Show Axes: false
181 | Show Trail: false
182 | Value: true
183 | l_gripper_l_finger_tip_link:
184 | Alpha: 1
185 | Show Axes: false
186 | Show Trail: false
187 | Value: true
188 | l_gripper_motor_accelerometer_link:
189 | Alpha: 1
190 | Show Axes: false
191 | Show Trail: false
192 | Value: true
193 | l_gripper_palm_link:
194 | Alpha: 1
195 | Show Axes: false
196 | Show Trail: false
197 | Value: true
198 | l_gripper_r_finger_link:
199 | Alpha: 1
200 | Show Axes: false
201 | Show Trail: false
202 | Value: true
203 | l_gripper_r_finger_tip_link:
204 | Alpha: 1
205 | Show Axes: false
206 | Show Trail: false
207 | Value: true
208 | l_shoulder_lift_link:
209 | Alpha: 1
210 | Show Axes: false
211 | Show Trail: false
212 | Value: true
213 | l_shoulder_pan_link:
214 | Alpha: 1
215 | Show Axes: false
216 | Show Trail: false
217 | Value: true
218 | l_upper_arm_link:
219 | Alpha: 1
220 | Show Axes: false
221 | Show Trail: false
222 | Value: true
223 | l_upper_arm_roll_link:
224 | Alpha: 1
225 | Show Axes: false
226 | Show Trail: false
227 | Value: true
228 | l_wrist_flex_link:
229 | Alpha: 1
230 | Show Axes: false
231 | Show Trail: false
232 | Value: true
233 | l_wrist_roll_link:
234 | Alpha: 1
235 | Show Axes: false
236 | Show Trail: false
237 | Value: true
238 | laser_tilt_mount_link:
239 | Alpha: 1
240 | Show Axes: false
241 | Show Trail: false
242 | Value: true
243 | r_elbow_flex_link:
244 | Alpha: 1
245 | Show Axes: false
246 | Show Trail: false
247 | Value: true
248 | r_forearm_link:
249 | Alpha: 1
250 | Show Axes: false
251 | Show Trail: false
252 | Value: true
253 | r_forearm_roll_link:
254 | Alpha: 1
255 | Show Axes: false
256 | Show Trail: false
257 | Value: true
258 | r_gripper_l_finger_link:
259 | Alpha: 1
260 | Show Axes: false
261 | Show Trail: false
262 | Value: true
263 | r_gripper_l_finger_tip_link:
264 | Alpha: 1
265 | Show Axes: false
266 | Show Trail: false
267 | Value: true
268 | r_gripper_motor_accelerometer_link:
269 | Alpha: 1
270 | Show Axes: false
271 | Show Trail: false
272 | Value: true
273 | r_gripper_palm_link:
274 | Alpha: 1
275 | Show Axes: false
276 | Show Trail: false
277 | Value: true
278 | r_gripper_r_finger_link:
279 | Alpha: 1
280 | Show Axes: false
281 | Show Trail: false
282 | Value: true
283 | r_gripper_r_finger_tip_link:
284 | Alpha: 1
285 | Show Axes: false
286 | Show Trail: false
287 | Value: true
288 | r_shoulder_lift_link:
289 | Alpha: 1
290 | Show Axes: false
291 | Show Trail: false
292 | Value: true
293 | r_shoulder_pan_link:
294 | Alpha: 1
295 | Show Axes: false
296 | Show Trail: false
297 | Value: true
298 | r_upper_arm_link:
299 | Alpha: 1
300 | Show Axes: false
301 | Show Trail: false
302 | Value: true
303 | r_upper_arm_roll_link:
304 | Alpha: 1
305 | Show Axes: false
306 | Show Trail: false
307 | Value: true
308 | r_wrist_flex_link:
309 | Alpha: 1
310 | Show Axes: false
311 | Show Trail: false
312 | Value: true
313 | r_wrist_roll_link:
314 | Alpha: 1
315 | Show Axes: false
316 | Show Trail: false
317 | Value: true
318 | sensor_mount_link:
319 | Alpha: 1
320 | Show Axes: false
321 | Show Trail: false
322 | Value: true
323 | torso_lift_link:
324 | Alpha: 1
325 | Show Axes: false
326 | Show Trail: false
327 | Value: true
328 | Loop Animation: true
329 | Robot Alpha: 0.5
330 | Show Robot Collision: false
331 | Show Robot Visual: true
332 | Show Trail: false
333 | State Display Time: 0.05 s
334 | Trajectory Topic: move_group/display_planned_path
335 | Planning Metrics:
336 | Payload: 1
337 | Show Joint Torques: false
338 | Show Manipulability: false
339 | Show Manipulability Index: false
340 | Show Weight Limit: false
341 | Planning Request:
342 | Colliding Link Color: 255; 0; 0
343 | Goal State Alpha: 1
344 | Goal State Color: 250; 128; 0
345 | Interactive Marker Size: 0
346 | Joint Violation Color: 255; 0; 255
347 | Planning Group: left_arm
348 | Query Goal State: true
349 | Query Start State: false
350 | Show Workspace: false
351 | Start State Alpha: 1
352 | Start State Color: 0; 255; 0
353 | Planning Scene Topic: move_group/monitored_planning_scene
354 | Robot Description: robot_description
355 | Scene Geometry:
356 | Scene Alpha: 1
357 | Scene Color: 50; 230; 50
358 | Scene Display Time: 0.2
359 | Show Scene Geometry: true
360 | Voxel Coloring: Z-Axis
361 | Voxel Rendering: Occupied Voxels
362 | Scene Robot:
363 | Attached Body Color: 150; 50; 150
364 | Links:
365 | base_bellow_link:
366 | Alpha: 1
367 | Show Axes: false
368 | Show Trail: false
369 | Value: true
370 | base_footprint:
371 | Alpha: 1
372 | Show Axes: false
373 | Show Trail: false
374 | Value: true
375 | base_link:
376 | Alpha: 1
377 | Show Axes: false
378 | Show Trail: false
379 | Value: true
380 | bl_caster_l_wheel_link:
381 | Alpha: 1
382 | Show Axes: false
383 | Show Trail: false
384 | Value: true
385 | bl_caster_r_wheel_link:
386 | Alpha: 1
387 | Show Axes: false
388 | Show Trail: false
389 | Value: true
390 | bl_caster_rotation_link:
391 | Alpha: 1
392 | Show Axes: false
393 | Show Trail: false
394 | Value: true
395 | br_caster_l_wheel_link:
396 | Alpha: 1
397 | Show Axes: false
398 | Show Trail: false
399 | Value: true
400 | br_caster_r_wheel_link:
401 | Alpha: 1
402 | Show Axes: false
403 | Show Trail: false
404 | Value: true
405 | br_caster_rotation_link:
406 | Alpha: 1
407 | Show Axes: false
408 | Show Trail: false
409 | Value: true
410 | double_stereo_link:
411 | Alpha: 1
412 | Show Axes: false
413 | Show Trail: false
414 | Value: true
415 | fl_caster_l_wheel_link:
416 | Alpha: 1
417 | Show Axes: false
418 | Show Trail: false
419 | Value: true
420 | fl_caster_r_wheel_link:
421 | Alpha: 1
422 | Show Axes: false
423 | Show Trail: false
424 | Value: true
425 | fl_caster_rotation_link:
426 | Alpha: 1
427 | Show Axes: false
428 | Show Trail: false
429 | Value: true
430 | fr_caster_l_wheel_link:
431 | Alpha: 1
432 | Show Axes: false
433 | Show Trail: false
434 | Value: true
435 | fr_caster_r_wheel_link:
436 | Alpha: 1
437 | Show Axes: false
438 | Show Trail: false
439 | Value: true
440 | fr_caster_rotation_link:
441 | Alpha: 1
442 | Show Axes: false
443 | Show Trail: false
444 | Value: true
445 | head_mount_kinect_ir_link:
446 | Alpha: 1
447 | Show Axes: false
448 | Show Trail: false
449 | Value: true
450 | head_mount_kinect_rgb_link:
451 | Alpha: 1
452 | Show Axes: false
453 | Show Trail: false
454 | Value: true
455 | head_mount_link:
456 | Alpha: 1
457 | Show Axes: false
458 | Show Trail: false
459 | Value: true
460 | head_mount_prosilica_link:
461 | Alpha: 1
462 | Show Axes: false
463 | Show Trail: false
464 | Value: true
465 | head_pan_link:
466 | Alpha: 1
467 | Show Axes: false
468 | Show Trail: false
469 | Value: true
470 | head_plate_frame:
471 | Alpha: 1
472 | Show Axes: false
473 | Show Trail: false
474 | Value: true
475 | head_tilt_link:
476 | Alpha: 1
477 | Show Axes: false
478 | Show Trail: false
479 | Value: true
480 | l_elbow_flex_link:
481 | Alpha: 1
482 | Show Axes: false
483 | Show Trail: false
484 | Value: true
485 | l_forearm_link:
486 | Alpha: 1
487 | Show Axes: false
488 | Show Trail: false
489 | Value: true
490 | l_forearm_roll_link:
491 | Alpha: 1
492 | Show Axes: false
493 | Show Trail: false
494 | Value: true
495 | l_gripper_l_finger_link:
496 | Alpha: 1
497 | Show Axes: false
498 | Show Trail: false
499 | Value: true
500 | l_gripper_l_finger_tip_link:
501 | Alpha: 1
502 | Show Axes: false
503 | Show Trail: false
504 | Value: true
505 | l_gripper_motor_accelerometer_link:
506 | Alpha: 1
507 | Show Axes: false
508 | Show Trail: false
509 | Value: true
510 | l_gripper_palm_link:
511 | Alpha: 1
512 | Show Axes: false
513 | Show Trail: false
514 | Value: true
515 | l_gripper_r_finger_link:
516 | Alpha: 1
517 | Show Axes: false
518 | Show Trail: false
519 | Value: true
520 | l_gripper_r_finger_tip_link:
521 | Alpha: 1
522 | Show Axes: false
523 | Show Trail: false
524 | Value: true
525 | l_shoulder_lift_link:
526 | Alpha: 1
527 | Show Axes: false
528 | Show Trail: false
529 | Value: true
530 | l_shoulder_pan_link:
531 | Alpha: 1
532 | Show Axes: false
533 | Show Trail: false
534 | Value: true
535 | l_upper_arm_link:
536 | Alpha: 1
537 | Show Axes: false
538 | Show Trail: false
539 | Value: true
540 | l_upper_arm_roll_link:
541 | Alpha: 1
542 | Show Axes: false
543 | Show Trail: false
544 | Value: true
545 | l_wrist_flex_link:
546 | Alpha: 1
547 | Show Axes: false
548 | Show Trail: false
549 | Value: true
550 | l_wrist_roll_link:
551 | Alpha: 1
552 | Show Axes: false
553 | Show Trail: false
554 | Value: true
555 | laser_tilt_mount_link:
556 | Alpha: 1
557 | Show Axes: false
558 | Show Trail: false
559 | Value: true
560 | r_elbow_flex_link:
561 | Alpha: 1
562 | Show Axes: false
563 | Show Trail: false
564 | Value: true
565 | r_forearm_link:
566 | Alpha: 1
567 | Show Axes: false
568 | Show Trail: false
569 | Value: true
570 | r_forearm_roll_link:
571 | Alpha: 1
572 | Show Axes: false
573 | Show Trail: false
574 | Value: true
575 | r_gripper_l_finger_link:
576 | Alpha: 1
577 | Show Axes: false
578 | Show Trail: false
579 | Value: true
580 | r_gripper_l_finger_tip_link:
581 | Alpha: 1
582 | Show Axes: false
583 | Show Trail: false
584 | Value: true
585 | r_gripper_motor_accelerometer_link:
586 | Alpha: 1
587 | Show Axes: false
588 | Show Trail: false
589 | Value: true
590 | r_gripper_palm_link:
591 | Alpha: 1
592 | Show Axes: false
593 | Show Trail: false
594 | Value: true
595 | r_gripper_r_finger_link:
596 | Alpha: 1
597 | Show Axes: false
598 | Show Trail: false
599 | Value: true
600 | r_gripper_r_finger_tip_link:
601 | Alpha: 1
602 | Show Axes: false
603 | Show Trail: false
604 | Value: true
605 | r_shoulder_lift_link:
606 | Alpha: 1
607 | Show Axes: false
608 | Show Trail: false
609 | Value: true
610 | r_shoulder_pan_link:
611 | Alpha: 1
612 | Show Axes: false
613 | Show Trail: false
614 | Value: true
615 | r_upper_arm_link:
616 | Alpha: 1
617 | Show Axes: false
618 | Show Trail: false
619 | Value: true
620 | r_upper_arm_roll_link:
621 | Alpha: 1
622 | Show Axes: false
623 | Show Trail: false
624 | Value: true
625 | r_wrist_flex_link:
626 | Alpha: 1
627 | Show Axes: false
628 | Show Trail: false
629 | Value: true
630 | r_wrist_roll_link:
631 | Alpha: 1
632 | Show Axes: false
633 | Show Trail: false
634 | Value: true
635 | sensor_mount_link:
636 | Alpha: 1
637 | Show Axes: false
638 | Show Trail: false
639 | Value: true
640 | torso_lift_link:
641 | Alpha: 1
642 | Show Axes: false
643 | Show Trail: false
644 | Value: true
645 | Robot Alpha: 0.5
646 | Show Scene Robot: true
647 | Value: true
648 | Enabled: true
649 | Global Options:
650 | Background Color: 48; 48; 48
651 | Fixed Frame: /odom
652 | Name: root
653 | Tools:
654 | - Class: rviz/Interact
655 | Hide Inactive Objects: true
656 | - Class: rviz/MoveCamera
657 | - Class: rviz/Select
658 | Value: true
659 | Views:
660 | Current:
661 | Class: rviz/XYOrbit
662 | Distance: 2.9965
663 | Focal Point:
664 | X: 0.113567
665 | Y: 0.10592
666 | Z: 2.23518e-07
667 | Name: Current View
668 | Near Clip Distance: 0.01
669 | Pitch: 0.509797
670 | Target Frame: /base_footprint
671 | Value: XYOrbit (rviz)
672 | Yaw: 5.65995
673 | Saved: ~
674 | Window Geometry:
675 | Displays:
676 | collapsed: false
677 | Height: 1337
678 | Help:
679 | collapsed: false
680 | Hide Left Dock: false
681 | Hide Right Dock: false
682 | Motion Planning:
683 | collapsed: false
684 | QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
685 | Views:
686 | collapsed: false
687 | Width: 1828
688 | X: 459
689 | Y: -243
690 |
--------------------------------------------------------------------------------