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 path to marine_acoustic_msgs #9

Open
wants to merge 1 commit into
base: master
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 norbit/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
18 changes: 9 additions & 9 deletions norbit/include/norbit/conversions.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,24 +2,24 @@
#define TYPE_CONVERER_H

#include "defs.h"
#include <acoustic_msgs/DetectionFlag.h>
#include <acoustic_msgs/RawSonarImage.h>
#include <acoustic_msgs/SonarRanges.h>
#include <acoustic_msgs/SonarDetections.h>
#include <marine_acoustic_msgs/DetectionFlag.h>
#include <marine_acoustic_msgs/RawSonarImage.h>
#include <marine_acoustic_msgs/SonarRanges.h>
#include <marine_acoustic_msgs/SonarDetections.h>

#include <norbit_msgs/BathymetricStamped.h>
#include <norbit_msgs/WaterColumnStamped.h>

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

Expand Down
6 changes: 3 additions & 3 deletions norbit/nodes/norbit_msgs2acoustic_msgs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<norbit_msgs::BathymetricStamped>();
Expand Down
2 changes: 1 addition & 1 deletion norbit/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>

<depend>acoustic_msgs</depend>
<depend>marine_acoustic_msgs</depend>
<depend>roscpp</depend>
<depend>std_msgs</depend>
<depend>pcl_conversions</depend>
Expand Down
34 changes: 17 additions & 17 deletions norbit/src/conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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;
Expand All @@ -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;
Expand All @@ -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;
Expand All @@ -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

Expand Down Expand Up @@ -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;
Expand Down
12 changes: 6 additions & 6 deletions norbit/src/norbit_connection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,12 +59,12 @@ void NorbitConnection::setupPubSub() {
}

if (params_.pubDetections()){
detect_pub_ = node_.advertise<acoustic_msgs::SonarDetections>(
detect_pub_ = node_.advertise<marine_acoustic_msgs::SonarDetections>(
params_.detections_topic,1);
}

if (params_.pubRanges()) {
ranges_pub_ = node_.advertise<acoustic_msgs::SonarRanges>(params_.ranges_topic, 1);
ranges_pub_ = node_.advertise<marine_acoustic_msgs::SonarRanges>(params_.ranges_topic, 1);
}

if (params_.pubBathymetric()){
Expand All @@ -78,7 +78,7 @@ void NorbitConnection::setupPubSub() {
}

if(params_.pubMultibeamWC()){
wc_pub_ = node_.advertise<acoustic_msgs::RawSonarImage>(
wc_pub_ = node_.advertise<marine_acoustic_msgs::RawSonarImage>(
params_.watercolumn_topic, 1);
}

Expand Down Expand Up @@ -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);
}
Expand All @@ -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);
}
Expand Down