From c72e359e6d435a5e54461bc34a061f190bc25b6e Mon Sep 17 00:00:00 2001 From: Kleio Baxevani Date: Fri, 12 Apr 2024 12:05:23 -0400 Subject: [PATCH] Update path to marine_acoustic_msgs --- norbit/CMakeLists.txt | 2 +- norbit/include/norbit/conversions.h | 18 ++++++------ norbit/nodes/norbit_msgs2acoustic_msgs.cpp | 6 ++-- norbit/package.xml | 2 +- norbit/src/conversions.cpp | 34 +++++++++++----------- norbit/src/norbit_connection.cpp | 12 ++++---- 6 files changed, 37 insertions(+), 37 deletions(-) diff --git a/norbit/CMakeLists.txt b/norbit/CMakeLists.txt index 076d267..fa7da34 100644 --- a/norbit/CMakeLists.txt +++ b/norbit/CMakeLists.txt @@ -11,7 +11,7 @@ project(${PACKAGE_NAME}) ## this package name is the name of the directory this ################################ set(ROS_DEPENDS - acoustic_msgs + marine_acoustic_msgs ${PROJECT_NAME}_msgs roscpp std_msgs diff --git a/norbit/include/norbit/conversions.h b/norbit/include/norbit/conversions.h index 792468a..4eaa28f 100644 --- a/norbit/include/norbit/conversions.h +++ b/norbit/include/norbit/conversions.h @@ -2,10 +2,10 @@ #define TYPE_CONVERER_H #include "defs.h" -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -13,13 +13,13 @@ NS_HEAD namespace conversions { /*! - * \brief Converts norbit_msgs::BathymetricStamped to acoustic_msgs::SonarRanges all parameters passed by reference + * \brief Converts norbit_msgs::BathymetricStamped to marine_acoustic_msgs::SonarRanges all parameters passed by reference * \param in the norbit_msgs::BathymetricStamped you want to convert - * \param out the acoustic_msgs::SonarRanges that will be overwritten with the converted Batymetric data + * \param out the marine_acoustic_msgs::SonarRanges that will be overwritten with the converted Batymetric data */ - void bathymetric2SonarRanges(const norbit_msgs::BathymetricStamped & in, acoustic_msgs::SonarRanges & out); - void bathymetric2SonarDetections(const norbit_msgs::BathymetricStamped & in, acoustic_msgs::SonarDetections & out); - void norbitWC2RawSonarImage(const norbit_msgs::WaterColumnStamped & in, acoustic_msgs::RawSonarImage & out); + void bathymetric2SonarRanges(const norbit_msgs::BathymetricStamped & in, marine_acoustic_msgs::SonarRanges & out); + void bathymetric2SonarDetections(const norbit_msgs::BathymetricStamped & in, marine_acoustic_msgs::SonarDetections & out); + void norbitWC2RawSonarImage(const norbit_msgs::WaterColumnStamped & in, marine_acoustic_msgs::RawSonarImage & out); } NS_FOOT diff --git a/norbit/nodes/norbit_msgs2acoustic_msgs.cpp b/norbit/nodes/norbit_msgs2acoustic_msgs.cpp index a38f77d..42cc68b 100644 --- a/norbit/nodes/norbit_msgs2acoustic_msgs.cpp +++ b/norbit/nodes/norbit_msgs2acoustic_msgs.cpp @@ -15,9 +15,9 @@ int main(int argc, char *argv[]) { rosbag::Bag out_bag; out_bag.open(argv[2], rosbag::bagmode::Write); - acoustic_msgs::SonarDetections::Ptr detections_msg(new acoustic_msgs::SonarDetections); - acoustic_msgs::SonarRanges::Ptr ranges_msg(new acoustic_msgs::SonarRanges); - acoustic_msgs::RawSonarImage::Ptr wc_pointer(new acoustic_msgs::RawSonarImage); + marine_acoustic_msgs::SonarDetections::Ptr detections_msg(new marine_acoustic_msgs::SonarDetections); + marine_acoustic_msgs::SonarRanges::Ptr ranges_msg(new marine_acoustic_msgs::SonarRanges); + marine_acoustic_msgs::RawSonarImage::Ptr wc_pointer(new marine_acoustic_msgs::RawSonarImage); for (rosbag::MessageInstance const m: rosbag::View(in_bag)) { norbit_msgs::BathymetricStamped::ConstPtr i = m.instantiate(); diff --git a/norbit/package.xml b/norbit/package.xml index 7201f00..c81ff59 100644 --- a/norbit/package.xml +++ b/norbit/package.xml @@ -20,7 +20,7 @@ message_generation message_runtime - acoustic_msgs + marine_acoustic_msgs roscpp std_msgs pcl_conversions diff --git a/norbit/src/conversions.cpp b/norbit/src/conversions.cpp index 15ef85c..b91faa5 100644 --- a/norbit/src/conversions.cpp +++ b/norbit/src/conversions.cpp @@ -5,7 +5,7 @@ NS_HEAD namespace conversions { void bathymetric2SonarRanges(const norbit_msgs::BathymetricStamped & in, - acoustic_msgs::SonarRanges & out) { + marine_acoustic_msgs::SonarRanges & out) { auto num_beams = in.bathy.bathymetric_header.N; out.header = in.header; @@ -26,9 +26,9 @@ namespace conversions { for (size_t i = 0; i < num_beams; i++) { if (in.bathy.detections[i].quality_flag == 3) { - out.flags[i].flag = acoustic_msgs::DetectionFlag::DETECT_OK; + out.flags[i].flag = marine_acoustic_msgs::DetectionFlag::DETECT_OK; } else { - out.flags[i].flag = acoustic_msgs::DetectionFlag::DETECT_BAD_SONAR; + out.flags[i].flag = marine_acoustic_msgs::DetectionFlag::DETECT_BAD_SONAR; } out.transmit_delays[i] = 0; out.intensities[i] = in.bathy.detections[i].intensity; @@ -46,7 +46,7 @@ namespace conversions { } void bathymetric2SonarDetections(const norbit_msgs::BathymetricStamped & in, - acoustic_msgs::SonarDetections & out) { + marine_acoustic_msgs::SonarDetections & out) { auto num_beams = in.bathy.bathymetric_header.N; out.header = in.header; @@ -64,9 +64,9 @@ namespace conversions { out.rx_angles.resize(num_beams); for (size_t i = 0; i < num_beams; i++) { if (in.bathy.detections[i].quality_flag == 3) { - out.flags[i].flag = acoustic_msgs::DetectionFlag::DETECT_OK; + out.flags[i].flag = marine_acoustic_msgs::DetectionFlag::DETECT_OK; } else { - out.flags[i].flag = acoustic_msgs::DetectionFlag::DETECT_BAD_SONAR; + out.flags[i].flag = marine_acoustic_msgs::DetectionFlag::DETECT_BAD_SONAR; } out.two_way_travel_times[i] = in.bathy.detections[i].sample_number / in.bathy.bathymetric_header.sample_rate; @@ -81,7 +81,7 @@ namespace conversions { } void norbitWC2RawSonarImage(const norbit_msgs::WaterColumnStamped & in, - acoustic_msgs::RawSonarImage & out) { + marine_acoustic_msgs::RawSonarImage & out) { auto num_beams = in.water_column.water_column_header.N; // Number of beams auto num_samples = in.water_column.water_column_header.M; // Number of samples in each beam @@ -114,34 +114,34 @@ namespace conversions { out.image.is_bigendian = false; switch (in.water_column.water_column_header.dtype) { case norbit_msgs::WaterColumnHeader::DTYPE_UINT8: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_UINT8; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_UINT8; break; case norbit_msgs::WaterColumnHeader::DTYPE_INT8: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_INT8; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_INT8; break; case norbit_msgs::WaterColumnHeader::DTYPE_UINT16: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_UINT16; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_UINT16; break; case norbit_msgs::WaterColumnHeader::DTYPE_INT16: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_INT16; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_INT16; break; case norbit_msgs::WaterColumnHeader::DTYPE_UINT32: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_UINT32; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_UINT32; break; case norbit_msgs::WaterColumnHeader::DTYPE_INT32: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_INT32; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_INT32; break; case norbit_msgs::WaterColumnHeader::DTYPE_UINT64: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_UINT64; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_UINT64; break; case norbit_msgs::WaterColumnHeader::DTYPE_INT64: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_INT64; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_INT64; break; case norbit_msgs::WaterColumnHeader::DTYPE_FLOAT32: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_FLOAT32; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_FLOAT32; break; case norbit_msgs::WaterColumnHeader::DTYPE_FLOAT64: - out.image.dtype = acoustic_msgs::SonarImageData::DTYPE_FLOAT64; + out.image.dtype = marine_acoustic_msgs::SonarImageData::DTYPE_FLOAT64; break; } //out.image.dtype = in.water_column.water_column_header.dtype; diff --git a/norbit/src/norbit_connection.cpp b/norbit/src/norbit_connection.cpp index 35bcff9..72a2d05 100644 --- a/norbit/src/norbit_connection.cpp +++ b/norbit/src/norbit_connection.cpp @@ -59,12 +59,12 @@ void NorbitConnection::setupPubSub() { } if (params_.pubDetections()){ - detect_pub_ = node_.advertise( + detect_pub_ = node_.advertise( params_.detections_topic,1); } if (params_.pubRanges()) { - ranges_pub_ = node_.advertise(params_.ranges_topic, 1); + ranges_pub_ = node_.advertise(params_.ranges_topic, 1); } if (params_.pubBathymetric()){ @@ -78,7 +78,7 @@ void NorbitConnection::setupPubSub() { } if(params_.pubMultibeamWC()){ - wc_pub_ = node_.advertise( + wc_pub_ = node_.advertise( params_.watercolumn_topic, 1); } @@ -332,13 +332,13 @@ void NorbitConnection::bathyCallback(norbit_types::BathymetricData data) { } if (params_.pubDetections()) { - acoustic_msgs::SonarDetections detections_msg; + marine_acoustic_msgs::SonarDetections detections_msg; norbit::conversions::bathymetric2SonarDetections(bathy_msg, detections_msg); detect_pub_.publish(detections_msg); } if (params_.pubRanges()) { - acoustic_msgs::SonarRanges ranges_msg; + marine_acoustic_msgs::SonarRanges ranges_msg; norbit::conversions::bathymetric2SonarRanges(bathy_msg, ranges_msg); ranges_pub_.publish(ranges_msg); } @@ -352,7 +352,7 @@ void NorbitConnection::wcCallback(norbit_types::WaterColumnData data){ norbit_wc_pub_.publish(norb_wc_msg); if(params_.pubMultibeamWC()){ - acoustic_msgs::RawSonarImage::Ptr hydro_wc_msg(new acoustic_msgs::RawSonarImage); + marine_acoustic_msgs::RawSonarImage::Ptr hydro_wc_msg(new marine_acoustic_msgs::RawSonarImage); norbit::conversions::norbitWC2RawSonarImage(norb_wc_msg, *hydro_wc_msg); wc_pub_.publish(hydro_wc_msg); }