Skip to content

Commit

Permalink
Merge pull request #37 from SBG-Systems/6-cant-launch-mag-calibration
Browse files Browse the repository at this point in the history
Issue 6: Can't launch mag calibration
  • Loading branch information
tolesam authored Oct 17, 2024
2 parents 6d3c16f + f26296f commit 9e88e2b
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 11 deletions.
20 changes: 10 additions & 10 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -315,32 +315,32 @@ The ELLIPSE offers both a 2D and 3D magnetic field calibration mode.
2) Start a new magnetic calibration session once you are ready to map the magnetic field:

```
roslaunch sbg_driver sbg_device_mag_calibration.launch
rosservice call /sbg/mag_calibration
ros2 launch sbg_driver sbg_device_mag_calibration_launch.py
ros2 service call /sbg/mag_calibration std_srvs/srv/Trigger
```

> success: True
> message: "Magnetometer calibration process started."
> response:
> std_srvs.srv.Trigger_Response(success=True, message='Magnetometer calibration process started.')
3) Rotate as much as possible the unit to map the surrounding magnetic field (ideally, perform a 360° with X then Y then Z axis pointing downward).
4) Once you believe you have covered enough orientations, compute a magnetic field calibration:

```
rosservice call /sbg/mag_calibration
ros2 service call /sbg/mag_calibration std_srvs/srv/Trigger
```

> success: True
> message: "Magnetometer calibration is finished. See the output console to get calibration information."
> response:
> std_srvs.srv.Trigger_Response(success=True, message='Magnetometer calibration is finished. See the output console to get calibration information.')
5) If you are happy with the results (Quality, Confidence), apply and save the new magnetic calibration parameters.
If not, you can continue to rotate the product and try to perform a new computation (and repeat step 4)

```
rosservice call /sbg/mag_calibration_save
ros2 service call /sbg/mag_calibration_save std_srvs/srv/Trigger
```

> success: True
> message: "Magnetometer calibration has been uploaded to the device."
> response:
> std_srvs.srv.Trigger_Response(success=True, message='Magnetometer calibration has been uploaded to the device.')
6) Reset/Power Cycle the device and you should now get an accurate magnetic based heading.

Expand Down
2 changes: 1 addition & 1 deletion src/main_mag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ using sbg::SbgDevice;
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
rclcpp::Node::SharedPtr node_handle;
auto node_handle = std::make_shared<rclcpp::Node>("sbg_device_mag");

try
{
Expand Down

0 comments on commit 9e88e2b

Please sign in to comment.