Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
R
Robobin
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Deploy
Releases
Package Registry
Model registry
Operate
Terraform modules
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
plw1g21
Robobin
Commits
de28947d
Commit
de28947d
authored
2 months ago
by
Paul-Winpenny
Browse files
Options
Downloads
Patches
Plain Diff
Removed even more comments!
parent
c9359a98
No related branches found
Branches containing commit
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
ros2/src/robobin/robobin/uwb_navigation_node.py
+20
-9
20 additions, 9 deletions
ros2/src/robobin/robobin/uwb_navigation_node.py
with
20 additions
and
9 deletions
ros2/src/robobin/robobin/uwb_navigation_node.py
+
20
−
9
View file @
de28947d
...
@@ -676,18 +676,29 @@ class UWBNode(Node):
...
@@ -676,18 +676,29 @@ class UWBNode(Node):
dy
=
calib_end_position
[
1
]
-
self
.
calib_start_position
[
1
]
dy
=
calib_end_position
[
1
]
-
self
.
calib_start_position
[
1
]
uwb_heading
=
math
.
atan2
(
dy
,
dx
)
uwb_heading
=
math
.
atan2
(
dy
,
dx
)
offset
=
calib_end_yaw
-
uwb_heading
# Convert UWB heading to degrees
self
.
uwb_to_imu_offset
=
offset
uwb_heading_deg
=
math
.
degrees
(
uwb_heading
)
# Normalize to [0, 360)
uwb_heading_deg_normalized
=
(
uwb_heading_deg
+
360
)
%
360
self
.
get_logger
().
info
(
"
CALIBRATION COMPLETE!
"
)
# Convert IMU yaw to degrees
self
.
get_logger
().
info
(
f
"
Start Pos (UWB):
{
self
.
calib_start_position
}
"
)
calib_end_yaw_deg
=
math
.
degrees
(
calib_end_yaw
)
self
.
get_logger
().
info
(
f
"
End Pos (UWB):
{
calib_end_position
}
"
)
self
.
get_logger
().
info
(
f
"
UWB heading:
{
uwb_heading
:
.
3
f
}
rad
"
)
self
.
get_logger
().
info
(
f
"
IMU yaw:
{
calib_end_yaw
:
.
3
f
}
rad
"
)
self
.
get_logger
().
info
(
f
"
--> OFFSET:
{
offset
:
.
3
f
}
rad
"
)
# Calculate offset
offset_deg
=
calib_end_yaw_deg
-
uwb_heading_deg_normalized
# Normalize offset to [0, 360)
offset_deg_normalized
=
(
offset_deg
+
360
)
%
360
# Logging information
print
(
"
CALIBRATION COMPLETE!
"
)
print
(
f
"
Start Pos (UWB):
{
self
.
calib_start_position
}
"
)
print
(
f
"
End Pos (UWB):
{
calib_end_position
}
"
)
print
(
f
"
UWB heading:
{
uwb_heading
:
.
3
f
}
rad (
{
uwb_heading_deg_normalized
:
.
3
f
}
deg)
"
)
print
(
f
"
IMU yaw:
{
calib_end_yaw
:
.
3
f
}
rad (
{
calib_end_yaw_deg
:
.
3
f
}
deg)
"
)
print
(
f
"
--> OFFSET:
{
offset_deg
:
.
3
f
}
deg (normalized to
{
offset_deg_normalized
:
.
3
f
}
deg)
"
)
self
.
calibration_active
=
False
self
.
calibration_active
=
False
self
.
mode
=
"
Manual
"
self
.
mode
=
"
Manual
"
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment