Skip to content

Commit

Permalink
add navsat conversion and gps
Browse files Browse the repository at this point in the history
  • Loading branch information
SimonR99 committed May 15, 2024
1 parent c1635ec commit 24d7712
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 26 deletions.
40 changes: 19 additions & 21 deletions src/rove_bringup/launch/common.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,23 +45,24 @@ def generate_launch_description():
# used tutorial: https://navigation.ros.org/tutorials/docs/navigation2_with_gps.html

robot_localization_node_local = Node(
package='robot_localization',
executable='ekf_node',
name='ekf_filter_node_local',
output='screen',
parameters=[os.path.join(pkg_rove_slam, 'config/ekf.yaml'),
{'use_sim_time': True}]
)
package='robot_localization',
executable='ekf_node',
name='ekf_filter_node_local',
output='screen',
parameters=[os.path.join(pkg_rove_slam, 'config/ekf.yaml'),
{'use_sim_time': True}],
remappings=[('odometry/filtered', 'odometry/local')])


robot_localization_node_global = Node(
package='robot_localization',
executable='ekf_node',
name='ekf_filter_node_global',
output='screen',
parameters=[os.path.join(pkg_rove_slam, 'config/ekf.yaml'),
{'use_sim_time': True}],
remappings=[("odometry/filtered", "odometry/filtered/global")],
)
package='robot_localization',
executable='ekf_node',
name='ekf_filter_node_global',
output='screen',
parameters=[os.path.join(pkg_rove_slam, 'config/ekf.yaml'),
{'use_sim_time': True}],
remappings=[('odometry/filtered', 'odometry/global')])


navsat_transform = Node(
package="robot_localization",
Expand All @@ -74,10 +75,7 @@ def generate_launch_description():
# Subscribed Topics
("imu/data", "imu"),
("gps/fix", "gps"),
("odometry/filtered", "odometry/filtered/global"),
# Published Topics
("gps/filtered", "gps/filtered"),
("odometry/gps", "odometry/gps"),
('odometry/filtered', 'odometry/global'),
],
)

Expand All @@ -101,8 +99,8 @@ def generate_launch_description():
return LaunchDescription([
robot_state_publisher,
robot_localization_node_local,
#robot_localization_node_global,
#navsat_transform,
robot_localization_node_global,
navsat_transform,
rviz,
teleop,
autonomy,
Expand Down
5 changes: 3 additions & 2 deletions src/rove_description/config/navsat_transform.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,10 @@ navsat_transform:
frequency: 30.0
delay: 3.0
magnetic_declination_radians: 0.0
yaw_offset: 0.0
yaw_offset: pi
zero_altitude: true
broadcast_utm_transform: true
publish_filtered_gps: true
use_odometry_yaw: true
wait_for_datum: false
wait_for_datum: false
broadcast_utm_transform_as_parent_frame: false
5 changes: 2 additions & 3 deletions src/rove_slam/config/ekf.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,11 @@ ekf_filter_node_global:
ros__parameters:
frequency: 30.0
two_d_mode: false
publish_acceleration: true
publish_tf: true

map_frame: map
odom_frame: odom
base_link_frame: base_link
world_frame: map
world_frame: gps

odom0: /odom
odom0_config: [true, true, false,
Expand All @@ -49,6 +47,7 @@ ekf_filter_node_global:
false, false, false, # vx vy vz
false, false, true, # vroll vpitch vyaw
true, true, false] # ax ay az
imu0_queue_size: 20

# description from https://github.com/cra-ros-pkg/robot_localization/blob/ros2/params/ekf.yaml
# Each sensor reading updates some or all of the filter's state. These options give you greater control over which
Expand Down

0 comments on commit 24d7712

Please sign in to comment.