@ -0,0 +1,207 @@ | |||
cmake_minimum_required(VERSION 3.0.2) | |||
project(vz_stretch_navigation) | |||
## Compile as C++11, supported in ROS Kinetic and newer | |||
# add_compile_options(-std=c++11) | |||
## Find catkin macros and libraries | |||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) | |||
## is used, also find other catkin packages | |||
find_package(catkin REQUIRED COMPONENTS | |||
roscpp | |||
rospy | |||
std_msgs | |||
move_base | |||
) | |||
## System dependencies are found with CMake's conventions | |||
# find_package(Boost REQUIRED COMPONENTS system) | |||
## Uncomment this if the package has a setup.py. This macro ensures | |||
## modules and global scripts declared therein get installed | |||
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html | |||
# catkin_python_setup() | |||
################################################ | |||
## Declare ROS messages, services and actions ## | |||
################################################ | |||
## To declare and build messages, services or actions from within this | |||
## package, follow these steps: | |||
## * Let MSG_DEP_SET be the set of packages whose message types you use in | |||
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). | |||
## * In the file package.xml: | |||
## * add a build_depend tag for "message_generation" | |||
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET | |||
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in | |||
## but can be declared for certainty nonetheless: | |||
## * add a exec_depend tag for "message_runtime" | |||
## * In this file (CMakeLists.txt): | |||
## * add "message_generation" and every package in MSG_DEP_SET to | |||
## find_package(catkin REQUIRED COMPONENTS ...) | |||
## * add "message_runtime" and every package in MSG_DEP_SET to | |||
## catkin_package(CATKIN_DEPENDS ...) | |||
## * uncomment the add_*_files sections below as needed | |||
## and list every .msg/.srv/.action file to be processed | |||
## * uncomment the generate_messages entry below | |||
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) | |||
## Generate messages in the 'msg' folder | |||
# add_message_files( | |||
# FILES | |||
# Message1.msg | |||
# Message2.msg | |||
# ) | |||
## Generate services in the 'srv' folder | |||
# add_service_files( | |||
# FILES | |||
# Service1.srv | |||
# Service2.srv | |||
# ) | |||
## Generate actions in the 'action' folder | |||
# add_action_files( | |||
# FILES | |||
# Action1.action | |||
# Action2.action | |||
# ) | |||
## Generate added messages and services with any dependencies listed here | |||
# generate_messages( | |||
# DEPENDENCIES | |||
# std_msgs | |||
# ) | |||
################################################ | |||
## Declare ROS dynamic reconfigure parameters ## | |||
################################################ | |||
## To declare and build dynamic reconfigure parameters within this | |||
## package, follow these steps: | |||
## * In the file package.xml: | |||
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" | |||
## * In this file (CMakeLists.txt): | |||
## * add "dynamic_reconfigure" to | |||
## find_package(catkin REQUIRED COMPONENTS ...) | |||
## * uncomment the "generate_dynamic_reconfigure_options" section below | |||
## and list every .cfg file to be processed | |||
## Generate dynamic reconfigure parameters in the 'cfg' folder | |||
# generate_dynamic_reconfigure_options( | |||
# cfg/DynReconf1.cfg | |||
# cfg/DynReconf2.cfg | |||
# ) | |||
################################### | |||
## catkin specific configuration ## | |||
################################### | |||
## The catkin_package macro generates cmake config files for your package | |||
## Declare things to be passed to dependent projects | |||
## INCLUDE_DIRS: uncomment this if your package contains header files | |||
## LIBRARIES: libraries you create in this project that dependent projects also need | |||
## CATKIN_DEPENDS: catkin_packages dependent projects also need | |||
## DEPENDS: system dependencies of this project that dependent projects also need | |||
catkin_package( | |||
# INCLUDE_DIRS include | |||
# LIBRARIES vz_stretch_navigation | |||
# CATKIN_DEPENDS roscpp rospy std_msgs | |||
# DEPENDS system_lib | |||
) | |||
########### | |||
## Build ## | |||
########### | |||
## Specify additional locations of header files | |||
## Your package locations should be listed before other locations | |||
include_directories( | |||
# include | |||
${catkin_INCLUDE_DIRS} | |||
) | |||
## Declare a C++ library | |||
# add_library(${PROJECT_NAME} | |||
# src/${PROJECT_NAME}/vz_stretch.cpp | |||
# ) | |||
## Add cmake target dependencies of the library | |||
## as an example, code may need to be generated before libraries | |||
## either from message generation or dynamic reconfigure | |||
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) | |||
## Declare a C++ executable | |||
## With catkin_make all packages are built within a single CMake context | |||
## The recommended prefix ensures that target names across packages don't collide | |||
# add_executable(${PROJECT_NAME}_node src/vz_stretch_node.cpp) | |||
## Rename C++ executable without prefix | |||
## The above recommended prefix causes long target names, the following renames the | |||
## target back to the shorter version for ease of user use | |||
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" | |||
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") | |||
## Add cmake target dependencies of the executable | |||
## same as for the library above | |||
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) | |||
## Specify libraries to link a library or executable target against | |||
# target_link_libraries(${PROJECT_NAME}_node | |||
# ${catkin_LIBRARIES} | |||
# ) | |||
############# | |||
## Install ## | |||
############# | |||
# all install targets should use catkin DESTINATION variables | |||
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html | |||
## Mark executable scripts (Python etc.) for installation | |||
## in contrast to setup.py, you can choose the destination | |||
catkin_install_python(PROGRAMS | |||
scripts/simple_navigation_goal_client.py | |||
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} | |||
) | |||
## Mark executables for installation | |||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html | |||
# install(TARGETS ${PROJECT_NAME}_node | |||
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} | |||
# ) | |||
## Mark libraries for installation | |||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html | |||
# install(TARGETS ${PROJECT_NAME} | |||
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | |||
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | |||
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} | |||
# ) | |||
## Mark cpp header files for installation | |||
# install(DIRECTORY include/${PROJECT_NAME}/ | |||
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} | |||
# FILES_MATCHING PATTERN "*.h" | |||
# PATTERN ".svn" EXCLUDE | |||
# ) | |||
## Mark other files for installation (e.g. launch and bag files, etc.) | |||
# install(FILES | |||
# # myfile1 | |||
# # myfile2 | |||
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} | |||
# ) | |||
############# | |||
## Testing ## | |||
############# | |||
## Add gtest based cpp test target and link libraries | |||
# catkin_add_gtest(${PROJECT_NAME}-test test/test_vz_stretch.cpp) | |||
# if(TARGET ${PROJECT_NAME}-test) | |||
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) | |||
# endif() | |||
## Add folders to be run by python nosetests | |||
# catkin_add_nosetests(test) |
@ -0,0 +1,14 @@ | |||
DWAPlannerROS: | |||
max_vel_x: 0.4 | |||
min_vel_x: -0.2 | |||
max_vel_theta: 0.4 | |||
acc_lim_th: 1.5 | |||
acc_lim_x: 1.5 | |||
yaw_goal_tolerance: 0.1 | |||
xy_goal_tolerance: 0.1 | |||
holonomic_robot: false | |||
path_distance_bias: 50.0 |
@ -0,0 +1,8 @@ | |||
obstacle_range: 2.5 | |||
raytrace_range: 3.0 | |||
robot_radius: 0.1 | |||
inflation_radius: 0.25 | |||
observation_sources: laser_scan_sensor | |||
laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan_filtered, marking: true, clearing: true} |
@ -0,0 +1,8 @@ | |||
obstacle_range: 2.5 | |||
raytrace_range: 3.0 | |||
robot_radius: 0.1 | |||
inflation_radius: 0.25 | |||
observation_sources: laser_scan_sensor | |||
laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true} |
@ -0,0 +1,5 @@ | |||
global_costmap: | |||
global_frame: map | |||
robot_base_frame: base_link | |||
update_frequency: 5.0 | |||
static_map: false |
@ -0,0 +1,5 @@ | |||
global_costmap: | |||
global_frame: map | |||
robot_base_frame: base_link | |||
update_frequency: 5.0 | |||
static_map: true |
@ -0,0 +1,10 @@ | |||
local_costmap: | |||
global_frame: map | |||
robot_base_frame: base_link | |||
update_frequency: 5.0 | |||
publish_frequency: 2.0 | |||
static_map: false | |||
rolling_window: true | |||
width: 6.0 | |||
height: 6.0 | |||
resolution: 0.05 |
@ -0,0 +1,14 @@ | |||
TebLocalPlannerROS: | |||
max_vel_x: 0.4 | |||
max_vel_theta: 0.4 | |||
acc_lim_theta: 1.5 | |||
acc_lim_x: 1.5 | |||
acc_lim_y: 1.5 | |||
yaw_goal_tolerance: 0.05 | |||
xy_goal_tolerance: 0.1 | |||
holonomic_robot: false | |||
global_plan_viapoint_sep: 0.1 |
@ -0,0 +1,24 @@ | |||
<launch> | |||
<arg name="teleop_type" default="keyboard" doc="how to teleop ('keyboard', 'joystick', or 'none')" /> | |||
<!-- STRETCH DRIVER --> | |||
<param name="/stretch_driver/broadcast_odom_tf" type="bool" value="true"/> | |||
<param name="/stretch_driver/mode" type="string" value="navigation" /> | |||
<include file="$(find stretch_core)/launch/stretch_driver.launch" pass_all_args="true"/> | |||
<!-- LASER RANGE FINDER --> | |||
<include file="$(find stretch_core)/launch/rplidar.launch" /> | |||
<!-- TELEOP --> | |||
<include file="$(find stretch_core)/launch/teleop_twist.launch"> | |||
<arg name="teleop_type" value="$(arg teleop_type)" /> | |||
<arg name="linear" value="0.04" /> | |||
<arg name="angular" value="0.1" /> | |||
<arg name="twist_topic" value="/stretch/cmd_vel" /> | |||
</include> | |||
<!-- MAPPING --> | |||
<node pkg="gmapping" type="slam_gmapping" name="gmapping_record_map" output="log" /> | |||
</launch> |
@ -0,0 +1,30 @@ | |||
<launch> | |||
<arg name="rviz" default="true" doc="whether to show Rviz" /> | |||
<arg name="teleop_type" default="keyboard" doc="how to teleop ('keyboard', 'joystick', or 'none')" /> | |||
<arg name="gazebo_world" default="worlds/willowgarage.world" doc="the environment within which Stretch is loaded in Gazebo" /> | |||
<arg name="gazebo_gpu_lidar" default="false" doc="whether to compute lidar with hardware acceleration (requires GPU)" /> | |||
<arg name="gazebo_visualize_lidar" default="false" doc="whether to visualize planar lidar within Gazebo" /> | |||
<!-- GAZEBO SIMULATION --> | |||
<include file="$(find stretch_gazebo)/launch/gazebo.launch"> | |||
<arg name="world" value="$(arg gazebo_world)" /> | |||
<arg name="visualize_lidar" value="$(arg gazebo_visualize_lidar)" /> | |||
<arg name="gpu_lidar" value="$(arg gazebo_gpu_lidar)" /> | |||
</include> | |||
<!-- TELEOP --> | |||
<include file="$(find stretch_core)/launch/teleop_twist.launch"> | |||
<arg name="teleop_type" value="$(arg teleop_type)" /> | |||
<arg name="linear" value="1.0" /> | |||
<arg name="angular" value="2.0" /> | |||
<arg name="twist_topic" value="/stretch_diff_drive_controller/cmd_vel" /> | |||
</include> | |||
<!-- MAPPING --> | |||
<node pkg="gmapping" type="slam_gmapping" name="gmapping_record_map" output="log" /> | |||
<!-- VISUALIZE --> | |||
<node name="rviz" pkg="rviz" type="rviz" output="log" args="-d $(find stretch_navigation)/rviz/mapping.rviz" if="$(arg rviz)" /> | |||
</launch> |
@ -0,0 +1,4 @@ | |||
<launch> | |||
<arg name="rviz" default="true" doc="whether to show Rviz" /> | |||
<node name="rviz" pkg="rviz" type="rviz" output="log" args="-d $(find vz_stretch_navigation)/rviz/mapping.rviz" if="$(arg rviz)" /> | |||
</launch> |
@ -0,0 +1,30 @@ | |||
<launch> | |||
<arg name="map_yaml" doc="filepath to previously captured map (required)" /> | |||
<!-- STRETCH DRIVER --> | |||
<param name="/stretch_driver/broadcast_odom_tf" type="bool" value="true" /> | |||
<param name="/stretch_driver/mode" type="string" value="navigation" /> | |||
<include file="$(find stretch_core)/launch/stretch_driver.launch" pass_all_args="true" /> | |||
<!-- LASER RANGE FINDER --> | |||
<include file="$(find stretch_core)/launch/rplidar.launch" /> | |||
<!-- MAP SERVER --> | |||
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_yaml)" /> | |||
<!-- LOCALIZATION --> | |||
<include file="$(find amcl)/examples/amcl_diff.launch" /> | |||
<!-- NAVIGATION --> | |||
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen"> | |||
<rosparam file="$(find vz_stretch_navigation)/config/common_costmap_params.yaml" command="load" ns="global_costmap" /> | |||
<rosparam file="$(find vz_stretch_navigation)/config/common_costmap_params.yaml" command="load" ns="local_costmap" /> | |||
<rosparam file="$(find vz_stretch_navigation)/config/local_costmap_params.yaml" command="load" /> | |||
<rosparam file="$(find vz_stretch_navigation)/config/global_costmap_params_withmap.yaml" command="load" /> | |||
<rosparam file="$(find vz_stretch_navigation)/config/base_local_planner_params.yaml" command="load" /> | |||
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" /> | |||
<remap from="/cmd_vel" to="/stretch/cmd_vel" /> | |||
</node> | |||
</launch> |
@ -0,0 +1,8 @@ | |||
<launch> | |||
<!-- Doc: http://wiki.ros.org/map_server?distro=kinetic --> | |||
<arg name="map_name" default="map" /> | |||
<!-- launch map server --> | |||
<node name="map_server" pkg="map_server" type="map_server" output="screen" args="$(arg map_name)"/> | |||
</launch> |
@ -0,0 +1,30 @@ | |||
<launch> | |||
<!-- Doc: http://wiki.ros.org/move_base?distro=kinetic --> | |||
<arg name="config"/> | |||
<arg name="cmd_vel_topic"/> | |||
<arg name="odom_topic"/> | |||
<!-- Use global costmap--> | |||
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen"> | |||
<!-- Include robot specific parameters from the robot config folder --> | |||
<rosparam file="$(find stretch_navigation)/resources/config/$(arg config)/costmap_common_params.yaml" command="load" ns="global_costmap" /> | |||
<rosparam file="$(find stretch_navigation)/resources/config/costmap_height.yaml" command="load" ns="global_costmap" /> | |||
<rosparam file="$(find stretch_navigation)/resources/config/$(arg config)/global_costmap_params.yaml" command="load" /> | |||
<rosparam file="$(find stretch_navigation)/resources/config/$(arg config)/costmap_common_params.yaml" command="load" ns="local_costmap" /> | |||
<rosparam file="$(find stretch_navigation)/resources/config/costmap_height.yaml" command="load" ns="local_costmap" /> | |||
<rosparam file="$(find stretch_navigation)/resources/config/$(arg config)/local_costmap_params.yaml" command="load" /> | |||
<rosparam file="$(find stretch_navigation)/resources/config/$(arg config)/base_local_planner_params.yaml" command="load" /> | |||
<rosparam file="$(find stretch_navigation)/resources/config/$(arg config)/global_planner_params.yaml" command="load" /> | |||
<param name="conservative_reset_dist" type="double" value="3.0" /> | |||
<param name="controller_frequency" type="double" value="7.0" /> <!-- 20 --> | |||
<param name="planner_patience" value="10.0" /> | |||
<param name="max_planning_retries" value="20" /> | |||
<remap from="cmd_vel" to="$(arg cmd_vel_topic)" /> | |||
<remap from="odom" to="$(arg odom_topic)" /> | |||
</node> | |||
</launch> |
@ -0,0 +1,33 @@ | |||
<launch> | |||
<!-- Doc: http://wiki.ros.org/octomap_server?distro=kinetic --> | |||
<arg name="map" default="map" /> | |||
<arg name="base_link" default="base_link" /> | |||
<!-- launch server for positive map--> | |||
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server" output="screen" args="$(arg map)" > | |||
<remap from="cloud_in" to="pointcloud_static_octomap_ignore" /> | |||
<param name="base_frame_id" value="$(arg base_link)" /> | |||
<param name="frame_id" type="string" value="map" /> | |||
<param name="occupancy_min_z" value="0.23" /> | |||
<param name="occupancy_max_z" value="2" /> | |||
</node> | |||
<!-- launch server for negative map--> | |||
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server_negative" output="screen" args="$(arg map)" > | |||
<remap from="cloud_in" to="pointcloud_static_octomap_ignore" /> | |||
<param name="base_frame_id" value="$(arg base_link)" /> | |||
<param name="frame_id" type="string" value="map" /> | |||
<param name="occupancy_max_z" value="-0.23" /> | |||
<param name="occupancy_min_z" value="-10" /> | |||
<!-- rename all colliding topics and services--> | |||
<remap from="octomap_binary" to="octomap_binary_negative" /> | |||
<remap from="octomap_full" to="octomap_full_negative" /> | |||
<remap from="occupied_cells_vis_array" to="occupied_cells_vis_array_negative" /> | |||
<remap from="octomap_point_cloud_centers" to="octomap_point_cloud_centers_negative" /> | |||
<remap from="projected_map" to="projected_map_negative" /> | |||
<remap from="clear_bbx" to="clear_bbx_negative" /> | |||
<remap from="reset" to="reset_negative" /> | |||
</node> | |||
</launch> |
@ -0,0 +1,46 @@ | |||
<launch> | |||
<!-- The navigation_3d launch file includes all of the launch files needed for a robot to accomplish 3D navigation. | |||
The nodes needed for navigation are map_server, octomap_server, amcl, and move_base.--> | |||
<!-- Map name --> | |||
<arg name="map" default="map"/> | |||
<!-- Move_base configuration folder. --> | |||
<arg name="move_base_config" value="3d" /> | |||
<!-- Robot sensor topic mapping--> | |||
<arg name="laser_topic" default="scan"/> | |||
<arg name="pointcloud_topic" default="/camera/depth/color/points"/> | |||
<arg name="cmd_vel_topic" default="/stretch_diff_drive_controller/cmd_vel"/> | |||
<arg name="odom_topic" default="/stretch_diff_drive_controller/odom"/> | |||
<arg name="odom_link" default="odom"/> | |||
<arg name="base_link" default="base_link"/> | |||
<!-- Launch Map Server --> | |||
<include file="$(find stretch_navigation)/launch/navigation/map_server.launch"> | |||
<arg name="map_name" value="$(find stretch_navigation)/resources/static_maps/2d/$(arg map).yaml" /> | |||
</include> | |||
<!-- Launch positive and negative Octomap Server --> | |||
<include file="$(find stretch_navigation)/launch/navigation/octomap_server.launch"> | |||
<arg name="map" value="$(find stretch_navigation)/resources/static_maps/3d/$(arg map).bt" /> | |||
<arg name="base_link" value="$(arg base_link)" /> | |||
</include> | |||
<!--- Launch AMCL (Laser Localization) --> | |||
<node pkg="amcl" type="amcl" name="amcl" output="screen"> | |||
<rosparam file="$(find stretch_navigation)/resources/config/amcl.yaml" command="load" /> | |||
</node> | |||
<!-- Launch move_base --> | |||
<!-- Note that you will also need to change the relevant .yaml files (or make new copies) | |||
if you wish to use another namespace/robot_name. --> | |||
<include file="$(find stretch_navigation)/launch/navigation/move_base.launch"> | |||
<arg name="config" value="$(arg move_base_config)" /> | |||
<arg name="cmd_vel_topic" value="$(arg cmd_vel_topic)" /> | |||
<arg name="odom_topic" value="$(arg odom_topic)" /> | |||
</include> | |||
<node type="rviz" name="rviz" pkg="rviz" args="-d $(find stretch_navigation)/rviz/octomap.rviz" /> | |||
</launch> |
@ -0,0 +1,47 @@ | |||
<launch> | |||
<arg name="map_yaml" doc="filepath to previously captured map (required)" /> | |||
<arg name="rviz" default="true" doc="whether to show Rviz" /> | |||
<arg name="gazebo_world" default="worlds/willowgarage.world" doc="the environment within which Stretch is loaded in Gazebo" /> | |||
<arg name="gazebo_gpu_lidar" default="false" doc="whether to compute lidar with hardware acceleration (requires GPU)" /> | |||
<arg name="gazebo_visualize_lidar" default="false" doc="whether to visualize planar lidar within Gazebo" /> | |||
<!-- GAZEBO SIMULATION --> | |||
<include file="$(find stretch_gazebo)/launch/gazebo.launch"> | |||
<arg name="world" value="$(arg gazebo_world)" /> | |||
<arg name="visualize_lidar" value="$(arg gazebo_visualize_lidar)" /> | |||
<arg name="gpu_lidar" value="$(arg gazebo_gpu_lidar)" /> | |||
</include> | |||
<!-- MAP SERVER --> | |||
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_yaml)" /> | |||
<!-- LOCALIZATION --> | |||
<include file="$(find amcl)/examples/amcl_diff.launch" /> | |||
<!-- NAVIGATION --> | |||
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen"> | |||
<!-- The common_costmap_params_gazebo.yaml sends laser data on the /scan topic. Physical robot uses /scan_filtered --> | |||
<rosparam file="$(find vz_stretch_navigation)/config/common_costmap_params_gazebo.yaml" command="load" ns="global_costmap" /> | |||
<rosparam file="$(find vz_stretch_navigation)/config/common_costmap_params_gazebo.yaml" command="load" ns="local_costmap" /> | |||
<rosparam file="$(find vz_stretch_navigation)/config/local_costmap_params.yaml" command="load" /> | |||
<rosparam file="$(find vz_stretch_navigation)/config/global_costmap_params_withmap.yaml" command="load" /> | |||
<rosparam file="$(find vz_stretch_navigation)/config/base_local_planner_params.yaml" command="load" /> | |||
<remap from="/cmd_vel" to="/stretch_diff_drive_controller/cmd_vel" /> | |||
<!-- Switch base local planners--> | |||
<!-- Uncommenting both the following uses the simplest planner. | |||
The bottom two are long term solutions which need tuning. | |||
So they will not work well as of now --> | |||
<!-- <param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" /> --> | |||
<!-- <param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" /> --> | |||
</node> | |||
<!-- VISUALIZE --> | |||
<node name="rviz" pkg="rviz" type="rviz" output="log" args="-d $(find stretch_navigation)/rviz/navigation.rviz" if="$(arg rviz)" /> | |||
</launch> |
@ -0,0 +1,4 @@ | |||
<launch> | |||
<arg name="rviz" default="true" doc="whether to show Rviz" /> | |||
<node name="rviz" pkg="rviz" type="rviz" output="log" args="-d $(find vz_stretch_navigation)/rviz/navigation.rviz" if="$(arg rviz)" /> | |||
</launch> |
@ -0,0 +1,74 @@ | |||
<?xml version="1.0"?> | |||
<package format="2"> | |||
<name>vz_stretch_navigation</name> | |||
<version>0.0.0</version> | |||
<description>The vz_stretch_navigation package</description> | |||
<!-- One maintainer tag required, multiple allowed, one person per tag --> | |||
<!-- Example: --> | |||
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> --> | |||
<maintainer email="trivedi.ana@northeastern.edu">Ananya Trivedi</maintainer> | |||
<!-- One license tag required, multiple allowed, one license per tag --> | |||
<!-- Commonly used license strings: --> | |||
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 --> | |||
<license>BSD</license> | |||
<!-- Url tags are optional, but multiple are allowed, one per tag --> | |||
<!-- Optional attribute type can be: website, bugtracker, or repository --> | |||
<!-- Example: --> | |||
<!-- <url type="website">http://wiki.ros.org/vz_stretch_navigation</url> --> | |||
<!-- Author tags are optional, multiple are allowed, one per tag --> | |||
<!-- Authors do not have to be maintainers, but could be --> | |||
<!-- Example: --> | |||
<!-- <author email="jane.doe@example.com">Jane Doe</author> --> | |||
<!-- The *depend tags are used to specify dependencies --> | |||
<!-- Dependencies can be catkin packages or system dependencies --> | |||
<!-- Examples: --> | |||
<!-- Use depend as a shortcut for packages that are both build and exec dependencies --> | |||
<!-- <depend>roscpp</depend> --> | |||
<!-- Note that this is equivalent to the following: --> | |||
<!-- <build_depend>roscpp</build_depend> --> | |||
<!-- <exec_depend>roscpp</exec_depend> --> | |||
<!-- Use build_depend for packages you need at compile time: --> | |||
<!-- <build_depend>message_generation</build_depend> --> | |||
<!-- Use build_export_depend for packages you need in order to build against this package: --> | |||
<!-- <build_export_depend>message_generation</build_export_depend> --> | |||
<!-- Use buildtool_depend for build tool packages: --> | |||
<!-- <buildtool_depend>catkin</buildtool_depend> --> | |||
<!-- Use exec_depend for packages you need at runtime: --> | |||
<!-- <exec_depend>message_runtime</exec_depend> --> | |||
<!-- Use test_depend for packages you need only for testing: --> | |||
<!-- <test_depend>gtest</test_depend> --> | |||
<!-- Use doc_depend for packages you need only for building documentation: --> | |||
<!-- <doc_depend>doxygen</doc_depend> --> | |||
<buildtool_depend>catkin</buildtool_depend> | |||
<build_depend>roscpp</build_depend> | |||
<build_depend>rospy</build_depend> | |||
<build_depend>std_msgs</build_depend> | |||
<build_export_depend>roscpp</build_export_depend> | |||
<build_export_depend>rospy</build_export_depend> | |||
<build_export_depend>std_msgs</build_export_depend> | |||
<exec_depend>roscpp</exec_depend> | |||
<exec_depend>rospy</exec_depend> | |||
<exec_depend>std_msgs</exec_depend> | |||
<exec_depend>move_base</exec_depend> | |||
<exec_depend>amcl</exec_depend> | |||
<exec_depend>map_server</exec_depend> | |||
<exec_depend>gmapping</exec_depend> | |||
<exec_depend>stretch_core</exec_depend> | |||
<!-- The export tag contains other, unspecified, tags --> | |||
<export> | |||
<!-- Other tools can request additional information be placed here --> | |||
</export> | |||
</package> |
@ -0,0 +1,445 @@ | |||
Panels: | |||
- Class: rviz/Displays | |||
Help Height: 78 | |||
Name: Displays | |||
Property Tree Widget: | |||
Expanded: | |||
- /Odometry1/Shape1 | |||
- /OccupancyGrid1 | |||
Splitter Ratio: 0.5 | |||
Tree Height: 539 | |||
- Class: rviz/Selection | |||
Name: Selection | |||
- Class: rviz/Tool Properties | |||
Expanded: | |||
- /2D Pose Estimate1 | |||
- /2D Nav Goal1 | |||
- /Publish Point1 | |||
Name: Tool Properties | |||
Splitter Ratio: 0.5886790156364441 | |||
- Class: rviz/Views | |||
Expanded: | |||
- /Current View1 | |||
Name: Views | |||
Splitter Ratio: 0.5 | |||
- Class: rviz/Time | |||
Experimental: false | |||
Name: Time | |||
SyncMode: 0 | |||
SyncSource: LaserScan | |||
Preferences: | |||
PromptSaveOnExit: true | |||
Toolbars: | |||
toolButtonStyle: 2 | |||
Visualization Manager: | |||
Class: "" | |||
Displays: | |||
- Alpha: 0.5 | |||
Cell Size: 1 | |||
Class: rviz/Grid | |||
Color: 160; 160; 164 | |||
Enabled: true | |||
Line Style: | |||
Line Width: 0.029999999329447746 | |||
Value: Lines | |||
Name: Grid | |||
Normal Cell Count: 0 | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Plane: XY | |||
Plane Cell Count: 10 | |||
Reference Frame: <Fixed Frame> | |||
Value: true | |||
- Alpha: 0.5 | |||
Class: rviz/RobotModel | |||
Collision Enabled: false | |||
Enabled: true | |||
Links: | |||
All Links Enabled: true | |||
Expand Joint Details: false | |||
Expand Link Details: false | |||
Expand Tree: false | |||
Link Tree Style: Links in Alphabetic Order | |||
base_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
camera_accel_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_accel_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_bottom_screw_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
caster_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
laser: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l0: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l1: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l2: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l3: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l4: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_inner_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_left_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_right_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_shoulder: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_top_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_grasp_center: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
link_gripper: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_pan: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_tilt: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_left_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_lift: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_mast: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_right_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_wrist_yaw: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
respeaker_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
Name: RobotModel | |||
Robot Description: robot_description | |||
TF Prefix: "" | |||
Update Interval: 0 | |||
Value: true | |||
Visual Enabled: true | |||
- Alpha: 1 | |||
Autocompute Intensity Bounds: true | |||
Autocompute Value Bounds: | |||
Max Value: 10 | |||
Min Value: -10 | |||
Value: true | |||
Axis: Z | |||
Channel Name: intensity | |||
Class: rviz/LaserScan | |||
Color: 255; 255; 255 | |||
Color Transformer: Intensity | |||
Decay Time: 0 | |||
Enabled: true | |||
Invert Rainbow: false | |||
Max Color: 255; 255; 255 | |||
Min Color: 0; 0; 0 | |||
Name: LaserScan | |||
Position Transformer: XYZ | |||
Queue Size: 10 | |||
Selectable: true | |||
Size (Pixels): 3 | |||
Size (m): 0.009999999776482582 | |||
Style: Flat Squares | |||
Topic: /scan | |||
Unreliable: false | |||
Use Fixed Frame: true | |||
Use rainbow: true | |||
Value: true | |||
- Alpha: 1 | |||
Autocompute Intensity Bounds: true | |||
Autocompute Value Bounds: | |||
Max Value: 10 | |||
Min Value: -10 | |||
Value: true | |||
Axis: Z | |||
Channel Name: intensity | |||
Class: rviz/PointCloud2 | |||
Color: 255; 255; 255 | |||
Color Transformer: RGB8 | |||
Decay Time: 0 | |||
Enabled: false | |||
Invert Rainbow: false | |||
Max Color: 255; 255; 255 | |||
Min Color: 0; 0; 0 | |||
Name: PointCloud2 | |||
Position Transformer: XYZ | |||
Queue Size: 10 | |||
Selectable: true | |||
Size (Pixels): 4 | |||
Size (m): 0.004000000189989805 | |||
Style: Points | |||
Topic: /camera/depth/color/points | |||
Unreliable: false | |||
Use Fixed Frame: true | |||
Use rainbow: true | |||
Value: false | |||
- Angle Tolerance: 0.10000000149011612 | |||
Class: rviz/Odometry | |||
Covariance: | |||
Orientation: | |||
Alpha: 0.5 | |||
Color: 255; 255; 127 | |||
Color Style: Unique | |||
Frame: Local | |||
Offset: 1 | |||
Scale: 1 | |||
Value: true | |||
Position: | |||
Alpha: 0.30000001192092896 | |||
Color: 204; 51; 204 | |||
Scale: 1 | |||
Value: true | |||
Value: true | |||
Enabled: true | |||
Keep: 10 | |||
Name: Odometry | |||
Position Tolerance: 0.10000000149011612 | |||
Queue Size: 10 | |||
Shape: | |||
Alpha: 1 | |||
Axes Length: 1 | |||
Axes Radius: 0.10000000149011612 | |||
Color: 237; 212; 0 | |||
Head Length: 0.03999999910593033 | |||
Head Radius: 0.05000000074505806 | |||
Shaft Length: 0.15000000596046448 | |||
Shaft Radius: 0.019999999552965164 | |||
Value: Arrow | |||
Topic: /odom | |||
Unreliable: false | |||
Value: true | |||
- Alpha: 0.699999988079071 | |||
Class: rviz/Map | |||
Color Scheme: map | |||
Draw Behind: false | |||
Enabled: true | |||
Name: Map | |||
Topic: map | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Class: octomap_rviz_plugin/OccupancyGrid | |||
Enabled: true | |||
Max. Height Display: inf | |||
Max. Octree Depth: 16 | |||
Min. Height Display: -inf | |||
Name: OccupancyGrid | |||
Octomap Topic: /octomap_full | |||
Queue Size: 5 | |||
Value: true | |||
Voxel Alpha: 1 | |||
Voxel Coloring: Z-Axis | |||
Voxel Rendering: Occupied Voxels | |||
Enabled: true | |||
Global Options: | |||
Background Color: 48; 48; 48 | |||
Default Light: true | |||
Fixed Frame: odom | |||
Frame Rate: 30 | |||
Name: root | |||
Tools: | |||
- Class: rviz/Interact | |||
Hide Inactive Objects: true | |||
- Class: rviz/MoveCamera | |||
- Class: rviz/Select | |||
- Class: rviz/FocusCamera | |||
- Class: rviz/Measure | |||
- Class: rviz/SetInitialPose | |||
Theta std deviation: 0.2617993950843811 | |||
Topic: /initialpose | |||
X std deviation: 0.5 | |||
Y std deviation: 0.5 | |||
- Class: rviz/SetGoal | |||
Topic: /move_base_simple/goal | |||
- Class: rviz/PublishPoint | |||
Single click: true | |||
Topic: /clicked_point | |||
Value: true | |||
Views: | |||
Current: | |||
Class: rviz/Orbit | |||
Distance: 5.0032243728637695 | |||
Enable Stereo Rendering: | |||
Stereo Eye Separation: 0.05999999865889549 | |||
Stereo Focal Distance: 1 | |||
Swap Stereo Eyes: false | |||
Value: false | |||
Field of View: 0.7853981852531433 | |||
Focal Point: | |||
X: 0.2743038535118103 | |||
Y: 0.44053205847740173 | |||
Z: 0.8585693836212158 | |||
Focal Shape Fixed Size: true | |||
Focal Shape Size: 0.05000000074505806 | |||
Invert Z Axis: false | |||
Name: Current View | |||
Near Clip Distance: 0.009999999776482582 | |||
Pitch: 1.5697963237762451 | |||
Target Frame: <Fixed Frame> | |||
Yaw: 3.2263076305389404 | |||
Saved: ~ | |||
Window Geometry: | |||
Displays: | |||
collapsed: false | |||
Height: 836 | |||
Hide Left Dock: false | |||
Hide Right Dock: false | |||
QMainWindow State: 000000ff00000000fd0000000400000000000001b5000002a6fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002a6000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d0065010000000000000640000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000485000002a600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 | |||
Selection: | |||
collapsed: false | |||
Time: | |||
collapsed: false | |||
Tool Properties: | |||
collapsed: false | |||
Views: | |||
collapsed: false | |||
Width: 1600 | |||
X: 0 | |||
Y: 27 |
@ -0,0 +1,544 @@ | |||
Panels: | |||
- Class: rviz/Displays | |||
Help Height: 78 | |||
Name: Displays | |||
Property Tree Widget: | |||
Expanded: | |||
- /Odometry1/Shape1 | |||
- /Path to Goal1 | |||
- /Path1 | |||
Splitter Ratio: 0.6117647290229797 | |||
Tree Height: 839 | |||
- Class: rviz/Selection | |||
Name: Selection | |||
- Class: rviz/Tool Properties | |||
Expanded: | |||
- /2D Pose Estimate1 | |||
- /2D Nav Goal1 | |||
- /Publish Point1 | |||
Name: Tool Properties | |||
Splitter Ratio: 0.5886790156364441 | |||
- Class: rviz/Views | |||
Expanded: | |||
- /Current View1 | |||
Name: Views | |||
Splitter Ratio: 0.5 | |||
- Class: rviz/Time | |||
Experimental: false | |||
Name: Time | |||
SyncMode: 0 | |||
SyncSource: Filtered Laser Scan | |||
Preferences: | |||
PromptSaveOnExit: true | |||
Toolbars: | |||
toolButtonStyle: 2 | |||
Visualization Manager: | |||
Class: "" | |||
Displays: | |||
- Alpha: 0.5 | |||
Cell Size: 1 | |||
Class: rviz/Grid | |||
Color: 160; 160; 164 | |||
Enabled: true | |||
Line Style: | |||
Line Width: 0.029999999329447746 | |||
Value: Lines | |||
Name: Grid | |||
Normal Cell Count: 0 | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Plane: XY | |||
Plane Cell Count: 10 | |||
Reference Frame: <Fixed Frame> | |||
Value: true | |||
- Alpha: 0.5 | |||
Class: rviz/RobotModel | |||
Collision Enabled: false | |||
Enabled: true | |||
Links: | |||
All Links Enabled: true | |||
Expand Joint Details: false | |||
Expand Link Details: false | |||
Expand Tree: false | |||
Link Tree Style: Links in Alphabetic Order | |||
base_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
camera_accel_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_accel_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_bottom_screw_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
caster_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
laser: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l0: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l1: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l2: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l3: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l4: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_inner_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_left_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_right_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_shoulder: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_top_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_grasp_center: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
link_gripper: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_pan: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_tilt: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_left_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_lift: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_mast: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_right_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_wrist_yaw: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
respeaker_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
Name: RobotModel | |||
Robot Description: robot_description | |||
TF Prefix: "" | |||
Update Interval: 0 | |||
Value: true | |||
Visual Enabled: true | |||
- Alpha: 1 | |||
Autocompute Intensity Bounds: true | |||
Autocompute Value Bounds: | |||
Max Value: 10 | |||
Min Value: -10 | |||
Value: true | |||
Axis: Z | |||
Channel Name: intensity | |||
Class: rviz/LaserScan | |||
Color: 255; 255; 255 | |||
Color Transformer: Intensity | |||
Decay Time: 0 | |||
Enabled: false | |||
Invert Rainbow: false | |||
Max Color: 255; 255; 255 | |||
Min Color: 0; 0; 0 | |||
Name: Captured Laser Scan | |||
Position Transformer: XYZ | |||
Queue Size: 10 | |||
Selectable: true | |||
Size (Pixels): 3 | |||
Size (m): 0.009999999776482582 | |||
Style: Flat Squares | |||
Topic: /scan | |||
Unreliable: false | |||
Use Fixed Frame: true | |||
Use rainbow: true | |||
Value: false | |||
- Alpha: 1 | |||
Autocompute Intensity Bounds: true | |||
Autocompute Value Bounds: | |||
Max Value: 10 | |||
Min Value: -10 | |||
Value: true | |||
Axis: Z | |||
Channel Name: intensity | |||
Class: rviz/LaserScan | |||
Color: 255; 255; 255 | |||
Color Transformer: Intensity | |||
Decay Time: 0 | |||
Enabled: true | |||
Invert Rainbow: false | |||
Max Color: 255; 255; 255 | |||
Min Color: 0; 0; 0 | |||
Name: Filtered Laser Scan | |||
Position Transformer: XYZ | |||
Queue Size: 10 | |||
Selectable: true | |||
Size (Pixels): 3 | |||
Size (m): 0.009999999776482582 | |||
Style: Flat Squares | |||
Topic: /scan_filtered | |||
Unreliable: false | |||
Use Fixed Frame: true | |||
Use rainbow: true | |||
Value: true | |||
- Angle Tolerance: 0.10000000149011612 | |||
Class: rviz/Odometry | |||
Covariance: | |||
Orientation: | |||
Alpha: 0.5 | |||
Color: 255; 255; 127 | |||
Color Style: Unique | |||
Frame: Local | |||
Offset: 1 | |||
Scale: 1 | |||
Value: true | |||
Position: | |||
Alpha: 0.30000001192092896 | |||
Color: 204; 51; 204 | |||
Scale: 1 | |||
Value: true | |||
Value: true | |||
Enabled: true | |||
Keep: 30 | |||
Name: Odometry | |||
Position Tolerance: 0.10000000149011612 | |||
Queue Size: 10 | |||
Shape: | |||
Alpha: 1 | |||
Axes Length: 1 | |||
Axes Radius: 0.10000000149011612 | |||
Color: 237; 212; 0 | |||
Head Length: 0.03999999910593033 | |||
Head Radius: 0.05000000074505806 | |||
Shaft Length: 0.10000000149011612 | |||
Shaft Radius: 0.019999999552965164 | |||
Value: Arrow | |||
Topic: /odom | |||
Unreliable: false | |||
Value: true | |||
- Alpha: 1 | |||
Arrow Length: 0.10000000149011612 | |||
Axes Length: 0.30000001192092896 | |||
Axes Radius: 0.009999999776482582 | |||
Class: rviz/PoseArray | |||
Color: 252; 175; 62 | |||
Enabled: true | |||
Head Length: 0.07000000029802322 | |||
Head Radius: 0.029999999329447746 | |||
Name: AMCL Particles | |||
Queue Size: 10 | |||
Shaft Length: 0.23000000417232513 | |||
Shaft Radius: 0.009999999776482582 | |||
Shape: Arrow (Flat) | |||
Topic: /particlecloud | |||
Unreliable: false | |||
Value: true | |||
- Alpha: 0.699999988079071 | |||
Class: rviz/Map | |||
Color Scheme: map | |||
Draw Behind: false | |||
Enabled: true | |||
Name: Map | |||
Topic: map | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Alpha: 0.699999988079071 | |||
Class: rviz/Map | |||
Color Scheme: costmap | |||
Draw Behind: true | |||
Enabled: true | |||
Name: Global Costmap | |||
Topic: /move_base/global_costmap/costmap | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Alpha: 0.699999988079071 | |||
Class: rviz/Map | |||
Color Scheme: costmap | |||
Draw Behind: true | |||
Enabled: true | |||
Name: Local Costmap | |||
Topic: /move_base/local_costmap/costmap | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Alpha: 1 | |||
Class: rviz/Polygon | |||
Color: 252; 233; 79 | |||
Enabled: true | |||
Name: Local Footprint | |||
Queue Size: 10 | |||
Topic: /move_base/local_costmap/footprint | |||
Unreliable: false | |||
Value: true | |||
- Alpha: 1 | |||
Axes Length: 1 | |||
Axes Radius: 0.10000000149011612 | |||
Class: rviz/Pose | |||
Color: 138; 226; 52 | |||
Enabled: true | |||
Head Length: 0.07000000029802322 | |||
Head Radius: 0.10000000149011612 | |||
Name: Goal Pose | |||
Queue Size: 10 | |||
Shaft Length: 0.23000000417232513 | |||
Shaft Radius: 0.05000000074505806 | |||
Shape: Arrow | |||
Topic: /move_base_simple/goal | |||
Unreliable: false | |||
Value: true | |||
- Alpha: 1 | |||
Buffer Length: 1 | |||
Class: rviz/Path | |||
Color: 25; 255; 0 | |||
Enabled: true | |||
Head Diameter: 0.05000000074505806 | |||
Head Length: 0.019999999552965164 | |||
Length: 0.05000000074505806 | |||
Line Style: Billboards | |||
Line Width: 0.029999999329447746 | |||
Name: Path to Goal | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Pose Color: 114; 159; 207 | |||
Pose Style: None | |||
Queue Size: 10 | |||
Radius: 0.009999999776482582 | |||
Shaft Diameter: 0.03999999910593033 | |||
Shaft Length: 0.10000000149011612 | |||
Topic: /move_base/DWAPlannerROS/global_plan | |||
Unreliable: false | |||
Value: true | |||
- Alpha: 1 | |||
Buffer Length: 10 | |||
Class: rviz/Path | |||
Color: 239; 41; 41 | |||
Enabled: true | |||
Head Diameter: 0.30000001192092896 | |||
Head Length: 0.20000000298023224 | |||
Length: 0.30000001192092896 | |||
Line Style: Lines | |||
Line Width: 0.029999999329447746 | |||
Name: Path | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Pose Color: 255; 85; 255 | |||
Pose Style: None | |||
Queue Size: 10 | |||
Radius: 0.029999999329447746 | |||
Shaft Diameter: 0.10000000149011612 | |||
Shaft Length: 0.10000000149011612 | |||
Topic: /move_base/DWAPlannerROS/local_plan | |||
Unreliable: false | |||
Value: true | |||
Enabled: true | |||
Global Options: | |||
Background Color: 48; 48; 48 | |||
Default Light: true | |||
Fixed Frame: map | |||
Frame Rate: 30 | |||
Name: root | |||
Tools: | |||
- Class: rviz/Interact | |||
Hide Inactive Objects: true | |||
- Class: rviz/MoveCamera | |||
- Class: rviz/Select | |||
- Class: rviz/FocusCamera | |||
- Class: rviz/Measure | |||
- Class: rviz/SetInitialPose | |||
Theta std deviation: 0.2617993950843811 | |||
Topic: /initialpose | |||
X std deviation: 0.5 | |||
Y std deviation: 0.5 | |||
- Class: rviz/SetGoal | |||
Topic: /move_base_simple/goal | |||
- Class: rviz/PublishPoint | |||
Single click: true | |||
Topic: /clicked_point | |||
Value: true | |||
Views: | |||
Current: | |||
Class: rviz/Orbit | |||
Distance: 17.69406509399414 | |||
Enable Stereo Rendering: | |||
Stereo Eye Separation: 0.05999999865889549 | |||
Stereo Focal Distance: 1 | |||
Swap Stereo Eyes: false | |||
Value: false | |||
Field of View: 0.7853981852531433 | |||
Focal Point: | |||
X: -0.35903388261795044 | |||
Y: 0.7160218954086304 | |||
Z: 0.5280526876449585 | |||
Focal Shape Fixed Size: true | |||
Focal Shape Size: 0.05000000074505806 | |||
Invert Z Axis: false | |||
Name: Current View | |||
Near Clip Distance: 0.009999999776482582 | |||
Pitch: 1.5697963237762451 | |||
Target Frame: <Fixed Frame> | |||
Yaw: 3.1481218338012695 | |||
Saved: ~ | |||
Window Geometry: | |||
Displays: | |||
collapsed: false | |||
Height: 1136 | |||
Hide Left Dock: false | |||
Hide Right Dock: false | |||
QMainWindow State: 000000ff00000000fd000000040000000000000156000003d2fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003d2000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d0065010000000000000738000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005dc000003d200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 | |||
Selection: | |||
collapsed: false | |||
Time: | |||
collapsed: false | |||
Tool Properties: | |||
collapsed: false | |||
Views: | |||
collapsed: false | |||
Width: 1848 | |||
X: 72 | |||
Y: 27 |
@ -0,0 +1,405 @@ | |||
Panels: | |||
- Class: rviz/Displays | |||
Help Height: 78 | |||
Name: Displays | |||
Property Tree Widget: | |||
Expanded: | |||
- /Global Options1 | |||
- /Status1 | |||
- /OccupancyMap1 | |||
- /Map1 | |||
- /Path1 | |||
- /Path2 | |||
Splitter Ratio: 0.5 | |||
Tree Height: 1082 | |||
- Class: rviz/Selection | |||
Name: Selection | |||
- Class: rviz/Tool Properties | |||
Expanded: | |||
- /2D Pose Estimate1 | |||
- /2D Nav Goal1 | |||
- /Publish Point1 | |||
Name: Tool Properties | |||
Splitter Ratio: 0.5886790156364441 | |||
- Class: rviz/Views | |||
Expanded: | |||
- /Current View1 | |||
Name: Views | |||
Splitter Ratio: 0.5 | |||
- Class: rviz/Time | |||
Experimental: false | |||
Name: Time | |||
SyncMode: 0 | |||
SyncSource: "" | |||
Preferences: | |||
PromptSaveOnExit: true | |||
Toolbars: | |||
toolButtonStyle: 2 | |||
Visualization Manager: | |||
Class: "" | |||
Displays: | |||
- Alpha: 0.5 | |||
Cell Size: 1 | |||
Class: rviz/Grid | |||
Color: 160; 160; 164 | |||
Enabled: true | |||
Line Style: | |||
Line Width: 0.029999999329447746 | |||
Value: Lines | |||
Name: Grid | |||
Normal Cell Count: 0 | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Plane: XY | |||
Plane Cell Count: 10 | |||
Reference Frame: <Fixed Frame> | |||
Value: true | |||
- Alpha: 0.699999988079071 | |||
Class: octomap_rviz_plugin/OccupancyMap | |||
Color Scheme: map | |||
Draw Behind: false | |||
Enabled: true | |||
Max. Octree Depth: 16 | |||
Name: OccupancyMap | |||
Octomap Binary Topic: /octomap_full | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Alpha: 1 | |||
Class: rviz/RobotModel | |||
Collision Enabled: false | |||
Enabled: true | |||
Links: | |||
All Links Enabled: true | |||
Expand Joint Details: false | |||
Expand Link Details: false | |||
Expand Tree: false | |||
Link Tree Style: Links in Alphabetic Order | |||
base_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
camera_accel_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_accel_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_bottom_screw_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
caster_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
laser: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l0: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l1: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l2: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l3: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l4: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_inner_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_left_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_right_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_shoulder: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_top_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_grasp_center: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
link_gripper: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_pan: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_tilt: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_left_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_lift: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_mast: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_right_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_wrist_yaw: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
respeaker_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
Name: RobotModel | |||
Robot Description: robot_description | |||
TF Prefix: "" | |||
Update Interval: 0 | |||
Value: true | |||
Visual Enabled: true | |||
- Alpha: 0.699999988079071 | |||
Class: rviz/Map | |||
Color Scheme: costmap | |||
Draw Behind: false | |||
Enabled: true | |||
Name: Map | |||
Topic: /move_base/local_costmap/costmap | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Alpha: 1 | |||
Buffer Length: 1 | |||
Class: rviz/Path | |||
Color: 25; 255; 0 | |||
Enabled: true | |||
Head Diameter: 0.30000001192092896 | |||
Head Length: 0.20000000298023224 | |||
Length: 0.30000001192092896 | |||
Line Style: Lines | |||
Line Width: 0.029999999329447746 | |||
Name: Path | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Pose Color: 255; 85; 255 | |||
Pose Style: None | |||
Queue Size: 10 | |||
Radius: 0.029999999329447746 | |||
Shaft Diameter: 0.10000000149011612 | |||
Shaft Length: 0.10000000149011612 | |||
Topic: /move_base/DWAPlannerROS/global_plan | |||
Unreliable: false | |||
Value: true | |||
- Alpha: 1 | |||
Buffer Length: 1 | |||
Class: rviz/Path | |||
Color: 25; 255; 0 | |||
Enabled: true | |||
Head Diameter: 0.30000001192092896 | |||
Head Length: 0.20000000298023224 | |||
Length: 0.30000001192092896 | |||
Line Style: Lines | |||
Line Width: 0.029999999329447746 | |||
Name: Path | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Pose Color: 255; 85; 255 | |||
Pose Style: None | |||
Queue Size: 10 | |||
Radius: 0.029999999329447746 | |||
Shaft Diameter: 0.10000000149011612 | |||
Shaft Length: 0.10000000149011612 | |||
Topic: /move_base/DWAPlannerROS/local_plan | |||
Unreliable: false | |||
Value: true | |||
Enabled: true | |||
Global Options: | |||
Background Color: 48; 48; 48 | |||
Default Light: true | |||
Fixed Frame: map | |||
Frame Rate: 30 | |||
Name: root | |||
Tools: | |||
- Class: rviz/Interact | |||
Hide Inactive Objects: true | |||
- Class: rviz/MoveCamera | |||
- Class: rviz/Select | |||
- Class: rviz/FocusCamera | |||
- Class: rviz/Measure | |||
- Class: rviz/SetInitialPose | |||
Theta std deviation: 0.2617993950843811 | |||
Topic: /initialpose | |||
X std deviation: 0.5 | |||
Y std deviation: 0.5 | |||
- Class: rviz/SetGoal | |||
Topic: /move_base_simple/goal | |||
- Class: rviz/PublishPoint | |||
Single click: true | |||
Topic: /clicked_point | |||
Value: true | |||
Views: | |||
Current: | |||
Class: rviz/Orbit | |||
Distance: 24.759632110595703 | |||
Enable Stereo Rendering: | |||
Stereo Eye Separation: 0.05999999865889549 | |||
Stereo Focal Distance: 1 | |||
Swap Stereo Eyes: false | |||
Value: false | |||
Field of View: 0.7853981852531433 | |||
Focal Point: | |||
X: -4.327556133270264 | |||
Y: -6.250387668609619 | |||
Z: -5.1258134841918945 | |||
Focal Shape Fixed Size: true | |||
Focal Shape Size: 0.05000000074505806 | |||
Invert Z Axis: false | |||
Name: Current View | |||
Near Clip Distance: 0.009999999776482582 | |||
Pitch: 0.785398006439209 | |||
Target Frame: <Fixed Frame> | |||
Yaw: 0.785398006439209 | |||
Saved: ~ | |||
Window Geometry: | |||
Displays: | |||
collapsed: false | |||
Height: 1376 | |||
Hide Left Dock: false | |||
Hide Right Dock: false | |||
QMainWindow State: 000000ff00000000fd000000040000000000000156000004c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003c000004c4000000c800fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000004c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003c000004c4000000a200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005000000003efc0100000002fb0000000800540069006d00650100000000000005000000029800fffffffb0000000800540069006d006501000000000000045000000000000000000000028f000004c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 | |||
Selection: | |||
collapsed: false | |||
Time: | |||
collapsed: false | |||
Tool Properties: | |||
collapsed: false | |||
Views: | |||
collapsed: false | |||
Width: 1280 | |||
X: 0 | |||
Y: 27 |
@ -0,0 +1,447 @@ | |||
Panels: | |||
- Class: rviz/Displays | |||
Help Height: 78 | |||
Name: Displays | |||
Property Tree Widget: | |||
Expanded: | |||
- /Global Options1 | |||
- /Status1 | |||
- /Odometry1/Shape1 | |||
- /OccupancyGrid1 | |||
Splitter Ratio: 0.4206896424293518 | |||
Tree Height: 1109 | |||
- Class: rviz/Selection | |||
Name: Selection | |||
- Class: rviz/Tool Properties | |||
Expanded: | |||
- /2D Pose Estimate1 | |||
- /2D Nav Goal1 | |||
- /Publish Point1 | |||
Name: Tool Properties | |||
Splitter Ratio: 0.5886790156364441 | |||
- Class: rviz/Views | |||
Expanded: | |||
- /Current View1 | |||
Name: Views | |||
Splitter Ratio: 0.5 | |||
- Class: rviz/Time | |||
Experimental: false | |||
Name: Time | |||
SyncMode: 0 | |||
SyncSource: LaserScan | |||
Preferences: | |||
PromptSaveOnExit: true | |||
Toolbars: | |||
toolButtonStyle: 2 | |||
Visualization Manager: | |||
Class: "" | |||
Displays: | |||
- Alpha: 0.5 | |||
Cell Size: 1 | |||
Class: rviz/Grid | |||
Color: 160; 160; 164 | |||
Enabled: false | |||
Line Style: | |||
Line Width: 0.029999999329447746 | |||
Value: Lines | |||
Name: Grid | |||
Normal Cell Count: 0 | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Plane: XY | |||
Plane Cell Count: 10 | |||
Reference Frame: <Fixed Frame> | |||
Value: false | |||
- Alpha: 0.5 | |||
Class: rviz/RobotModel | |||
Collision Enabled: false | |||
Enabled: true | |||
Links: | |||
All Links Enabled: true | |||
Expand Joint Details: false | |||
Expand Link Details: false | |||
Expand Tree: false | |||
Link Tree Style: Links in Alphabetic Order | |||
base_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
camera_accel_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_accel_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_bottom_screw_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
caster_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
laser: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l0: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l1: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l2: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l3: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l4: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_inner_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_left_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_right_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_shoulder: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_top_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_grasp_center: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
link_gripper: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_pan: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_tilt: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_left_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_lift: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_mast: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_right_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_wrist_yaw: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
respeaker_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
Name: RobotModel | |||
Robot Description: robot_description | |||
TF Prefix: "" | |||
Update Interval: 0 | |||
Value: true | |||
Visual Enabled: true | |||
- Alpha: 1 | |||
Autocompute Intensity Bounds: true | |||
Autocompute Value Bounds: | |||
Max Value: 10 | |||
Min Value: -10 | |||
Value: true | |||
Axis: Z | |||
Channel Name: intensity | |||
Class: rviz/LaserScan | |||
Color: 255; 255; 255 | |||
Color Transformer: Intensity | |||
Decay Time: 0 | |||
Enabled: true | |||
Invert Rainbow: false | |||
Max Color: 255; 255; 255 | |||
Min Color: 0; 0; 0 | |||
Name: LaserScan | |||
Position Transformer: XYZ | |||
Queue Size: 10 | |||
Selectable: true | |||
Size (Pixels): 3 | |||
Size (m): 0.009999999776482582 | |||
Style: Flat Squares | |||
Topic: /scan | |||
Unreliable: false | |||
Use Fixed Frame: true | |||
Use rainbow: true | |||
Value: true | |||
- Alpha: 1 | |||
Autocompute Intensity Bounds: true | |||
Autocompute Value Bounds: | |||
Max Value: 10 | |||
Min Value: -10 | |||
Value: true | |||
Axis: Z | |||
Channel Name: intensity | |||
Class: rviz/PointCloud2 | |||
Color: 255; 255; 255 | |||
Color Transformer: RGB8 | |||
Decay Time: 0 | |||
Enabled: false | |||
Invert Rainbow: false | |||
Max Color: 255; 255; 255 | |||
Min Color: 0; 0; 0 | |||
Name: PointCloud2 | |||
Position Transformer: XYZ | |||
Queue Size: 10 | |||
Selectable: true | |||
Size (Pixels): 4 | |||
Size (m): 0.004000000189989805 | |||
Style: Points | |||
Topic: /camera/depth/color/points | |||
Unreliable: false | |||
Use Fixed Frame: true | |||
Use rainbow: true | |||
Value: false | |||
- Angle Tolerance: 0.10000000149011612 | |||
Class: rviz/Odometry | |||
Covariance: | |||
Orientation: | |||
Alpha: 0.5 | |||
Color: 255; 255; 127 | |||
Color Style: Unique | |||
Frame: Local | |||
Offset: 1 | |||
Scale: 1 | |||
Value: true | |||
Position: | |||
Alpha: 0.30000001192092896 | |||
Color: 204; 51; 204 | |||
Scale: 1 | |||
Value: true | |||
Value: true | |||
Enabled: true | |||
Keep: 10 | |||
Name: Odometry | |||
Position Tolerance: 0.10000000149011612 | |||
Queue Size: 10 | |||
Shape: | |||
Alpha: 1 | |||
Axes Length: 1 | |||
Axes Radius: 0.10000000149011612 | |||
Color: 237; 212; 0 | |||
Head Length: 0.03999999910593033 | |||
Head Radius: 0.05000000074505806 | |||
Shaft Length: 0.15000000596046448 | |||
Shaft Radius: 0.019999999552965164 | |||
Value: Arrow | |||
Topic: /odom | |||
Unreliable: false | |||
Value: true | |||
- Alpha: 0.699999988079071 | |||
Class: rviz/Map | |||
Color Scheme: map | |||
Draw Behind: false | |||
Enabled: true | |||
Name: Map | |||
Topic: map | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Class: octomap_rviz_plugin/OccupancyGrid | |||
Enabled: true | |||
Max. Height Display: inf | |||
Max. Octree Depth: 16 | |||
Min. Height Display: -inf | |||
Name: OccupancyGrid | |||
Octomap Topic: /octomap_full | |||
Queue Size: 5 | |||
Value: true | |||
Voxel Alpha: 1 | |||
Voxel Coloring: Z-Axis | |||
Voxel Rendering: Occupied Voxels | |||
Enabled: true | |||
Global Options: | |||
Background Color: 48; 48; 48 | |||
Default Light: true | |||
Fixed Frame: map | |||
Frame Rate: 30 | |||
Name: root | |||
Tools: | |||
- Class: rviz/Interact | |||
Hide Inactive Objects: true | |||
- Class: rviz/MoveCamera | |||
- Class: rviz/Select | |||
- Class: rviz/FocusCamera | |||
- Class: rviz/Measure | |||
- Class: rviz/SetInitialPose | |||
Theta std deviation: 0.2617993950843811 | |||
Topic: /initialpose | |||
X std deviation: 0.5 | |||
Y std deviation: 0.5 | |||
- Class: rviz/SetGoal | |||
Topic: /move_base_simple/goal | |||
- Class: rviz/PublishPoint | |||
Single click: true | |||
Topic: /clicked_point | |||
Value: true | |||
Views: | |||
Current: | |||
Class: rviz/Orbit | |||
Distance: 11.191774368286133 | |||
Enable Stereo Rendering: | |||
Stereo Eye Separation: 0.05999999865889549 | |||
Stereo Focal Distance: 1 | |||
Swap Stereo Eyes: false | |||
Value: false | |||
Field of View: 0.7853981852531433 | |||
Focal Point: | |||
X: -5.315392971038818 | |||
Y: -3.4429707527160645 | |||
Z: -0.27000176906585693 | |||
Focal Shape Fixed Size: true | |||
Focal Shape Size: 0.05000000074505806 | |||
Invert Z Axis: false | |||
Name: Current View | |||
Near Clip Distance: 0.009999999776482582 | |||
Pitch: 1.0197970867156982 | |||
Target Frame: <Fixed Frame> | |||
Yaw: 3.8762691020965576 | |||
Saved: ~ | |||
Window Geometry: | |||
Displays: | |||
collapsed: false | |||
Height: 1403 | |||
Hide Left Dock: false | |||
Hide Right Dock: false | |||
QMainWindow State: 000000ff00000000fd00000004000000000000025f000004dffc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003c000004df000000c800fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000363000000a200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000a000000003efc0100000002fb0000000800540069006d0065010000000000000a000000029800fffffffb0000000800540069006d006501000000000000045000000000000000000000079b000004df00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 | |||
Selection: | |||
collapsed: false | |||
Time: | |||
collapsed: false | |||
Tool Properties: | |||
collapsed: false | |||
Views: | |||
collapsed: false | |||
Width: 2560 | |||
X: 2560 | |||
Y: 0 |
@ -0,0 +1,396 @@ | |||
Panels: | |||
- Class: rviz/Displays | |||
Help Height: 78 | |||
Name: Displays | |||
Property Tree Widget: | |||
Expanded: | |||
- /Global Options1 | |||
- /Status1 | |||
Splitter Ratio: 0.5 | |||
Tree Height: 787 | |||
- Class: rviz/Selection | |||
Name: Selection | |||
- Class: rviz/Tool Properties | |||
Expanded: | |||
- /2D Pose Estimate1 | |||
- /2D Nav Goal1 | |||
- /Publish Point1 | |||
Name: Tool Properties | |||
Splitter Ratio: 0.5886790156364441 | |||
- Class: rviz/Views | |||
Expanded: | |||
- /Current View1 | |||
- /Current View1/Focal Point1 | |||
Name: Views | |||
Splitter Ratio: 0.5 | |||
- Class: rviz/Time | |||
Experimental: false | |||
Name: Time | |||
SyncMode: 0 | |||
SyncSource: MapCloud | |||
Preferences: | |||
PromptSaveOnExit: true | |||
Toolbars: | |||
toolButtonStyle: 2 | |||
Visualization Manager: | |||
Class: "" | |||
Displays: | |||
- Alpha: 1 | |||
Class: rviz/RobotModel | |||
Collision Enabled: false | |||
Enabled: true | |||
Links: | |||
All Links Enabled: true | |||
Expand Joint Details: false | |||
Expand Link Details: false | |||
Expand Tree: false | |||
Link Tree Style: Links in Alphabetic Order | |||
base_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
camera_accel_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_accel_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_bottom_screw_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
caster_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
laser: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l0: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l1: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l2: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l3: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l4: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_inner_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_left_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_right_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_shoulder: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_top_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_grasp_center: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
link_gripper: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_pan: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_tilt: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_left_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_lift: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_mast: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_right_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_wrist_yaw: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
respeaker_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
Name: RobotModel | |||
Robot Description: robot_description | |||
TF Prefix: "" | |||
Update Interval: 0 | |||
Value: true | |||
Visual Enabled: true | |||
- Alpha: 1 | |||
Class: rtabmap_ros/MapGraph | |||
Enabled: true | |||
Global loop closure: 255; 0; 0 | |||
Landmark: 0; 128; 0 | |||
Local loop closure: 255; 255; 0 | |||
Merged neighbor: 255; 170; 0 | |||
Name: MapGraph | |||
Neighbor: 0; 0; 255 | |||
Queue Size: 10 | |||
Topic: /rtabmap/mapGraph | |||
Unreliable: false | |||
User: 255; 0; 0 | |||
Value: true | |||
Virtual: 255; 0; 255 | |||
- Alpha: 1 | |||
Autocompute Intensity Bounds: true | |||
Autocompute Value Bounds: | |||
Max Value: 10 | |||
Min Value: -10 | |||
Value: true | |||
Axis: Z | |||
Channel Name: intensity | |||
Class: rtabmap_ros/MapCloud | |||
Cloud decimation: 4 | |||
Cloud from scan: false | |||
Cloud max depth (m): 4 | |||
Cloud min depth (m): 0 | |||
Cloud voxel size (m): 0.009999999776482582 | |||
Color: 255; 255; 255 | |||
Color Transformer: RGB8 | |||
Download graph: false | |||
Download map: false | |||
Enabled: true | |||
Filter ceiling (m): 0 | |||
Filter floor (m): 0 | |||
Invert Rainbow: false | |||
Max Color: 255; 255; 255 | |||
Min Color: 0; 0; 0 | |||
Name: MapCloud | |||
Node filtering angle (degrees): 30 | |||
Node filtering radius (m): 0 | |||
Position Transformer: XYZ | |||
Queue Size: 10 | |||
Size (Pixels): 3 | |||
Size (m): 0.009999999776482582 | |||
Style: Flat Squares | |||
Topic: /rtabmap/mapData | |||
Unreliable: false | |||
Use Fixed Frame: true | |||
Use rainbow: true | |||
Value: true | |||
- Alpha: 0.699999988079071 | |||
Class: rviz/Map | |||
Color Scheme: map | |||
Draw Behind: false | |||
Enabled: true | |||
Name: Map | |||
Topic: /map | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Alpha: 0.699999988079071 | |||
Class: rviz/Map | |||
Color Scheme: costmap | |||
Draw Behind: false | |||
Enabled: true | |||
Name: Map | |||
Topic: /move_base/global_costmap/costmap | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Alpha: 1 | |||
Class: rviz/Polygon | |||
Color: 25; 255; 0 | |||
Enabled: true | |||
Name: Polygon | |||
Queue Size: 10 | |||
Topic: /move_base/global_costmap/footprint | |||
Unreliable: false | |||
Value: true | |||
Enabled: true | |||
Global Options: | |||
Background Color: 48; 48; 48 | |||
Default Light: true | |||
Fixed Frame: map | |||
Frame Rate: 30 | |||
Name: root | |||
Tools: | |||
- Class: rviz/Interact | |||
Hide Inactive Objects: true | |||
- Class: rviz/MoveCamera | |||
- Class: rviz/Select | |||
- Class: rviz/FocusCamera | |||
- Class: rviz/Measure | |||
- Class: rviz/SetInitialPose | |||
Theta std deviation: 0.2617993950843811 | |||
Topic: /initialpose | |||
X std deviation: 0.5 | |||
Y std deviation: 0.5 | |||
- Class: rviz/SetGoal | |||
Topic: /move_base_simple/goal | |||
- Class: rviz/PublishPoint | |||
Single click: true | |||
Topic: /clicked_point | |||
Value: true | |||
Views: | |||
Current: | |||
Class: rtabmap_ros/OrbitOriented | |||
Distance: 17.96693229675293 | |||
Enable Stereo Rendering: | |||
Stereo Eye Separation: 0.05999999865889549 | |||
Stereo Focal Distance: 1 | |||
Swap Stereo Eyes: false | |||
Value: false | |||
Field of View: 0.7853981852531433 | |||
Focal Point: | |||
X: -3.853421926498413 | |||
Y: 0.7817280888557434 | |||
Z: 0.4164792597293854 | |||
Focal Shape Fixed Size: false | |||
Focal Shape Size: 0.05000000074505806 | |||
Invert Z Axis: false | |||
Name: Current View | |||
Near Clip Distance: 0.009999999776482582 | |||
Pitch: 0.7947970628738403 | |||
Target Frame: <Fixed Frame> | |||
Yaw: 4.218579292297363 | |||
Saved: ~ | |||
Window Geometry: | |||
Displays: | |||
collapsed: true | |||
Height: 1016 | |||
Hide Left Dock: true | |||
Hide Right Dock: true | |||
QMainWindow State: 000000ff00000000fd0000000400000000000001560000039efc0200000007fb0000001200530065006c0065006300740069006f006e000000003d0000009b0000005c00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d0000039e000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000039efc0200000003fb0000001e0054006f006f006c002000500072006f0070006500720074006900650073000000003d000000810000005c00fffffffb0000000a0056006900650077007300000000c400000317000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000078000000134fc0100000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730000000000000007800000000000000000fb0000000800540069006d0065000000000000000780000004f300fffffffb0000000800540069006d00650100000000000004500000000000000000000003c00000039e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 | |||
Selection: | |||
collapsed: false | |||
Time: | |||
collapsed: false | |||
Tool Properties: | |||
collapsed: true | |||
Views: | |||
collapsed: true | |||
Width: 960 | |||
X: 0 | |||
Y: 27 |
@ -0,0 +1,374 @@ | |||
Panels: | |||
- Class: rviz/Displays | |||
Help Height: 78 | |||
Name: Displays | |||
Property Tree Widget: | |||
Expanded: | |||
- /Global Options1 | |||
- /Status1 | |||
- /Map1 | |||
- /Path1 | |||
Splitter Ratio: 0.5 | |||
Tree Height: 1082 | |||
- Class: rviz/Selection | |||
Name: Selection | |||
- Class: rviz/Tool Properties | |||
Expanded: | |||
- /2D Pose Estimate1 | |||
- /2D Nav Goal1 | |||
- /Publish Point1 | |||
Name: Tool Properties | |||
Splitter Ratio: 0.5886790156364441 | |||
- Class: rviz/Views | |||
Expanded: | |||
- /Current View1 | |||
Name: Views | |||
Splitter Ratio: 0.5 | |||
- Class: rviz/Time | |||
Experimental: false | |||
Name: Time | |||
SyncMode: 0 | |||
SyncSource: "" | |||
Preferences: | |||
PromptSaveOnExit: true | |||
Toolbars: | |||
toolButtonStyle: 2 | |||
Visualization Manager: | |||
Class: "" | |||
Displays: | |||
- Alpha: 1 | |||
Class: rviz/RobotModel | |||
Collision Enabled: false | |||
Enabled: true | |||
Links: | |||
All Links Enabled: true | |||
Expand Joint Details: false | |||
Expand Link Details: false | |||
Expand Tree: false | |||
Link Tree Style: Links in Alphabetic Order | |||
base_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
camera_accel_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_accel_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_bottom_screw_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_color_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_depth_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_gyro_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra1_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_infra2_optical_frame: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
camera_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
caster_link: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
laser: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l0: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l1: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l2: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l3: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_arm_l4: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_inner_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_left_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_right_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_shoulder: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_aruco_top_wrist: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_grasp_center: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
link_gripper: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_finger_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_left: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_gripper_fingertip_right: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_pan: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_head_tilt: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_left_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_lift: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_mast: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_right_wheel: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
link_wrist_yaw: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
respeaker_base: | |||
Alpha: 1 | |||
Show Axes: false | |||
Show Trail: false | |||
Value: true | |||
Name: RobotModel | |||
Robot Description: robot_description | |||
TF Prefix: "" | |||
Update Interval: 0 | |||
Value: true | |||
Visual Enabled: true | |||
- Alpha: 0.699999988079071 | |||
Class: rviz/Map | |||
Color Scheme: map | |||
Draw Behind: false | |||
Enabled: true | |||
Name: Map | |||
Topic: /rtabmap/grid_prob_map | |||
Unreliable: false | |||
Use Timestamp: false | |||
Value: true | |||
- Alpha: 1 | |||
Buffer Length: 1 | |||
Class: rviz/Path | |||
Color: 25; 255; 0 | |||
Enabled: true | |||
Head Diameter: 0.30000001192092896 | |||
Head Length: 0.20000000298023224 | |||
Length: 0.30000001192092896 | |||
Line Style: Lines | |||
Line Width: 0.029999999329447746 | |||
Name: Path | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Pose Color: 255; 85; 255 | |||
Pose Style: None | |||
Queue Size: 10 | |||
Radius: 0.029999999329447746 | |||
Shaft Diameter: 0.10000000149011612 | |||
Shaft Length: 0.10000000149011612 | |||
Topic: /move_base/DWAPlannerROS/global_plan | |||
Unreliable: false | |||
Value: true | |||
- Alpha: 1 | |||
Buffer Length: 1 | |||
Class: rviz/Path | |||
Color: 25; 255; 0 | |||
Enabled: true | |||
Head Diameter: 0.30000001192092896 | |||
Head Length: 0.20000000298023224 | |||
Length: 0.30000001192092896 | |||
Line Style: Lines | |||
Line Width: 0.029999999329447746 | |||
Name: Path | |||
Offset: | |||
X: 0 | |||
Y: 0 | |||
Z: 0 | |||
Pose Color: 255; 85; 255 | |||
Pose Style: None | |||
Queue Size: 10 | |||
Radius: 0.029999999329447746 | |||
Shaft Diameter: 0.10000000149011612 | |||
Shaft Length: 0.10000000149011612 | |||
Topic: /rtabmap/mapPath | |||
Unreliable: false | |||
Value: true | |||
Enabled: true | |||
Global Options: | |||
Background Color: 48; 48; 48 | |||
Default Light: true | |||
Fixed Frame: map | |||
Frame Rate: 30 | |||
Name: root | |||
Tools: | |||
- Class: rviz/Interact | |||
Hide Inactive Objects: true | |||
- Class: rviz/MoveCamera | |||
- Class: rviz/Select | |||
- Class: rviz/FocusCamera | |||
- Class: rviz/Measure | |||
- Class: rviz/SetInitialPose | |||
Theta std deviation: 0.2617993950843811 | |||
Topic: /initialpose | |||
X std deviation: 0.5 | |||
Y std deviation: 0.5 | |||
- Class: rviz/SetGoal | |||
Topic: /move_base_simple/goal | |||
- Class: rviz/PublishPoint | |||
Single click: true | |||
Topic: /clicked_point | |||
Value: true | |||
Views: | |||
Current: | |||
Class: rviz/Orbit | |||
Distance: 24.471881866455078 | |||
Enable Stereo Rendering: | |||
Stereo Eye Separation: 0.05999999865889549 | |||
Stereo Focal Distance: 1 | |||
Swap Stereo Eyes: false | |||
Value: false | |||
Field of View: 0.7853981852531433 | |||
Focal Point: | |||
X: -2.2477076053619385 | |||
Y: -1.80465567111969 | |||
Z: -6.365629196166992 | |||
Focal Shape Fixed Size: true | |||
Focal Shape Size: 0.05000000074505806 | |||
Invert Z Axis: false | |||
Name: Current View | |||
Near Clip Distance: 0.009999999776482582 | |||
Pitch: 1.5697963237762451 | |||
Target Frame: <Fixed Frame> | |||
Yaw: 1.2835423946380615 | |||
Saved: ~ | |||
Window Geometry: | |||
Displays: | |||
collapsed: false | |||
Height: 1376 | |||
Hide Left Dock: false | |||
Hide Right Dock: false | |||
QMainWindow State: 000000ff00000000fd000000040000000000000156000004c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003c000004c4000000c800fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000004c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003c000004c4000000a200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000a000000003efc0100000002fb0000000800540069006d0065010000000000000a000000029800fffffffb0000000800540069006d006501000000000000045000000000000000000000078f000004c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 | |||
Selection: | |||
collapsed: false | |||
Time: | |||
collapsed: false | |||
Tool Properties: | |||
collapsed: false | |||
Views: | |||
collapsed: false | |||
Width: 2560 | |||
X: 0 | |||
Y: 27 |
@ -0,0 +1,67 @@ | |||
#!/usr/bin/env python | |||
# license removed for brevity | |||
import rospy | |||
# Brings in the SimpleActionClient | |||
import actionlib | |||
# Brings in the .action file and messages used by the move base action | |||
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal | |||
# Gazebo messages | |||
from gazebo_msgs.msg import ModelStates | |||
# wrap all stuff below in a class later. global variables for now.sorry | |||
goal_dict = {"x" : 0.0, "y": 0.0 , "orientation" : 0.0} | |||
# A lot can be done here. Later | |||
def generate_goal_pose(data): | |||
person_of_interest_idx = data.name.index('unit_box') | |||
# return a goal that is 5,5 in front of the object | |||
goal_dict["x"] = data.pose[person_of_interest_idx].position.x - 8.0 | |||
goal_dict["y"] = data.pose[person_of_interest_idx].position.y - 8.0 | |||
return goal_dict | |||
def movebase_client(): | |||
# Create an action client called "move_base" with action definition file "MoveBaseAction" | |||
client = actionlib.SimpleActionClient('move_base',MoveBaseAction) | |||
# Waits until the action server has started up and started listening for goals. | |||
client.wait_for_server() | |||
# Creates a new goal with the MoveBaseGoal constructor | |||
goal = MoveBaseGoal() | |||
goal.target_pose.header.frame_id = "map" | |||
goal.target_pose.header.stamp = rospy.Time.now() | |||
# Generate a goal pose that gets us within 5m x and 5m y of the unit_block | |||
# goal.target_pose.pose.position.x = 0.5 | |||
goal.target_pose.pose.position.x = goal_dict["x"] | |||
goal.target_pose.pose.position.x = goal_dict["y"] | |||
# No rotation of the mobile base frame w.r.t. map frame | |||
goal.target_pose.pose.orientation.w = 1.0 | |||
# Sends the goal to the action server. | |||
client.send_goal(goal) | |||
# Waits for the server to finish performing the action. | |||
wait = client.wait_for_result() | |||
# If the result doesn't arrive, assume the Server is not available | |||
if not wait: | |||
rospy.logerr("Action server not available!") | |||
rospy.signal_shutdown("Action server not available!") | |||
else: | |||
# Result of executing the action | |||
return client.get_result() | |||
# If the python node is executed as main process (sourced directly) | |||
if __name__ == '__main__': | |||
try: | |||
# Initializes a rospy node to let the SimpleActionClient publish and subscribe | |||
rospy.init_node('movebase_client_py') | |||
rospy.Subscriber("gazebo/model_states",ModelStates,generate_goal_pose) | |||
result = movebase_client() | |||
if result: | |||
rospy.loginfo("Goal execution done!") | |||
except rospy.ROSInterruptException: | |||
rospy.loginfo("Navigation test finished.") |