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

Update to marine_acoustic_msgs. #3

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
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
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -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:

Expand Down
4 changes: 2 additions & 2 deletions include/acoustic_msgs_tools/water_column_view.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <QWidget>
#include "qcustomplot.h"
#include <ros/ros.h>
#include <acoustic_msgs/RawSonarImage.h>
#include <marine_acoustic_msgs/RawSonarImage.h>
#include <qtimer.h>
#include "libInterpolate/Interpolate.hpp"
#include "ros/master.h"
Expand All @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
<depend>std_msgs</depend>
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
<depend>acoustic_msgs</depend>
<depend>marine_acoustic_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tf2_msgs</depend>
Expand Down
34 changes: 17 additions & 17 deletions src/water_column_view.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -59,33 +59,33 @@ 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<const uint8_t*>(wc_msg->image.data.data())[index];
case acoustic_msgs::SonarImageData::DTYPE_INT8:
case marine_acoustic_msgs::SonarImageData::DTYPE_INT8:
return reinterpret_cast<const int8_t*>(wc_msg->image.data.data())[index];
case acoustic_msgs::SonarImageData::DTYPE_UINT16:
case marine_acoustic_msgs::SonarImageData::DTYPE_UINT16:
return reinterpret_cast<const uint16_t*>(wc_msg->image.data.data())[index];
case acoustic_msgs::SonarImageData::DTYPE_INT16:
case marine_acoustic_msgs::SonarImageData::DTYPE_INT16:
return reinterpret_cast<const int16_t*>(wc_msg->image.data.data())[index];
case acoustic_msgs::SonarImageData::DTYPE_UINT32:
case marine_acoustic_msgs::SonarImageData::DTYPE_UINT32:
return reinterpret_cast<const uint32_t*>(wc_msg->image.data.data())[index];
case acoustic_msgs::SonarImageData::DTYPE_INT32:
case marine_acoustic_msgs::SonarImageData::DTYPE_INT32:
return reinterpret_cast<const int32_t*>(wc_msg->image.data.data())[index];
case acoustic_msgs::SonarImageData::DTYPE_UINT64:
case marine_acoustic_msgs::SonarImageData::DTYPE_UINT64:
return reinterpret_cast<const uint64_t*>(wc_msg->image.data.data())[index];
case acoustic_msgs::SonarImageData::DTYPE_INT64:
case marine_acoustic_msgs::SonarImageData::DTYPE_INT64:
return reinterpret_cast<const int64_t*>(wc_msg->image.data.data())[index];
case acoustic_msgs::SonarImageData::DTYPE_FLOAT32:
case marine_acoustic_msgs::SonarImageData::DTYPE_FLOAT32:
return reinterpret_cast<const float*>(wc_msg->image.data.data())[index];
case acoustic_msgs::SonarImageData::DTYPE_FLOAT64:
case marine_acoustic_msgs::SonarImageData::DTYPE_FLOAT64:
return reinterpret_cast<const double*>(wc_msg->image.data.data())[index];
default:
return std::nan(""); // unknown data type
}
}
}

double getVal(const acoustic_msgs::RawSonarImage::ConstPtr &wc_msg,_1D::LinearInterpolator<double> beam_idx_interp, double x, double y){
double getVal(const marine_acoustic_msgs::RawSonarImage::ConstPtr &wc_msg,_1D::LinearInterpolator<double> beam_idx_interp, double x, double y){


auto angle = atan2(x,y);
Expand Down Expand Up @@ -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();

Expand Down Expand Up @@ -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<acoustic_msgs::RawSonarImage>(arg1.toStdString(), 1, &WaterColumnView::wcCallback, this);
wc_sub_ = nh_->subscribe<marine_acoustic_msgs::RawSonarImage>(arg1.toStdString(), 1, &WaterColumnView::wcCallback, this);
new_msg = true;
}
}
Expand Down Expand Up @@ -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));
}
Expand Down