Skip to content

Commit

Permalink
Remove AIS Ships from Local Transceiver
Browse files Browse the repository at this point in the history
  • Loading branch information
Jng468 committed Jan 18, 2025
1 parent af15740 commit 840fe26
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 34 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
#include "at_cmds.h"
#include "boost/asio/io_service.hpp"
#include "boost/asio/serial_port.hpp"
#include "custom_interfaces/msg/ais_ships.hpp"
#include "custom_interfaces/msg/batteries.hpp"
#include "custom_interfaces/msg/generic_sensors.hpp"
#include "custom_interfaces/msg/gps.hpp"
Expand Down Expand Up @@ -34,13 +33,6 @@ class LocalTransceiver
*/
void updateSensor(msg::GPS gps);

/**
* @brief Update the sensor with new AIS Ships data
*
* @param ships custom_interfaces AISShips object
*/
void updateSensor(msg::AISShips ships);

/**
* @brief Update the sensor with new Wind sensor data
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
#include <boost/asio/streambuf.hpp>
#include <boost/asio/write.hpp>
#include <boost/system/error_code.hpp>
#include <custom_interfaces/msg/ais_ships.hpp>
#include <custom_interfaces/msg/batteries.hpp>
#include <custom_interfaces/msg/generic_sensors.hpp>
#include <custom_interfaces/msg/gps.hpp>
Expand Down Expand Up @@ -37,22 +36,6 @@ void LocalTransceiver::updateSensor(msg::GPS gps)
sensors_.mutable_gps()->set_speed(gps.speed.speed);
}

void LocalTransceiver::updateSensor(msg::AISShips ships)
{
sensors_.clear_ais_ships();
for (const msg::HelperAISShip & ship : ships.ships) {
Sensors::Ais * new_ship = sensors_.add_ais_ships();
new_ship->set_id(ship.id);
new_ship->set_cog(ship.cog.heading);
new_ship->set_latitude(ship.lat_lon.latitude);
new_ship->set_longitude(ship.lat_lon.longitude);
new_ship->set_sog(ship.sog.speed);
new_ship->set_rot(ship.rot.rot);
new_ship->set_width(ship.width.dimension);
new_ship->set_length(ship.length.dimension);
}
}

void LocalTransceiver::updateSensor(msg::WindSensors wind)
{
sensors_.clear_wind_sensors();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,9 +71,6 @@ class LocalTransceiverIntf : public NetNode
sub_data_sensors = this->create_subscription<custom_interfaces::msg::GenericSensors>(
ros_topics::DATA_SENSORS, ROS_Q_SIZE,
std::bind(&LocalTransceiverIntf::sub_data_sensors_cb, this, std::placeholders::_1));
sub_ais_ships = this->create_subscription<custom_interfaces::msg::AISShips>(
ros_topics::AIS_SHIPS, ROS_Q_SIZE,
std::bind(&LocalTransceiverIntf::sub_ais_ships_cb, this, std::placeholders::_1));
sub_gps = this->create_subscription<custom_interfaces::msg::GPS>(
ros_topics::GPS, ROS_Q_SIZE, std::bind(&LocalTransceiverIntf::sub_gps_cb, this, std::placeholders::_1));
sub_local_path_data = this->create_subscription<custom_interfaces::msg::LPathData>(
Expand All @@ -90,7 +87,6 @@ class LocalTransceiverIntf : public NetNode
rclcpp::Subscription<custom_interfaces::msg::WindSensors>::SharedPtr sub_wind_sensor;
rclcpp::Subscription<custom_interfaces::msg::Batteries>::SharedPtr sub_batteries;
rclcpp::Subscription<custom_interfaces::msg::GenericSensors>::SharedPtr sub_data_sensors;
rclcpp::Subscription<custom_interfaces::msg::AISShips>::SharedPtr sub_ais_ships;
rclcpp::Subscription<custom_interfaces::msg::GPS>::SharedPtr sub_gps;
rclcpp::Subscription<custom_interfaces::msg::LPathData>::SharedPtr sub_local_path_data;

Expand Down Expand Up @@ -119,11 +115,6 @@ class LocalTransceiverIntf : public NetNode
*/
void sub_data_sensors_cb(custom_interfaces::msg::GenericSensors in_msg) { lcl_trns_->updateSensor(in_msg); }

/**
* @brief Callback function to subscribe to the onboard ROS network for ais ships
*/
void sub_ais_ships_cb(custom_interfaces::msg::AISShips in_msg) { lcl_trns_->updateSensor(in_msg); }

/**
* @brief Callback function to subscribe to the onboard ROS network for GPS
*/
Expand Down

0 comments on commit 840fe26

Please sign in to comment.