diff --git a/CMakeLists.txt b/CMakeLists.txt index 80a3672..03218b0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -19,7 +19,7 @@ set(ROS_DEPENDS tf2_ros tf2_msgs tf2_sensor_msgs - acoustic_msgs + marine_acoustic_msgs ) # if you end up using external dependencies it be a bit more manual (it's not that bad don't worry) diff --git a/README.md b/README.md index f22b8ba..f66aca5 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # acoustic_msgs_tools -This is a set of tools designed to view, debug and process the acoustic_msgs defined in https://github.com/apl-ocean-engineering/hydrographic_msgs +This is a set of tools designed to view, debug and process the marine_acoustic_msgs defined in https://github.com/apl-ocean-engineering/marine_msgs Currently it contains: diff --git a/include/acoustic_msgs_tools/water_column_view.h b/include/acoustic_msgs_tools/water_column_view.h index 26a4884..2ebbdc3 100644 --- a/include/acoustic_msgs_tools/water_column_view.h +++ b/include/acoustic_msgs_tools/water_column_view.h @@ -4,7 +4,7 @@ #include #include "qcustomplot.h" #include -#include +#include #include #include "libInterpolate/Interpolate.hpp" #include "ros/master.h" @@ -22,7 +22,7 @@ class WaterColumnView : public QWidget ~WaterColumnView(); void setupSignals(); - void wcCallback(const acoustic_msgs::RawSonarImage::ConstPtr& wc_msg); + void wcCallback(const marine_acoustic_msgs::RawSonarImage::ConstPtr& wc_msg); private slots: void spinOnce(); void updateRangeBearing(QMouseEvent *event); diff --git a/package.xml b/package.xml index 8103aa7..ec91a7c 100644 --- a/package.xml +++ b/package.xml @@ -24,7 +24,7 @@ std_msgs pcl_conversions pcl_ros - acoustic_msgs + marine_acoustic_msgs tf2 tf2_ros tf2_msgs diff --git a/src/water_column_view.cpp b/src/water_column_view.cpp index b52906f..0a303eb 100644 --- a/src/water_column_view.cpp +++ b/src/water_column_view.cpp @@ -32,21 +32,21 @@ void WaterColumnView::setupSignals(){ this,SLOT(updateRangeBearing(QMouseEvent*))); } -double getRange(const acoustic_msgs::RawSonarImage::ConstPtr &wc_msg, size_t sample_number){ +double getRange(const marine_acoustic_msgs::RawSonarImage::ConstPtr &wc_msg, size_t sample_number){ double range = double(sample_number) * wc_msg->ping_info.sound_speed / (2.0 * wc_msg->sample_rate); return range; } -int getSampleNo(const acoustic_msgs::RawSonarImage::ConstPtr &wc_msg, double range){ +int getSampleNo(const marine_acoustic_msgs::RawSonarImage::ConstPtr &wc_msg, double range){ double scale = (2.0 * wc_msg->sample_rate) / wc_msg->ping_info.sound_speed; int sample_no = range * scale; return sample_no; } -double rowMajor(const acoustic_msgs::RawSonarImage::ConstPtr &wc_msg, double beam_idx, double sample_idx){ +double rowMajor(const marine_acoustic_msgs::RawSonarImage::ConstPtr &wc_msg, double beam_idx, double sample_idx){ beam_idx = beam_idx + 0.5 - (beam_idx<0); sample_idx = sample_idx + 0.5 - (sample_idx<0); @@ -59,25 +59,25 @@ double rowMajor(const acoustic_msgs::RawSonarImage::ConstPtr &wc_msg, double be return 0.0; }else { switch( wc_msg->image.dtype){ - case acoustic_msgs::SonarImageData::DTYPE_UINT8: + case marine_acoustic_msgs::SonarImageData::DTYPE_UINT8: return reinterpret_cast(wc_msg->image.data.data())[index]; - case acoustic_msgs::SonarImageData::DTYPE_INT8: + case marine_acoustic_msgs::SonarImageData::DTYPE_INT8: return reinterpret_cast(wc_msg->image.data.data())[index]; - case acoustic_msgs::SonarImageData::DTYPE_UINT16: + case marine_acoustic_msgs::SonarImageData::DTYPE_UINT16: return reinterpret_cast(wc_msg->image.data.data())[index]; - case acoustic_msgs::SonarImageData::DTYPE_INT16: + case marine_acoustic_msgs::SonarImageData::DTYPE_INT16: return reinterpret_cast(wc_msg->image.data.data())[index]; - case acoustic_msgs::SonarImageData::DTYPE_UINT32: + case marine_acoustic_msgs::SonarImageData::DTYPE_UINT32: return reinterpret_cast(wc_msg->image.data.data())[index]; - case acoustic_msgs::SonarImageData::DTYPE_INT32: + case marine_acoustic_msgs::SonarImageData::DTYPE_INT32: return reinterpret_cast(wc_msg->image.data.data())[index]; - case acoustic_msgs::SonarImageData::DTYPE_UINT64: + case marine_acoustic_msgs::SonarImageData::DTYPE_UINT64: return reinterpret_cast(wc_msg->image.data.data())[index]; - case acoustic_msgs::SonarImageData::DTYPE_INT64: + case marine_acoustic_msgs::SonarImageData::DTYPE_INT64: return reinterpret_cast(wc_msg->image.data.data())[index]; - case acoustic_msgs::SonarImageData::DTYPE_FLOAT32: + case marine_acoustic_msgs::SonarImageData::DTYPE_FLOAT32: return reinterpret_cast(wc_msg->image.data.data())[index]; - case acoustic_msgs::SonarImageData::DTYPE_FLOAT64: + case marine_acoustic_msgs::SonarImageData::DTYPE_FLOAT64: return reinterpret_cast(wc_msg->image.data.data())[index]; default: return std::nan(""); // unknown data type @@ -85,7 +85,7 @@ double rowMajor(const acoustic_msgs::RawSonarImage::ConstPtr &wc_msg, double be } } -double getVal(const acoustic_msgs::RawSonarImage::ConstPtr &wc_msg,_1D::LinearInterpolator beam_idx_interp, double x, double y){ +double getVal(const marine_acoustic_msgs::RawSonarImage::ConstPtr &wc_msg,_1D::LinearInterpolator beam_idx_interp, double x, double y){ auto angle = atan2(x,y); @@ -121,7 +121,7 @@ double getVal(const acoustic_msgs::RawSonarImage::ConstPtr &wc_msg,_1D::LinearIn -void WaterColumnView::wcCallback(const acoustic_msgs::RawSonarImage::ConstPtr &wc_msg){ +void WaterColumnView::wcCallback(const marine_acoustic_msgs::RawSonarImage::ConstPtr &wc_msg){ auto M = wc_msg->samples_per_beam; auto N = wc_msg->rx_angles.size(); @@ -202,7 +202,7 @@ void WaterColumnView::spinOnce(){ void WaterColumnView::on_wc_topic_currentIndexChanged(const QString &arg1) { if(wc_sub_.getTopic() != arg1.toStdString()){ - wc_sub_ = nh_->subscribe(arg1.toStdString(), 1, &WaterColumnView::wcCallback, this); + wc_sub_ = nh_->subscribe(arg1.toStdString(), 1, &WaterColumnView::wcCallback, this); new_msg = true; } } @@ -242,7 +242,7 @@ void WaterColumnView::updateTopics(){ ui->wc_topic->clear(); QStringList topic_list; for(auto topic : master_topics){ - if(topic.datatype=="acoustic_msgs/RawSonarImage"){ + if(topic.datatype=="marine_acoustic_msgs/RawSonarImage"){ QString::fromStdString(topic.name); topic_list.push_back(QString::fromStdString(topic.name)); }