-
-
Save eithwa/a803f943a53faa3c5e1deab948161f48 to your computer and use it in GitHub Desktop.
cartographer issu #1715
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0"?> | |
<launch> | |
<param name="/use_sim_time" value="true" /> <!-- for rosbag --> | |
<!-- <arg name = "model_xacro" default = "$(find cartographer_ros)/urdf/scout_v2.xacro" /> | |
<param name="robot_description" command="$(find xacro)/xacro $(arg model_xacro)"/> | |
<node name="robot_state_publisher" | |
pkg="robot_state_publisher" | |
type="robot_state_publisher" /> --> | |
<param name="robot_description" | |
textfile="$(find cartographer_ros)/urdf/scout_v2.urdf" /> | |
<node name="robot_state_publisher" pkg="robot_state_publisher" | |
type="robot_state_publisher" /> | |
<node name="cartographer_node" pkg="cartographer_ros" | |
type="cartographer_node" args=" | |
-configuration_directory $(find cartographer_ros)/configuration_files | |
-configuration_basename robot.lua" | |
output="screen"> | |
<remap from="points2_1" to="/livox/lidar_3GGDJ9400100731" /> | |
<remap from="points2_2" to="/livox/lidar_3GGDJ8T00100411" /> | |
<remap from="odom" to="/odom" /> | |
<remap from="imu" to="/IMU_data"/> | |
</node> | |
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros" | |
type="cartographer_occupancy_grid_node" args="-resolution 0.05" /> | |
<node name="rviz" pkg="rviz" type="rviz" required="true" | |
args="-d $(find cartographer_ros)/configuration_files/demo_3d.rviz" /> | |
<!-- | |
<node name="playbag" pkg="rosbag" type="play" | |
args="clock /home/user/slam_ws/data/floor1-0416-pc2.bag" /> --> | |
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
include "map_builder.lua" | |
include "trajectory_builder.lua" | |
options = { | |
map_builder = MAP_BUILDER, | |
trajectory_builder = TRAJECTORY_BUILDER, | |
map_frame = "map", | |
tracking_frame = "base_link", | |
published_frame = "base_link", | |
odom_frame = "odom", | |
provide_odom_frame = false, | |
publish_frame_projected_to_2d = false, | |
use_pose_extrapolator = true, | |
use_odometry = true, | |
use_nav_sat = false, | |
use_landmarks = false, | |
num_laser_scans = 0, | |
num_multi_echo_laser_scans = 0, | |
num_subdivisions_per_laser_scan = 1, | |
num_point_clouds = 2, | |
lookup_transform_timeout_sec = 0.2, | |
submap_publish_period_sec = 0.3, | |
pose_publish_period_sec = 5e-3, | |
trajectory_publish_period_sec = 30e-3, | |
rangefinder_sampling_ratio = 1., | |
odometry_sampling_ratio = 1., | |
fixed_frame_pose_sampling_ratio = 1., | |
imu_sampling_ratio = 1., | |
landmarks_sampling_ratio = 1., | |
} | |
--TRAJECTORY_BUILDER_3D.num_accumulated_range_data = 160 | |
TRAJECTORY_BUILDER_3D.num_accumulated_range_data = 5 | |
MAP_BUILDER.use_trajectory_builder_3d = true | |
MAP_BUILDER.num_background_threads = 7 | |
POSE_GRAPH.optimization_problem.huber_scale = 5e2 | |
POSE_GRAPH.optimize_every_n_nodes = 320 | |
POSE_GRAPH.constraint_builder.sampling_ratio = 0.03 | |
POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10 | |
POSE_GRAPH.constraint_builder.min_score = 0.62 | |
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.66 | |
return options |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0"?> | |
<robot name="scout_v2" > | |
<!-- Base link --> | |
<link name="base_link"> | |
<visual> | |
<origin xyz="0 0 0" rpy="0 0 0" /> | |
<geometry> | |
<box size="0.06 0.04 0.02" /> | |
</geometry> | |
</visual> | |
<collision> | |
<origin xyz="0 0 0.008" rpy="0 0 0" /> | |
<geometry> | |
<box size="0.9250000 0.380000 0.210000"/> | |
</geometry> | |
</collision> | |
<collision> | |
<origin xyz="0 0 0.035" rpy="0 0 0" /> | |
<geometry> | |
<box size="0.154 0.627 0.07"/> | |
</geometry> | |
</collision> | |
</link> | |
<link name="motion_center" /> | |
<joint name="base_motion_joint" type="fixed"> | |
<parent link="base_link"/> | |
<child link="motion_center"/> | |
<origin rpy="0 0 0" xyz="0.0 0 0"/> | |
</joint> | |
<link name="base_footprint"/> | |
<joint name="base_footprint_joint" type="fixed"> | |
<origin xyz="0 0 -0.1647" rpy="0 0 0" /> | |
<parent link="base_link" /> | |
<child link="base_footprint" /> | |
</joint> | |
<link name="inertial_link"> | |
<inertial> | |
<mass value="40" /> | |
<origin xyz="0.0 0.0 0.0" /> | |
<inertia ixx="2.288641" ixy="0" ixz="0" iyy="5.103976" iyz="0" izz="3.431465" /> | |
</inertial> | |
</link> | |
<joint name="inertial_joint" type="fixed"> | |
<origin xyz="0 0 0" rpy="0 0 0" /> | |
<parent link="base_link" /> | |
<child link="inertial_link" /> | |
</joint> | |
<link name="livox_frame"> | |
<inertial> | |
<mass value="3"/> | |
<origin xyz="0 0 0"/> | |
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<box size="0.06 0.04 0.02" /> | |
</geometry> | |
<material name=""> | |
<color rgba="1 1 1 1" /> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<box size="0.1 0.1 0.1"/> | |
</geometry> | |
</collision> | |
</link> | |
<joint name="base_link_livox_joint" type="fixed"> | |
<parent link="base_link"/> | |
<child link="livox_frame"/> | |
<origin rpy="0 0 0" xyz="0.1 0.0 0.52"/> | |
<axis rpy="0 0 0" xyz="0 0 0"/> | |
</joint> | |
<link name="imu_link"/> | |
<joint name="base_link_imu_joint" type="fixed"> | |
<parent link="base_link"/> | |
<child link="imu_link"/> | |
<origin rpy="0 0 0" xyz="0.0 0.0 0.52"/> | |
<axis rpy="0 0 0" xyz="0 0 0"/> | |
</joint> | |
</robot> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment