Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add 3D tutorial #27

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion fuse_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,13 @@ target_link_libraries(${PROJECT_NAME} PUBLIC
${sensor_msgs_TARGETS}
)

# tutorial_sim executable
# tutorial_sim executables
add_executable(range_sensor_simulator src/range_sensor_simulator.cpp)
target_link_libraries(range_sensor_simulator ${PROJECT_NAME})

add_executable(three_dimensional_simulator src/three_dimensional_simulator.cpp)
target_link_libraries(three_dimensional_simulator ${PROJECT_NAME})

#############
## Testing ##
#############
Expand Down Expand Up @@ -75,6 +78,7 @@ install(TARGETS
TARGETS range_sensor_simulator
DESTINATION lib/${PROJECT_NAME}
)
install(TARGETS three_dimensional_simulator DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY launch config data
DESTINATION share/${PROJECT_NAME}
Expand Down
213 changes: 213 additions & 0 deletions fuse_tutorials/config/fuse_3d_tutorial.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,213 @@
Panels:
- Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /Odometry1/Shape1
- /Odometry2/Shape1
Splitter Ratio: 0.5
Tree Height: 555
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/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
- Angle Tolerance: 0.10000000149011612
Class: rviz_default_plugins/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: true
Keep: 1
Name: Odometry
Position Tolerance: 0.10000000149011612
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.10000000149011612
Color: 255; 0; 0
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Value: Arrow
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /ground_truth
Value: true
- Angle Tolerance: 0.10000000149011612
Class: rviz_default_plugins/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: 1
Name: Odometry
Position Tolerance: 0.10000000149011612
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.10000000149011612
Color: 0; 255; 0
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Value: Arrow
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /odom_filtered
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 10.72309398651123
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
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>
Value: Orbit (rviz)
Yaw: 0.785398006439209
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002b4000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000025300fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 60
Y: 60
61 changes: 61 additions & 0 deletions fuse_tutorials/config/fuse_3d_tutorial.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
state_estimator:
ros__parameters:
# Fixed-lag smoother configuration
optimization_frequency: 20.0
transaction_timeout: 0.01
lag_duration: 0.5

# all our sensors will be using this motion model
motion_models:
3d_motion_model:
type: fuse_models::Omnidirectional3D

3d_motion_model:
# x, y, z, roll, pitch, yaw, x_vel, y_vel, z_vel, roll_vel, pitch_vel, yaw_vel, x_acc, y_acc, z_acc
process_noise_diagonal: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]

sensor_models:
initial_localization_sensor:
type: fuse_models::Omnidirectional3DIgnition
motion_models: [3d_motion_model]
ignition: true
odometry_sensor:
type: fuse_models::Odometry3D
motion_models: [3d_motion_model]
imu_sensor:
type: fuse_models::Imu3D
motion_models: [3d_motion_model]

initial_localization_sensor:
publish_on_startup: true
# x, y, z, roll, pitch, yaw, x_vel, y_vel, z_vel, roll_vel, pitch_vel, yaw_vel, x_acc, y_acc, z_acc
initial_state: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
initial_sigma: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]

odometry_sensor:
topic: 'odom'
twist_target_frame: 'base_link'
# we only want position and orientation, but you can get a full odometry measurement from this sensor
position_dimensions: ['x', 'y', 'z']
orientation_dimensions: ['roll', 'pitch', 'yaw']

imu_sensor:
topic: 'imu'
acceleration_target_frame: 'base_link'
# we only care about linear acceleration for this tutorial
linear_acceleration_dimensions: ['x', 'y', 'z']

# this publishes our estimated odometry
publishers:
filtered_publisher:
type: fuse_models::Odometry3DPublisher

# the configuration of our output publisher
filtered_publisher:
topic: 'odom_filtered'
base_link_frame_id: 'base_link'
odom_frame_id: 'odom'
map_frame_id: 'map'
world_frame_id: 'odom'
publish_tf: true
publish_frequency: 10.0
67 changes: 67 additions & 0 deletions fuse_tutorials/launch/fuse_3d_tutorial.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
#! /usr/bin/env python3

# Copyright 2024 PickNik Robotics
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from launch import LaunchDescription
from launch.actions import ExecuteProcess
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node, SetParameter
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
pkg_dir = FindPackageShare("fuse_tutorials")

return LaunchDescription(
[
# tell tf2 that map is the same as odom
# without this, visualization won't work as we have no reference
Node(
package="tf2_ros",
executable="static_transform_publisher",
arguments=["0", "0", "0", "0", "0", "0", "map", "odom"],
),
# run our simulator
Node(
package="fuse_tutorials",
executable="three_dimensional_simulator",
name="three_dimensional_simulator",
output="screen",
),
# run our estimator
Node(
package="fuse_optimizers",
executable="fixed_lag_smoother_node",
name="state_estimator",
parameters=[
PathJoinSubstitution([pkg_dir, "config", "fuse_3d_tutorial.yaml"])
],
),
# run visualization
Node(
package="rviz2",
executable="rviz2",
name="rviz",
arguments=[
"-d",
[
PathJoinSubstitution(
[pkg_dir, "config", "fuse_3d_tutorial.rviz"]
)
],
],
),
]
)
Loading