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

tf2_gemometry_msgs as a dep for vn_sensor_msgs; try/catch readGpsCompassBaseline #59

Merged
merged 1 commit into from
Apr 12, 2021
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
4 changes: 2 additions & 2 deletions vectornav/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ target_link_libraries(${PROJECT_NAME} vncxx )

# vn_sensor_msgs
add_executable(vn_sensor_msgs src/vn_sensor_msgs.cc)
ament_target_dependencies(vn_sensor_msgs rclcpp sensor_msgs vectornav_msgs)
ament_target_dependencies(vn_sensor_msgs rclcpp sensor_msgs vectornav_msgs tf2_geometry_msgs)

# install
install(TARGETS
Expand All @@ -52,4 +52,4 @@ endif()

ament_export_dependencies(rosidl_default_runtime)

ament_package()
ament_package()
13 changes: 8 additions & 5 deletions vectornav/src/vectornav.cc
Original file line number Diff line number Diff line change
Expand Up @@ -363,14 +363,17 @@ class Vectornav : public rclcpp::Node {

// GPS Compass Baseline
// 8.2.3
auto gps_baseline = vs_.readGpsCompassBaseline();
RCLCPP_INFO(get_logger(), "GPS Baseline : (%f, %f, %f), (%f, %f, %f)",
gps_baseline.position[0], gps_baseline.position[1], gps_baseline.position[2],
gps_baseline.uncertainty[0], gps_baseline.uncertainty[1], gps_baseline.uncertainty[2]);
try {
auto gps_baseline = vs_.readGpsCompassBaseline();
RCLCPP_INFO(get_logger(), "GPS Baseline : (%f, %f, %f), (%f, %f, %f)",
gps_baseline.position[0], gps_baseline.position[1], gps_baseline.position[2],
gps_baseline.uncertainty[0], gps_baseline.uncertainty[1], gps_baseline.uncertainty[2]);

} catch (vn::sensors::sensor_error e) {
RCLCPP_ERROR(get_logger(), "readGpsCompassBaseline: %s", e.what());
}
// Register Binary Data Callback
vs_.registerAsyncPacketReceivedHandler(this, Vectornav::AsyncPacketReceivedHandler);

// Connection Successful
return true;
}
Expand Down