diff --git a/launch/imu2d_demo.launch b/launch/imu2d_demo.launch index ea29fa3954cbd96710f7ada8d324579bf73c4bc0..b141aaf5ebb2969e4fc881351aa063379f89306f 100644 --- a/launch/imu2d_demo.launch +++ b/launch/imu2d_demo.launch @@ -1,6 +1,5 @@ <!-- --> <launch> - <param name="use_sim_time" value="true" /> <arg name="record" default="true" /> <arg name="rviz" default="true" /> <arg name="speed" default="1" /> @@ -13,47 +12,71 @@ <arg name="launch_pref" default="" unless="$(eval profiling or gdb)"/> <arg name="launch_pref" value="valgrind --tool=callgrind --callgrind-out-file='callgrind.wolf.%p'" if="$(arg profiling)" /> <arg name="launch_pref" value="gdb -ex run --args" if="$(arg gdb)" /> - <!-- using "clock" option to use the simulated time. Rosbag launch as the first node --> + <arg name="robot" default="ana" /> <!-- ana or helena --> - <node pkg="rostopic" type="rostopic" name="" args='pub /helena/sensors/bno055_imu/imu/topic_enable std_msgs/Bool "data: True"'/> - + <node pkg="rostopic" type="rostopic" name="" args='pub /imu_bno/enable std_msgs/Bool "data: True"'/> + <node pkg="rostopic" type="rostopic" name="" args='pub /imu_micro/enable std_msgs/Bool "data: True"'/> + + <!-- RECORD --> <group if="$(arg record)"> - <node pkg="rosbag" type="record" name="recorder" args='record -O $(find wolf_demo_imu2d)/bag/recordings/trajectory_recording$(arg suffix).bag "/wolf_ros_node/trajectory" "/wolf_ros_node/pose_pose_with_cov"'/> + <node pkg="rosbag" + type="record" + name="recorder" + args='record -O $(find wolf_demo_imu2d)/bag/recordings/trajectory_recording$(arg suffix).bag "/wolf_ros_node/trajectory" "/wolf_ros_node/pose_pose_with_cov"'/> </group> - <node pkg="tf" - type="static_transform_publisher" - name="static_tf" - args="0 0 0 0 0 0 /ana/base_footprint /ana/base_link 100"/> + <!-- TF --> + <group> + <!-- <node pkg="tf" + type="static_transform_publisher" + name="static_tf" + args="0 0 0 0 0 0 /base_footprint /base_link 100"/> - <node pkg="tf" - type="static_transform_publisher" - name="static_tf2" - args="0 0 0 0 0 0 /ana/base_link /ana/imu_bno055 100"/> + <node pkg="tf" + type="static_transform_publisher" + name="static_tf2" + args="0 0 0 0 0 0 /base_link /imu_bno055 100"/> - <node pkg="tf" - type="static_transform_publisher" - name="static_tf3" - args="0 0 0 3.14159265 0 0 /ana/base_link /ana/velodyne 100"/> + <node pkg="tf" + type="static_transform_publisher" + name="static_tf3" + args="0 0 0 3.14159265 0 0 /base_link /velodyne 100"/> --> - <node pkg="tf" - type="static_transform_publisher" - name="static_tf4" - args="-0.11 0.01 0 0 0 0 /ana/base_link /ana/imu_microstrain 100"/> + <node pkg="tf" + type="static_transform_publisher" + name="static_tf4" + args="-0.11 0.01 0 0 0 0 /$(arg robot)/base_link /imu 100"/> + <node pkg="tf" + type="static_transform_publisher" + name="static_tf5" + args="-0.11 0.01 0 0 0 0 /$(arg robot)/base_link /$(arg robot)/imu_microstrain 100"/> + </group> + + <!-- using "clock" option to use the simulated time. Rosbag launch as the first node --> + <param name="use_sim_time" value="true" /> <node pkg="rosbag" type="play" name="player" required="true" - args="-s $(arg sec) -r $(arg speed) --clock $(find wolf_demo_imu2d)/bag/$(arg bag).bag"/> + args="-s $(arg sec) -r $(arg speed) --clock $(find wolf_demo_imu2d)/bag/$(arg bag).bag"> + <remap from="/$(arg robot)/sensors/imu/data" to="/imu_micro"/> + <remap from="/$(arg robot)/imu/data" to="/imu_micro"/> + <remap from="/$(arg robot)/sensors/bno055/imu" to="/imu_bno"/> + <remap from="/$(arg robot)/sensors/scan" to="/scan"/> + <remap from="/$(arg robot)/odom" to="/odom"/> + <remap from="/$(arg robot)/sensors/ublox_gps/raw_data_stream" to="/ublox_gps/raw_data_stream"/> + </node> + <!-- RVIZ --> <group if="$(arg rviz)"> <node type="rviz" name="rviz" pkg="rviz" - args="-d $(find wolf_demo_imu2d)/rviz/imu2d_demo.rviz"/> + args="-d $(find wolf_demo_imu2d)/rviz/imu2d_demo_$(arg robot).rviz"/> </group> + <!-- WOLF --> <node type="wolf_ros_node" name="wolf_ros_node" pkg="wolf_ros_node" diff --git a/rviz/imu2d_demo.rviz b/rviz/imu2d_demo.rviz index e1e2090e252d77b29f98ace7835b70e318240b28..2d76267e8a82ef31d6209a576809265f3093dc84 100644 --- a/rviz/imu2d_demo.rviz +++ b/rviz/imu2d_demo.rviz @@ -5,7 +5,6 @@ Panels: Property Tree Widget: Expanded: - /Global Options1 - - /TF1 - /TF1/Frames1 - /TF1/Tree1 - /Odometry1/Shape1 @@ -17,9 +16,8 @@ Panels: - /Trajectory1/Namespaces1 - /Axes1 - /PointCloud21 - - /Imu1 - Splitter Ratio: 0.5285326242446899 - Tree Height: 728 + Splitter Ratio: 0.708737850189209 + Tree Height: 839 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -38,7 +36,7 @@ Panels: Experimental: false Name: Time SyncMode: 0 - SyncSource: PointCloud2 + SyncSource: LaserScan Preferences: PromptSaveOnExit: true Toolbars: @@ -69,22 +67,79 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: false - ana/base_footprint: + helena/base_footprint: Value: false - ana/base_footprint_robot: - Value: false - ana/base_link: + helena/base_link: Value: true - ana/imu_bno055: + helena/camera_bottom_screw_frame: + Value: false + helena/camera_color_frame: + Value: false + helena/camera_color_optical_frame: + Value: false + helena/camera_depth_frame: + Value: false + helena/camera_depth_optical_frame: + Value: false + helena/camera_infra1_frame: + Value: false + helena/camera_infra1_optical_frame: + Value: false + helena/camera_infra2_frame: + Value: false + helena/camera_infra2_optical_frame: + Value: false + helena/camera_link: + Value: false + helena/front_left_axle: Value: false - ana/imu_microstrain: + helena/front_left_hub: Value: false - ana/odom: + helena/front_left_wheel: + Value: false + helena/front_right_axle: + Value: false + helena/front_right_hub: + Value: false + helena/front_right_wheel: + Value: false + helena/front_sonar: + Value: false + helena/helena_box: + Value: false + helena/helena_realsense_support: + Value: false + helena/imu_bno055: + Value: false + helena/imu_bno055_base: + Value: false + helena/odom: Value: true - ana/velodyne: + helena/rear_left_axle: Value: false - map: + helena/rear_left_hub: + Value: false + helena/rear_left_wheel: Value: false + helena/rear_right_axle: + Value: false + helena/rear_right_hub: + Value: false + helena/rear_right_wheel: + Value: false + helena/rear_sonar: + Value: false + helena/robosense: + Value: false + helena/robosense_base: + Value: false + helena/top_plate: + Value: false + imu: + Value: true + map: + Value: true + Marker Alpha: 1 Marker Scale: 5 Name: TF Show Arrows: false @@ -92,17 +147,55 @@ Visualization Manager: Show Names: true Tree: map: - ana/odom: - ana/base_footprint: - ana/base_link: - ana/imu_bno055: + helena/odom: + helena/base_footprint: + helena/base_link: + helena/front_left_axle: + helena/front_left_hub: + helena/front_left_wheel: + {} + helena/front_right_axle: + helena/front_right_hub: + helena/front_right_wheel: + {} + helena/front_sonar: + {} + helena/rear_left_axle: + helena/rear_left_hub: + helena/rear_left_wheel: + {} + helena/rear_right_axle: + helena/rear_right_hub: + helena/rear_right_wheel: + {} + helena/rear_sonar: {} - ana/imu_microstrain: + helena/top_plate: + helena/helena_box: + {} + helena/helena_realsense_support: + helena/camera_bottom_screw_frame: + helena/camera_link: + helena/camera_color_frame: + helena/camera_color_optical_frame: + {} + helena/camera_depth_frame: + helena/camera_depth_optical_frame: + {} + helena/camera_infra1_frame: + helena/camera_infra1_optical_frame: + {} + helena/camera_infra2_frame: + helena/camera_infra2_optical_frame: + {} + helena/robosense_base: + helena/robosense: + {} + imu: {} - ana/velodyne: + helena/imu_bno055_base: + helena/imu_bno055: {} - ana/base_footprint_robot: - {} Update Interval: 0 Value: true - Angle Tolerance: 0.10000000149011612 @@ -126,6 +219,7 @@ Visualization Manager: Keep: 300 Name: Odometry Position Tolerance: 0.10000000149011612 + Queue Size: 10 Shape: Alpha: 1 Axes Length: 1 @@ -151,7 +245,7 @@ Visualization Manager: Color: 250; 84; 255 Color Transformer: FlatColor Decay Time: 10 - Enabled: false + Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Min Color: 0; 0; 0 @@ -162,11 +256,11 @@ Visualization Manager: Size (Pixels): 3 Size (m): 0.05999999865889549 Style: Flat Squares - Topic: /ana/sensors/scan + Topic: /scan Unreliable: false Use Fixed Frame: true Use rainbow: true - Value: false + Value: true - Class: rviz/MarkerArray Enabled: false Marker Topic: /wolf_ros_node/graph_landmarks @@ -180,35 +274,26 @@ Visualization Manager: Marker Topic: /wolf_ros_node/graph_factors Name: Factors Namespaces: - factors_processorimu2dbno: true - factors_processorimu2dmicro: true - factors_processorloopclosureicp: true - factors_processorodom2d: true factors_processorodomicp: true - factors_text_processorimu2dbno: false - factors_text_processorimu2dmicro: false - factors_text_processorloopclosureicp: false - factors_text_processorodom2d: false factors_text_processorodomicp: false - factors_text_unnamed_processor: false - factors_unnamed_processor: true Queue Size: 100 Value: true - Class: rviz/MarkerArray - Enabled: true + Enabled: false Marker Topic: /wolf_ros_node/graph_trajectory Name: Trajectory Namespaces: - frames: false - frames_text: false + {} Queue Size: 100 - Value: true - - Class: rviz/Axes + Value: false + - Alpha: 1 + Class: rviz/Axes Enabled: true Length: 1 Name: Axes Radius: 0.10000000149011612 - Reference Frame: ana/base_link + Reference Frame: helena/base_link + Show Trail: false Value: true - Alpha: 1 Autocompute Intensity Bounds: true @@ -254,7 +339,8 @@ Visualization Manager: Enabled: true History Length: 1 Name: Imu - Topic: /ana/imu/data_remapped + Queue Size: 10 + Topic: /imu_micro Unreliable: false Value: true Enabled: true @@ -285,12 +371,13 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 27.63036346435547 + Distance: 29.216249465942383 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.3574845790863037 Y: -1.3090972900390625 @@ -300,10 +387,9 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.7247968912124634 + Pitch: 0.5097973346710205 Target Frame: map - Value: Orbit (rviz) - Yaw: 5.4131693840026855 + Yaw: 4.688166618347168 Saved: - Angle: 0 Class: rviz/TopDownOrtho @@ -317,7 +403,6 @@ Visualization Manager: Near Clip Distance: 0.009999999776482582 Scale: 64.65961456298828 Target Frame: map - Value: TopDownOrtho (rviz) X: 8.825014114379883 Y: -0.17566636204719543 - Angle: 0 @@ -332,7 +417,6 @@ Visualization Manager: Near Clip Distance: 0.009999999776482582 Scale: 50.07240295410156 Target Frame: map - Value: TopDownOrtho (rviz) X: 1.947830080986023 Y: 3.9687037467956543 - Angle: -1.5700000524520874 @@ -347,16 +431,15 @@ Visualization Manager: Near Clip Distance: 0.009999999776482582 Scale: 42.187442779541016 Target Frame: map - Value: TopDownOrtho (rviz) X: 1.9746785163879395 Y: 4.48727560043335 Window Geometry: Displays: collapsed: false - Height: 1025 + Height: 1136 Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd0000000400000000000002e200000363fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000363000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004550000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd000000040000000000000205000003d2fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003d2000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007420000003efc0100000002fb0000000800540069006d0065010000000000000742000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000537000003d200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -365,6 +448,6 @@ Window Geometry: collapsed: false Views: collapsed: true - Width: 1853 - X: 67 + Width: 1858 + X: 62 Y: 27 diff --git a/rviz/imu2d_demo_ana.rviz b/rviz/imu2d_demo_ana.rviz new file mode 100644 index 0000000000000000000000000000000000000000..37c624ac520ee25ef9a4f67c5a4446df25c2ceed --- /dev/null +++ b/rviz/imu2d_demo_ana.rviz @@ -0,0 +1,508 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /TF1/Status1 + - /TF1/Frames1 + - /TF1/Tree1 + - /Odometry1/Shape1 + - /Landmarks1 + - /Factors1 + - /Factors1/Namespaces1 + - /Trajectory1 + - /Trajectory1/Namespaces1 + - /Axes1 + - /PointCloud21 + Splitter Ratio: 0.708737850189209 + 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: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 5 + 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: 100 + Reference Frame: <Fixed Frame> + Value: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: false + ana/ana_box: + Value: false + ana/ana_realsense_support: + Value: false + ana/base_footprint: + Value: false + ana/base_footprint_robot: + Value: false + ana/base_link: + Value: true + ana/camera_aligned_depth_to_color_frame: + Value: false + ana/camera_aligned_depth_to_infra1_frame: + Value: false + ana/camera_bottom_screw_frame: + Value: false + ana/camera_color_frame: + Value: false + ana/camera_color_optical_frame: + Value: false + ana/camera_depth_frame: + Value: false + ana/camera_depth_optical_frame: + Value: false + ana/camera_infra1_frame: + Value: false + ana/camera_infra1_optical_frame: + Value: false + ana/camera_infra2_frame: + Value: false + ana/camera_infra2_optical_frame: + Value: false + ana/camera_link: + Value: false + ana/camera_pan_tilt_bottom_screw_frame: + Value: false + ana/camera_pan_tilt_color_frame: + Value: false + ana/camera_pan_tilt_color_optical_frame: + Value: false + ana/camera_pan_tilt_depth_frame: + Value: false + ana/camera_pan_tilt_depth_optical_frame: + Value: false + ana/camera_pan_tilt_infra1_frame: + Value: false + ana/camera_pan_tilt_infra1_optical_frame: + Value: false + ana/camera_pan_tilt_infra2_frame: + Value: false + ana/camera_pan_tilt_infra2_optical_frame: + Value: false + ana/camera_pan_tilt_link: + Value: false + ana/front_left_axle: + Value: false + ana/front_left_hub: + Value: false + ana/front_left_wheel: + Value: false + ana/front_right_axle: + Value: false + ana/front_right_hub: + Value: false + ana/front_right_wheel: + Value: false + ana/front_sonar: + Value: false + ana/imu_bno055: + Value: false + ana/imu_bno055_base: + Value: false + ana/imu_microstrain: + Value: false + ana/odom: + Value: true + ana/pan_frame: + Value: false + ana/realsense_support_pan_tilt: + Value: false + ana/rear_left_axle: + Value: false + ana/rear_left_hub: + Value: false + ana/rear_left_wheel: + Value: false + ana/rear_right_axle: + Value: false + ana/rear_right_hub: + Value: false + ana/rear_right_wheel: + Value: false + ana/rear_sonar: + Value: false + ana/top_plate: + Value: false + ana/velodyne: + Value: false + ana/velodyne_base: + Value: false + camera_accel_frame: + Value: false + camera_accel_optical_frame: + Value: false + camera_gyro_frame: + Value: false + camera_gyro_optical_frame: + Value: false + imu: + Value: false + map: + Value: true + Marker Alpha: 1 + Marker Scale: 5 + Name: TF + Show Arrows: false + Show Axes: true + Show Names: true + Tree: + map: + ana/odom: + ana/base_footprint: + ana/base_link: + ana/front_left_axle: + ana/front_left_hub: + ana/front_left_wheel: + {} + ana/front_right_axle: + ana/front_right_hub: + ana/front_right_wheel: + {} + ana/front_sonar: + {} + ana/imu_microstrain: + {} + ana/rear_left_axle: + ana/rear_left_hub: + ana/rear_left_wheel: + {} + ana/rear_right_axle: + ana/rear_right_hub: + ana/rear_right_wheel: + {} + ana/rear_sonar: + {} + ana/top_plate: + ana/ana_box: + ana/pan_frame: + {} + ana/ana_realsense_support: + ana/camera_bottom_screw_frame: + ana/camera_link: + ana/camera_aligned_depth_to_color_frame: + {} + ana/camera_aligned_depth_to_infra1_frame: + {} + ana/camera_color_frame: + ana/camera_color_optical_frame: + {} + ana/camera_depth_frame: + ana/camera_depth_optical_frame: + {} + ana/camera_infra1_frame: + ana/camera_infra1_optical_frame: + {} + ana/camera_infra2_frame: + ana/camera_infra2_optical_frame: + {} + camera_accel_frame: + camera_accel_optical_frame: + {} + camera_gyro_frame: + camera_gyro_optical_frame: + {} + ana/velodyne_base: + ana/velodyne: + {} + imu: + {} + ana/imu_bno055_base: + ana/imu_bno055: + {} + ana/base_footprint_robot: + {} + Update Interval: 0 + 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: false + Enabled: false + Keep: 300 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Queue Size: 10 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.10000000149011612 + Head Radius: 0.10000000149011612 + Shaft Length: 0.30000001192092896 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: /ana/odom + Unreliable: false + Value: false + - Alpha: 0.5 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensities + Class: rviz/LaserScan + Color: 250; 84; 255 + Color Transformer: FlatColor + Decay Time: 10 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 1 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05999999865889549 + Style: Flat Squares + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /wolf_ros_node/graph_landmarks + Name: Landmarks + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /wolf_ros_node/graph_factors + Name: Factors + Namespaces: + factors_processorodomicp: true + factors_text_processorodomicp: false + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /wolf_ros_node/graph_trajectory + Name: Trajectory + Namespaces: + {} + Queue Size: 100 + Value: false + - Alpha: 1 + Class: rviz/Axes + Enabled: true + Length: 1 + Name: Axes + Radius: 0.10000000149011612 + Reference Frame: ana/base_link + Show Trail: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 0 + Min Value: 0 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 0; 170; 0 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 173; 14 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 1 + Selectable: false + Size (Pixels): 3 + Size (m): 0.03999999910593033 + Style: Squares + Topic: /wolf_ros_node/map_pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: false + Name: Map + Topic: /wolf_ros_node/map_occgrid + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 0.5 + Class: rviz_plugin_tutorials/Imu + Color: 204; 51; 204 + Enabled: true + History Length: 1 + Name: Imu + Queue Size: 10 + Topic: /imu_micro + 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: 29.216249465942383 + 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.3574845790863037 + Y: -1.3090972900390625 + Z: -0.7893345952033997 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5097973346710205 + Target Frame: map + Yaw: 4.688166618347168 + Saved: + - Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 64.65961456298828 + Target Frame: map + X: 8.825014114379883 + Y: -0.17566636204719543 + - Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 50.07240295410156 + Target Frame: map + X: 1.947830080986023 + Y: 3.9687037467956543 + - Angle: -1.5700000524520874 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 42.187442779541016 + Target Frame: map + X: 1.9746785163879395 + Y: 4.48727560043335 +Window Geometry: + Displays: + collapsed: false + Height: 1136 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd000000040000000000000205000003d2fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003d2000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007420000003efc0100000002fb0000000800540069006d0065010000000000000742000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000537000003d200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1858 + X: 62 + Y: 27 diff --git a/rviz/imu2d_demo_helena.rviz b/rviz/imu2d_demo_helena.rviz new file mode 100644 index 0000000000000000000000000000000000000000..ef9c97ea73dd577308282ae46b46dad83c8c05cd --- /dev/null +++ b/rviz/imu2d_demo_helena.rviz @@ -0,0 +1,462 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /TF1/Frames1 + - /TF1/Tree1 + - /Odometry1/Shape1 + - /LaserScan1 + - /Landmarks1 + - /Factors1 + - /Factors1/Namespaces1 + - /Trajectory1 + - /Trajectory1/Namespaces1 + - /Axes1 + - /PointCloud21 + - /Imu1 + Splitter Ratio: 0.708737850189209 + 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: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 5 + 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: 100 + Reference Frame: <Fixed Frame> + Value: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: false + helena/base_footprint: + Value: false + helena/base_link: + Value: true + helena/camera_bottom_screw_frame: + Value: false + helena/camera_color_frame: + Value: false + helena/camera_color_optical_frame: + Value: false + helena/camera_depth_frame: + Value: false + helena/camera_depth_optical_frame: + Value: false + helena/camera_infra1_frame: + Value: false + helena/camera_infra1_optical_frame: + Value: false + helena/camera_infra2_frame: + Value: false + helena/camera_infra2_optical_frame: + Value: false + helena/camera_link: + Value: false + helena/front_left_axle: + Value: false + helena/front_left_hub: + Value: false + helena/front_left_wheel: + Value: false + helena/front_right_axle: + Value: false + helena/front_right_hub: + Value: false + helena/front_right_wheel: + Value: false + helena/front_sonar: + Value: false + helena/helena_box: + Value: false + helena/helena_realsense_support: + Value: false + helena/imu_bno055: + Value: false + helena/imu_bno055_base: + Value: false + helena/imu_microstrain: + Value: true + helena/odom: + Value: true + helena/rear_left_axle: + Value: false + helena/rear_left_hub: + Value: false + helena/rear_left_wheel: + Value: false + helena/rear_right_axle: + Value: false + helena/rear_right_hub: + Value: false + helena/rear_right_wheel: + Value: false + helena/rear_sonar: + Value: false + helena/robosense: + Value: false + helena/robosense_base: + Value: false + helena/top_plate: + Value: false + imu: + Value: true + map: + Value: true + Marker Alpha: 1 + Marker Scale: 5 + Name: TF + Show Arrows: false + Show Axes: true + Show Names: true + Tree: + map: + helena/odom: + helena/base_footprint: + helena/base_link: + helena/front_left_axle: + helena/front_left_hub: + helena/front_left_wheel: + {} + helena/front_right_axle: + helena/front_right_hub: + helena/front_right_wheel: + {} + helena/front_sonar: + {} + helena/imu_microstrain: + {} + helena/rear_left_axle: + helena/rear_left_hub: + helena/rear_left_wheel: + {} + helena/rear_right_axle: + helena/rear_right_hub: + helena/rear_right_wheel: + {} + helena/rear_sonar: + {} + helena/top_plate: + helena/helena_box: + {} + helena/helena_realsense_support: + helena/camera_bottom_screw_frame: + helena/camera_link: + helena/camera_color_frame: + helena/camera_color_optical_frame: + {} + helena/camera_depth_frame: + helena/camera_depth_optical_frame: + {} + helena/camera_infra1_frame: + helena/camera_infra1_optical_frame: + {} + helena/camera_infra2_frame: + helena/camera_infra2_optical_frame: + {} + helena/robosense_base: + helena/robosense: + {} + imu: + {} + helena/imu_bno055_base: + helena/imu_bno055: + {} + Update Interval: 0 + 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: false + Enabled: false + Keep: 300 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Queue Size: 10 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.10000000149011612 + Head Radius: 0.10000000149011612 + Shaft Length: 0.30000001192092896 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: /ana/odom + Unreliable: false + Value: false + - Alpha: 0.5 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensities + Class: rviz/LaserScan + Color: 250; 84; 255 + Color Transformer: FlatColor + Decay Time: 10 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 1 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05999999865889549 + Style: Flat Squares + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /wolf_ros_node/graph_landmarks + Name: Landmarks + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /wolf_ros_node/graph_factors + Name: Factors + Namespaces: + factors_processorimumicro: true + factors_processorodomicp: true + factors_text_processorimumicro: false + factors_text_processorodomicp: false + factors_text_unnamed_processor: false + factors_unnamed_processor: true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /wolf_ros_node/graph_trajectory + Name: Trajectory + Namespaces: + {} + Queue Size: 100 + Value: false + - Alpha: 1 + Class: rviz/Axes + Enabled: true + Length: 1 + Name: Axes + Radius: 0.10000000149011612 + Reference Frame: helena/base_link + Show Trail: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 0 + Min Value: 0 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 0; 170; 0 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 173; 14 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 1 + Selectable: false + Size (Pixels): 3 + Size (m): 0.03999999910593033 + Style: Squares + Topic: /wolf_ros_node/map_pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: false + Name: Map + Topic: /wolf_ros_node/map_occgrid + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 0.5 + Class: rviz_plugin_tutorials/Imu + Color: 204; 51; 204 + Enabled: true + History Length: 1 + Name: Imu + Queue Size: 10 + Topic: /imu_micro_remapped + 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: 32.773921966552734 + 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.3574845790863037 + Y: -1.3090972900390625 + Z: -0.7893345952033997 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7547971606254578 + Target Frame: map + Yaw: 0.05999409034848213 + Saved: + - Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 64.65961456298828 + Target Frame: map + X: 8.825014114379883 + Y: -0.17566636204719543 + - Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 50.07240295410156 + Target Frame: map + X: 1.947830080986023 + Y: 3.9687037467956543 + - Angle: -1.5700000524520874 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 42.187442779541016 + Target Frame: map + X: 1.9746785163879395 + Y: 4.48727560043335 +Window Geometry: + Displays: + collapsed: false + Height: 1136 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd000000040000000000000205000003d2fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003d2000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007420000003efc0100000002fb0000000800540069006d0065010000000000000742000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000537000003d200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1858 + X: 62 + Y: 27 diff --git a/yaml/imu2d_test0.yaml b/yaml/imu2d_test0.yaml index e8798ed2f78a98b782832be15ddfb0bf21404a0b..6034e3aa8725fae63bf6117ea02a292cc0412d2b 100644 --- a/yaml/imu2d_test0.yaml +++ b/yaml/imu2d_test0.yaml @@ -67,7 +67,7 @@ config: - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/ana/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true diff --git a/yaml/imu2d_test1.yaml b/yaml/imu2d_test1.yaml index 5ae135605b12c4b40f448ce85b8fb59f6a4e70e0..5258f9a027ea898fb4281e660dcdd546ceb2913b 100644 --- a/yaml/imu2d_test1.yaml +++ b/yaml/imu2d_test1.yaml @@ -99,24 +99,24 @@ config: - package: "wolf_ros_node" type: "SubscriberOdom2d" - topic: "/ana/odom" + topic: "/odom" sensor_name: "odom2d" - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/ana/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true - package: "wolf_ros_imu" type: "SubscriberImuEnableable" - topic: "/ana/sensors/bno055_imu/imu" + topic: "/imu_bno" sensor_name: "bno" follow: "test_imu_subscriber_bno.yaml" - package: "wolf_ros_imu" type: "SubscriberImuEnableable" - topic: "/ana/imu/data" + topic: "/imu_micro" sensor_name: "microstrain" follow: "test_imu_subscriber_microstrain.yaml" diff --git a/yaml/imu2d_test10.yaml b/yaml/imu2d_test10.yaml index 00406b56b52c2c3f178dc880b61e24c83dabc2ab..c137dade19549322a89fccaaf225ac6ea44ebbfe 100644 --- a/yaml/imu2d_test10.yaml +++ b/yaml/imu2d_test10.yaml @@ -1,7 +1,7 @@ config: debug: profiling: true - profiling_file: "~/wolf_demo_profiling_imu2d_test0.txt" + profiling_file: "~/wolf_demo_profiling_imu2d_test10.txt" print_problem: false print_period: 2 print_depth: 4 @@ -12,14 +12,6 @@ config: tree_manager: type: "none" frame_structure: "POV" - # dimension: 2 - # prior: - # mode: "fix" - # $state: - # P: [0,0] - # O: [0] - # V: [0,0] - # time_tolerance: 0.1 dimension: 3 prior: mode: "fix" @@ -50,32 +42,12 @@ config: sensor_name: "scanner_front_left" plugin: "laser" follow: "test_laser_processor.yaml" - # - - # type: "ProcessorLoopClosureIcp" - # name: "processorloopclosureicp" - # sensor_name: "scanner_front_left" - # plugin: "laser" - # time_tolerance: 0.1 - # apply_loss_function: true - # keyframe_vote: - # voting_active: false - # recent_frames_ignored: 3 - # frames_ignored_after_loop: 0 - # max_error_threshold: 0.02 - # min_points_percent: 40 - # max_loops: 3 - # max_candidates: 5 - # max_attempts: 15 - # candidate_generation: "random" # 'random' or 'tree' - # icp: - # follow: "csm.yaml" - ROS subscriber: - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/ana/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true diff --git a/yaml/imu2d_test15.yaml b/yaml/imu2d_test15.yaml index 853c457a44352782cdb64cf11e7b9a27f6b954ca..852bb199b2dbc913b8c90e6457063f1c44cd8608 100644 --- a/yaml/imu2d_test15.yaml +++ b/yaml/imu2d_test15.yaml @@ -12,14 +12,6 @@ config: tree_manager: type: "none" frame_structure: "POV" - # dimension: 2 - # prior: - # mode: "fix" - # $state: - # P: [0,0] - # O: [0] - # V: [0,0] - # time_tolerance: 0.1 dimension: 3 prior: mode: "factor" @@ -47,13 +39,13 @@ config: name: "scanner_front_left" plugin: "laser" follow: "test_laser_params.yaml" - - - type: "SensorImu" - name: "bno" - plugin: "imu" - extrinsic: - pose: [0,0,0,0,0,0,1] - follow: "test_imu_params_bno.yaml" + # - + # type: "SensorImu" + # name: "bno" + # plugin: "imu" + # extrinsic: + # pose: [0,0,0,0,0,0,1] + # follow: "test_imu_params_bno.yaml" - type: "SensorImu" name: "microstrain" @@ -70,30 +62,11 @@ config: plugin: "laser" follow: "test_laser_processor.yaml" # - - # type: "ProcessorLoopClosureIcp" - # name: "processorloopclosureicp" - # sensor_name: "scanner_front_left" - # plugin: "laser" - # time_tolerance: 0.1 - # apply_loss_function: true - # keyframe_vote: - # voting_active: false - # recent_frames_ignored: 10 - # frames_ignored_after_loop: 0 - # max_error_threshold: 0.02 - # min_points_percent: 40 - # max_loops: 1 - # max_candidates: 5 - # max_attempts: 5 - # candidate_generation: "random" # 'random' or 'tree' - # icp: - # follow: "csm.yaml" - - - type: "ProcessorImu" - name: "processorimubno" - sensor_name: "bno" - plugin: "imu" - follow: "test_imu_processor_bno.yaml" + # type: "ProcessorImu" + # name: "processorimubno" + # sensor_name: "bno" + # plugin: "imu" + # follow: "test_imu_processor_bno.yaml" - type: "ProcessorImu" name: "processorimumicro" @@ -105,22 +78,19 @@ config: - package: "wolf_ros_laser" type: "SubscriberLaser2d" - # topic: "/ana/sensors/scan" - topic: "/helena/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true + # - + # package: "wolf_ros_imu" + # type: "SubscriberImuEnableable" + # topic: "/imu_bnomal" + # sensor_name: "bno" + # follow: "test_imu_subscriber_bno.yaml" - package: "wolf_ros_imu" type: "SubscriberImuEnableable" - # topic: "/ana/sensors/bno055_imu/imumal" - topic: "/helena/sensors/bno055_imu/imumal" - sensor_name: "bno" - follow: "test_imu_subscriber_bno.yaml" - - - package: "wolf_ros_imu" - type: "SubscriberImuEnableable" - # topic: "/ana/imu/data" - topic: "/helena/imu/data" + topic: "/imu_micro" sensor_name: "microstrain" follow: "test_imu_subscriber_microstrain.yaml" diff --git a/yaml/imu2d_test2.yaml b/yaml/imu2d_test2.yaml index d13e4c2f6f81cdb9ee78cf4351edf6eb81f7df10..96965f11979b1105bd8ec04ee151b7942c702a32 100644 --- a/yaml/imu2d_test2.yaml +++ b/yaml/imu2d_test2.yaml @@ -56,12 +56,12 @@ config: - package: "wolf_ros_node" type: "SubscriberOdom2d" - topic: "/helena/odom" + topic: "/odom" sensor_name: "odom2d" - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/helena/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true diff --git a/yaml/imu2d_test3.yaml b/yaml/imu2d_test3.yaml index 668270350f786fc3b909e68e10792e6f74933212..8712bd58c6de4428b87ec0e6eebcd3d3e8609175 100644 --- a/yaml/imu2d_test3.yaml +++ b/yaml/imu2d_test3.yaml @@ -77,21 +77,21 @@ config: - package: "wolf_ros_node" type: "SubscriberOdom2d" - topic: "/ana/odom" + topic: "/odom" sensor_name: "odom2d" - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/ana/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true - package: "wolf_ros_imu" type: "SubscriberImuEnableable" - topic: "/ana/sensors/bno055_imu/imu" + topic: "/imu_bno" + # topic: "/imu_micro" sensor_name: "bno" - #topic: "/ana/imu/data" - #sensor_name: "microstrain" + # sensor_name: "microstrain" follow: "test_imu_subscriber.yaml" ROS publisher: diff --git a/yaml/imu2d_test4.yaml b/yaml/imu2d_test4.yaml index a338b354e4b6a3b66f4b64752f5f4bc2f5891900..fb09b0b5f71d6e2d0a7c0205dc99a00c473cc0da 100644 --- a/yaml/imu2d_test4.yaml +++ b/yaml/imu2d_test4.yaml @@ -69,17 +69,17 @@ config: - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/helena/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true - package: "wolf_ros_imu" type: "SubscriberImuEnableable" ##bno - #topic: "/ana/sensors/bno055_imu/imu" + #topic: "/imu_bno" #sensor_name: "bno" #microstrain - topic: "/helena/sensors/imu/data" + topic: "/imu_micro" sensor_name: "microstrain" follow: "test_imu_subscriber.yaml" diff --git a/yaml/imu2d_test5.yaml b/yaml/imu2d_test5.yaml index 37f81ab22d132723a3b9a4b207aee755b7d953f1..50c3a97b6af577bc31197cbe8898c8cbdb315290 100644 --- a/yaml/imu2d_test5.yaml +++ b/yaml/imu2d_test5.yaml @@ -89,19 +89,19 @@ config: - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/ana/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true - package: "wolf_ros_imu" type: "SubscriberImuEnableable" - topic: "/ana/sensors/bno055_imu/imumal" + topic: "/imu_bnomal" sensor_name: "bno" follow: "test_imu_subscriber_bno.yaml" - package: "wolf_ros_imu" type: "SubscriberImuEnableable" - topic: "/ana/imu/data" + topic: "/imu_micro" sensor_name: "microstrain" follow: "test_imu_subscriber_microstrain.yaml" diff --git a/yaml/imu2d_test6.yaml b/yaml/imu2d_test6.yaml index 01ccb1b039f2aba6ff4e5aa6deffb1626d04d42b..da0506330c8590e63f282c4597bd8b7da1ca8626 100644 --- a/yaml/imu2d_test6.yaml +++ b/yaml/imu2d_test6.yaml @@ -55,12 +55,12 @@ config: - package: "wolf_ros_node" type: "SubscriberOdom2d" - topic: "/ana/odom" + topic: "/odom" sensor_name: "odom2d" - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/ana/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true diff --git a/yaml/imu2d_test7.yaml b/yaml/imu2d_test7.yaml index b0fa2cbc4d3ae2b5a9d97cac4b808db1a2374c53..058f8a1f82cf017cf2187f7e7e2005115fa5d1d4 100644 --- a/yaml/imu2d_test7.yaml +++ b/yaml/imu2d_test7.yaml @@ -68,18 +68,18 @@ config: - package: "wolf_ros_node" type: "SubscriberOdom2d" - topic: "/helena/odom" + topic: "/odom" sensor_name: "odom2d" - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/helena/sensors/scan" + topic: "/scan" sensor_name: "scanner_front_left" load_params_from_msg: true - package: "wolf_ros_gnss" type: "SubscriberGnssUblox" - topic: "/helena/sensors/ublox_gps/raw_data_stream" + topic: "/ublox_gps/raw_data_stream" sensor_name: "gnss" follow: "test_subscriber_gnss.yaml" diff --git a/yaml/test_imu_subscriber_bno.yaml b/yaml/test_imu_subscriber_bno.yaml index 34e3cf7f9c4c37df9bb107fb8d9b7d4763ba0c47..25fa3ab2b8b9cad06e7d64b41f6ed9af72e25599 100644 --- a/yaml/test_imu_subscriber_bno.yaml +++ b/yaml/test_imu_subscriber_bno.yaml @@ -7,7 +7,7 @@ cov_source: "sensor" in_degrees: true #all -topic_enable: "/helena/sensors/bno055_imu/imu/topic_enable" +topic_enable: "/imu_bno/enable" static_init_duration: 5 lowpass_filter: true lowpass_cutoff_freq: 5 diff --git a/yaml/test_imu_subscriber_microstrain.yaml b/yaml/test_imu_subscriber_microstrain.yaml index 1bf1e8c462c3917a25c3351d3749473cc930d7d2..c4510187db7463dbaac0874b2709e6c62e3a176e 100644 --- a/yaml/test_imu_subscriber_microstrain.yaml +++ b/yaml/test_imu_subscriber_microstrain.yaml @@ -7,7 +7,7 @@ cov_source: "sensor" in_degrees: false #all -topic_enable: "/helena/sensors/bno055_imu/imu/topic_enable" +topic_enable: "/imu_micro/enable" static_init_duration: 3 lowpass_filter: false lowpass_cutoff_freq: 5 diff --git a/yaml/test_laser_processor.yaml b/yaml/test_laser_processor.yaml index fa2d98e94d6d031d86ad80300781d72d09e68036..bee6cc8ec51e1beacdc48353a0c7d31f520de9f7 100644 --- a/yaml/test_laser_processor.yaml +++ b/yaml/test_laser_processor.yaml @@ -3,7 +3,7 @@ keyframe_vote: min_features_for_keyframe: 10 min_dist: 999 min_angle: 999 - min_time: 0.1 + min_time: 0.5 min_error: 999 max_points: 0 max_new_features: 15 diff --git a/yaml/test_publisher_ros_node.yaml b/yaml/test_publisher_ros_node.yaml index a3e37459266db719cbea053e906bc686d902fec3..4c8807a5e3eb9081f7e36665f33cc2fa718ef1ff 100644 --- a/yaml/test_publisher_ros_node.yaml +++ b/yaml/test_publisher_ros_node.yaml @@ -1,4 +1,6 @@ map_frame_id: "map" -odom_frame_id: "ana/odom" -base_frame_id: "ana/base_footprint" +# odom_frame_id: "ana/odom" +# base_frame_id: "ana/base_footprint" +odom_frame_id: "helena/odom" +base_frame_id: "helena/base_footprint" publish_odom_tf: false