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 nav2_gps_waypoint_follower #2814

Merged
merged 91 commits into from
Sep 21, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
91 commits
Select commit Hold shift + click to select a range
5f33ac5
Add nav2_gps_waypoint_follower
jediofgever Dec 1, 2020
277c1e1
use correct client node while calling it to spin
jediofgever Dec 2, 2020
c6ee437
changed after 1'st review
jediofgever Dec 4, 2020
7b6f8cf
apply requested changes
jediofgever Dec 7, 2020
ac94d2d
nav2_util::ServiceClient instead of CallbackGroup
jediofgever Dec 7, 2020
cd9a287
another iteration to adress issues
jediofgever Dec 8, 2020
9c0e408
update poses with function in the follower logic
jediofgever Dec 8, 2020
f94e3b3
add deps of robot_localization: diagnostics
jediofgever Dec 8, 2020
e4fe184
fix typo in underlay.repo
jediofgever Dec 8, 2020
c2f4d95
add deps of robot_localization: geographic_info
jediofgever Dec 8, 2020
98804f1
minor clean-ups
jediofgever Dec 8, 2020
e95f55a
merge ros-planning::navigation2::main into jediofgever::navigation2::…
jediofgever Dec 9, 2020
960bb13
bond_core version has been updated
jediofgever Dec 9, 2020
623c6a6
rotation should also be considered in GPS WPFing
jediofgever Dec 14, 2020
ef57df0
use better namings related to gps wpf orientation
jediofgever Dec 14, 2020
063b8e7
handle cpplint errors
jediofgever Dec 14, 2020
e544fde
tf_listener needs to be initialized
jediofgever Dec 15, 2020
84c7ef0
apply requested changes
jediofgever Dec 17, 2020
d2c4127
apply requested changes 2.5/3.0
jediofgever Dec 17, 2020
aee13ca
apply requested changes 3.0/3.0
jediofgever Dec 17, 2020
4f83167
fix misplaced ";"
jediofgever Dec 17, 2020
6e322ea
use run time param for gps transform timeout
jediofgever Dec 18, 2020
81c7c64
change timeout var name
jediofgever Dec 18, 2020
7c69520
make use of stop_on_failure for GPS too
jediofgever Dec 21, 2020
7889ae3
passing emptywaypont vectors are seen as failure
jediofgever Dec 23, 2020
c28b93e
pull changes from ros-planing::navigation2::main
jediofgever Jan 5, 2021
c6613a8
update warning for empty requests
jediofgever Jan 8, 2021
0d0d59c
get upstream changes
jediofgever Jan 23, 2021
d7e2ad4
consider utm -> map yaw offset
jediofgever Jan 23, 2021
d6527d2
fix missed RCLCPP info
jediofgever Jan 23, 2021
f99ebff
reorrect action;s name
jediofgever Jan 23, 2021
e0a3aa6
get mainstream changes
jediofgever Mar 18, 2021
5fcfb83
waypoint stamps need to be updated
jediofgever Mar 19, 2021
5ceb349
Fix merge conflicts
pepisg Feb 10, 2022
3e7af6b
Fix segmentation fault on waypoint follower
pepisg Feb 10, 2022
bc87763
Parametric frames and matrix multiplications
pepisg Feb 10, 2022
cfb6f13
Replace oriented navsatfix for geographic_msgs/geopose
pepisg Feb 11, 2022
cafef39
Remove deprecated oriented navsatfix message
pepisg Feb 11, 2022
4b3f774
Update branch name on robot_localization dependency
pepisg Feb 11, 2022
534f01a
Fix parametric frames logic
pepisg Feb 11, 2022
f4466b6
Rename functions and adress comments
pepisg Feb 14, 2022
9cdefaf
fix style in underlay.repos
pepisg Feb 14, 2022
6aee420
remove duplicate word in underlay.repos
pepisg Feb 14, 2022
c7c8c01
update dependency version of ompl
pepisg Feb 14, 2022
eabbfcf
Template ServiceClient class to accept lifecycle node
pepisg Feb 15, 2022
af8f468
Remove link to stackoverflow answer
pepisg Feb 15, 2022
b14fcca
Remove yaw offset compensation
pepisg Mar 28, 2022
b5222b8
Merge branch 'main' of github.com:ros-planning/navigation2 into gps-w…
pepisg Mar 28, 2022
87b43f7
Merge branch 'main' of github.com:kiwicampus/navigation2 into gps-way…
pepisg Jun 15, 2022
84999e1
Fix API change
pepisg Jun 15, 2022
879b4e6
Fix styling
pepisg Jun 17, 2022
8cc6311
Minor docs fixes
pepisg Jun 17, 2022
03cca60
Fix style divergences
pepisg Jun 17, 2022
8e87793
Style fixes
pepisg Jun 21, 2022
231f705
Style fixes v2
pepisg Jun 21, 2022
6a3a5fb
Style fixes v3
pepisg Jun 22, 2022
f855cf2
Merge branch 'main' of github.com:kiwicampus/navigation2 into gps-way…
pepisg Jun 24, 2022
cf4ed6e
Remove unused variables and timestam overrides
pepisg Jun 24, 2022
3c58360
Update branch
pepisg Sep 2, 2022
46fce6e
restore goal timestamp override
pepisg Sep 26, 2022
d2c7fcb
fetch upstream
pepisg Sep 26, 2022
e84158a
WIP: Add follow gps waypoints test
pepisg Sep 28, 2022
939756e
Style fixes and gazebo world inertia fix
pepisg Sep 29, 2022
901ce78
Merge branch 'ros-planning:main' into gps-waypoint-follower
pepisg Sep 29, 2022
5f95c13
Reduce velocity smoother timeout
pepisg Sep 29, 2022
839655f
empty commit to rerun tests
pepisg Sep 29, 2022
5226c0b
Increment circle ci cache idx
pepisg Oct 3, 2022
292ce05
Merge branch 'ros-planning:main' into gps-waypoint-follower
pepisg Oct 3, 2022
96215ef
Remove extra space in cmakelists.txt
pepisg Oct 4, 2022
3252f6d
Merge branch 'gps-waypoint-follower' of github.com:kiwicampus/navigat…
pepisg Oct 4, 2022
e53886b
Merge branch 'ros-planning:main' into gps-waypoint-follower
pepisg Oct 12, 2022
a8c7a0f
Merge branch 'ros-planning:main' into gps-waypoint-follower
pepisg Oct 18, 2022
f6623ae
Merge branch 'ros-planning:main' into gps-waypoint-follower
pepisg Nov 7, 2022
376f599
Fix wrong usage of the global action server
pepisg Dec 30, 2022
339e260
Merge branch 'main' of github.com:kiwicampus/navigation2 into gps-way…
pepisg Dec 30, 2022
5ec4d8c
update follow gps waypoints action definition
pepisg Dec 30, 2022
dbcb923
Merge branch 'main' into gps-waypoint-follower
pepisg Aug 13, 2023
cefd0bf
Fix action definition and looping
pepisg Aug 13, 2023
ed96101
update params for the unit testing
pepisg Aug 13, 2023
179d5c5
WIP: update tests
pepisg Aug 14, 2023
0f7c700
fix tests
pepisg Aug 15, 2023
67aec18
fixes to nav2 simple commander
pepisg Aug 15, 2023
d31cc53
add robot_localization localizer
pepisg Aug 21, 2023
d595cca
Merge branch 'main' of github.com:kiwicampus/navigation2 into gps-way…
pepisg Sep 10, 2023
6fe265a
Bring back from LL client
pepisg Sep 10, 2023
40bf684
Update nav2_simple_commander/nav2_simple_commander/robot_navigator.py
pepisg Sep 16, 2023
0bb5072
missing argument in test function
pepisg Sep 16, 2023
85f57ed
Merge branch 'gps-waypoint-follower' of github.com:kiwicampus/navigat…
pepisg Sep 16, 2023
fb3a035
small test error
pepisg Sep 16, 2023
1ca58db
style fixes nav2 simple commander
pepisg Sep 17, 2023
a01cbbc
rename cartesian action server
pepisg Sep 20, 2023
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
4 changes: 3 additions & 1 deletion nav2_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ find_package(nav_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geographic_msgs)
find_package(action_msgs REQUIRED)

nav2_package()
Expand Down Expand Up @@ -49,7 +50,8 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"action/Spin.action"
"action/DummyBehavior.action"
"action/FollowWaypoints.action"
DEPENDENCIES builtin_interfaces geometry_msgs std_msgs action_msgs nav_msgs
"action/FollowGPSWaypoints.action"
DEPENDENCIES builtin_interfaces geometry_msgs std_msgs action_msgs nav_msgs geographic_msgs
)

ament_export_dependencies(rosidl_default_runtime)
Expand Down
17 changes: 17 additions & 0 deletions nav2_msgs/action/FollowGPSWaypoints.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
#goal definition
uint32 number_of_loops
uint32 goal_index 0
geographic_msgs/GeoPose[] gps_poses
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
---
#result definition

# Error codes
# Note: The expected priority order of the errors should match the message order
uint16 NONE=0
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
uint16 UNKNOWN=600
uint16 TASK_EXECUTOR_FAILED=601

MissedWaypoint[] missed_waypoints
---
#feedback
uint32 current_waypoint
1 change: 1 addition & 0 deletions nav2_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>geometry_msgs</depend>
<depend>action_msgs</depend>
<depend>nav_msgs</depend>
<depend>geographic_msgs</depend>

<member_of_group>rosidl_interface_packages</member_of_group>

Expand Down
30 changes: 28 additions & 2 deletions nav2_simple_commander/nav2_simple_commander/robot_navigator.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,8 @@
from lifecycle_msgs.srv import GetState
from nav2_msgs.action import AssistedTeleop, BackUp, Spin
from nav2_msgs.action import ComputePathThroughPoses, ComputePathToPose
from nav2_msgs.action import FollowPath, FollowWaypoints, NavigateThroughPoses, NavigateToPose
from nav2_msgs.action import FollowPath, FollowWaypoints, FollowGPSWaypoints, \
NavigateThroughPoses, NavigateToPose
from nav2_msgs.action import SmoothPath
from nav2_msgs.srv import ClearEntireCostmap, GetCostmap, LoadMap, ManageLifecycleNodes

Expand Down Expand Up @@ -67,6 +68,8 @@ def __init__(self, node_name='basic_navigator'):
'navigate_through_poses')
self.nav_to_pose_client = ActionClient(self, NavigateToPose, 'navigate_to_pose')
self.follow_waypoints_client = ActionClient(self, FollowWaypoints, 'follow_waypoints')
self.follow_gps_waypoints_client = ActionClient(self, FollowGPSWaypoints,
'follow_gps_waypoints')
self.follow_path_client = ActionClient(self, FollowPath, 'follow_path')
self.compute_path_to_pose_client = ActionClient(self, ComputePathToPose,
'compute_path_to_pose')
Expand Down Expand Up @@ -182,6 +185,28 @@ def followWaypoints(self, poses):
self.result_future = self.goal_handle.get_result_async()
return True

def followGpsWaypoints(self, gps_poses):
"""Send a `FollowGPSWaypoints` action request."""
self.debug("Waiting for 'FollowWaypoints' action server")
while not self.follow_gps_waypoints_client.wait_for_server(timeout_sec=1.0):
self.info("'FollowWaypoints' action server not available, waiting...")

goal_msg = FollowGPSWaypoints.Goal()
goal_msg.gps_poses = gps_poses

self.info(f'Following {len(goal_msg.gps_poses)} gps goals....')
send_goal_future = self.follow_gps_waypoints_client.send_goal_async(goal_msg,
self._feedbackCallback)
rclpy.spin_until_future_complete(self, send_goal_future)
self.goal_handle = send_goal_future.result()

if not self.goal_handle.accepted:
self.error(f'Following {len(gps_poses)} gps waypoints request was rejected!')
return False

self.result_future = self.goal_handle.get_result_async()
return True

def spin(self, spin_dist=1.57, time_allowance=10):
self.debug("Waiting for 'Spin' action server")
while not self.spin_client.wait_for_server(timeout_sec=1.0):
Expand Down Expand Up @@ -310,7 +335,8 @@ def getResult(self):

def waitUntilNav2Active(self, navigator='bt_navigator', localizer='amcl'):
"""Block until the full navigation system is up and running."""
self._waitForNodeToActivate(localizer)
if localizer != "robot_localization": # non-lifecycle node
self._waitForNodeToActivate(localizer)
if localizer == 'amcl':
self._waitForInitialPose()
self._waitForNodeToActivate(navigator)
Expand Down
1 change: 1 addition & 0 deletions nav2_system_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ if(BUILD_TESTING)
add_subdirectory(src/system_failure)
add_subdirectory(src/updown)
add_subdirectory(src/waypoint_follower)
add_subdirectory(src/gps_navigation)
add_subdirectory(src/behaviors/spin)
add_subdirectory(src/behaviors/wait)
add_subdirectory(src/behaviors/backup)
Expand Down
11 changes: 11 additions & 0 deletions nav2_system_tests/src/gps_navigation/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
ament_add_test(test_gps_waypoint_follower
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_case_py.launch.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
TIMEOUT 180
ENV
TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR}
TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo_gps.world
GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
BT_NAVIGATOR_XML=navigate_to_pose_w_replanning_and_recovery.xml
)
63 changes: 63 additions & 0 deletions nav2_system_tests/src/gps_navigation/dual_ekf_navsat.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
# Copyright 2018 Open Source Robotics Foundation, Inc.
# 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
import launch_ros.actions
import os
import launch.actions


def generate_launch_description():
launch_dir = os.path.dirname(os.path.realpath(__file__))
params_file = os.path.join(launch_dir, "dual_ekf_navsat_params.yaml")
os.environ["FILE_PATH"] = str(launch_dir)
return LaunchDescription(
[
launch.actions.DeclareLaunchArgument(
"output_final_position", default_value="false"
),
launch.actions.DeclareLaunchArgument(
"output_location", default_value="~/dual_ekf_navsat_example_debug.txt"
),
launch_ros.actions.Node(
package="robot_localization",
executable="ekf_node",
name="ekf_filter_node_odom",
output="screen",
parameters=[params_file, {"use_sim_time": True}],
remappings=[("odometry/filtered", "odometry/local")],
),
launch_ros.actions.Node(
package="robot_localization",
executable="ekf_node",
name="ekf_filter_node_map",
output="screen",
parameters=[params_file, {"use_sim_time": True}],
remappings=[("odometry/filtered", "odometry/global")],
),
launch_ros.actions.Node(
package="robot_localization",
executable="navsat_transform_node",
name="navsat_transform",
output="screen",
parameters=[params_file, {"use_sim_time": True}],
remappings=[
("imu/data", "imu/data"),
("gps/fix", "gps/fix"),
("gps/filtered", "gps/filtered"),
("odometry/gps", "odometry/gps"),
("odometry/filtered", "odometry/global"),
],
),
]
)
127 changes: 127 additions & 0 deletions nav2_system_tests/src/gps_navigation/dual_ekf_navsat_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,127 @@
# For parameter descriptions, please refer to the template parameter files for each node.

ekf_filter_node_odom:
ros__parameters:
frequency: 30.0
two_d_mode: true # Recommended to use 2d mode for nav2, since its world representation is 2d
print_diagnostics: true
debug: false
publish_tf: true

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

odom0: odom
odom0_config: [false, false, false,
false, false, false,
true, true, true,
false, false, true,
false, false, false]
odom0_queue_size: 10
odom0_differential: false
odom0_relative: false

imu0: imu/data
imu0_config: [false, false, false,
false, false, true,
false, false, false,
false, false, false,
false, false, false]
imu0_differential: false # If using a real robot you might want to set this to true, since usually absolute measurements from real imu's are not very accurate
imu0_relative: false
imu0_queue_size: 10
imu0_remove_gravitational_acceleration: true

use_control: false

process_noise_covariance: [1e-3, 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, 1e-3, 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, 1e-3, 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, 0.3, 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, 0.3, 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, 0.01, 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, 0.5, 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, 0.5, 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, 0.1, 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, 0.3, 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, 0.3, 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, 0.3, 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, 0.3, 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, 0.3, 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, 0.3]

ekf_filter_node_map:
ros__parameters:
frequency: 30.0
two_d_mode: true # Recommended to use 2d mode for nav2, since its world representation is 2d
print_diagnostics: true
debug: false
publish_tf: true

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

odom0: odom
odom0_config: [false, false, false,
false, false, false,
true, true, true,
false, false, true,
false, false, false]
odom0_queue_size: 10
odom0_differential: false
odom0_relative: false

odom1: odometry/gps
odom1_config: [true, true, false,
false, false, false,
false, false, false,
false, false, false,
false, false, false]
odom1_queue_size: 10
odom1_differential: false
odom1_relative: false

imu0: imu/data
imu0_config: [false, false, false,
false, false, true,
false, false, false,
false, false, false,
false, false, false]
imu0_differential: false # If using a real robot you might want to set this to true, since usually absolute measurements from real imu's are not very accurate
imu0_relative: false
imu0_queue_size: 10
imu0_remove_gravitational_acceleration: true

use_control: false

process_noise_covariance: [1.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.0, 1.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.0, 1e-3, 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, 0.3, 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, 0.3, 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, 0.01, 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, 0.5, 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, 0.5, 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, 0.1, 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, 0.3, 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, 0.3, 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, 0.3, 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, 0.3, 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, 0.3, 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, 0.3]

navsat_transform:
ros__parameters:
frequency: 30.0
delay: 3.0
magnetic_declination_radians: 0.0429351 # For lat/long 55.944831, -3.186998
yaw_offset: 0.0
zero_altitude: true
broadcast_utm_transform: true
publish_filtered_gps: true
use_odometry_yaw: true
wait_for_datum: false
Loading