Skip to content

Commit

Permalink
[NET] Local Transceiver: ROS modes and config file (#343)
Browse files Browse the repository at this point in the history
* Added modes and config file for Local Transceiver

* Fixed error with spacing

* Adjust comments

---------

Co-authored-by: hhenry01 <henryhuang2001@gmail.com>
  • Loading branch information
Jng468 and hhenry01 authored Mar 23, 2024
1 parent e2b3672 commit 092d097
Show file tree
Hide file tree
Showing 3 changed files with 105 additions and 68 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# Template for the local_transceiver module
local_transceiver_node:
ros__parameters:
enabled: true
# The following parameters are optional. Defaults are set in local_transceiver_ros_intf.cpp
port: # String: Serial port that the Local Transceiver will use (default: /tmp/local_transceiver_test_port)
32 changes: 32 additions & 0 deletions src/network_systems/launch/main_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,7 @@ def setup_launch(context: LaunchContext) -> List[Node]:
launch_description_entities.append(get_mock_ais_description(context))
launch_description_entities.append(get_can_transceiver_description(context))
launch_description_entities.append(get_remote_transceiver_description(context))
launch_description_entities.append(get_local_transceiver_description(context))
return launch_description_entities


Expand Down Expand Up @@ -215,3 +216,34 @@ def get_remote_transceiver_description(context: LaunchContext) -> Node:
)

return node


def get_local_transceiver_description(context: LaunchContext) -> Node:
"""Gets the launch description for the local_transceiver_node.
Args:
context (LaunchContext): The current launch context.
Returns:
Node: The node object that launches the local_transceiver_node.
"""
node_name = "local_transceiver_node"
ros_parameters = [
global_launch_config,
{"mode": LaunchConfiguration("mode")},
*LaunchConfiguration("config").perform(context).split(","),
]
ros_arguments: List[SomeSubstitutionsType] = [
"--log-level",
[f"{node_name}:=", LaunchConfiguration("log_level")],
]
node = Node(
package=PACKAGE_NAME,
namespace=NAMESPACE,
executable="local_transceiver",
name=node_name,
parameters=ros_parameters,
ros_arguments=ros_arguments,
)

return node
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
#include "net_node.h"

/**
* Local Transceiver Interface Node
* @brief Connect the Local Transceiver to the ROS network
*
*/
class LocalTransceiverIntf : public NetNode
Expand All @@ -24,40 +24,67 @@ class LocalTransceiverIntf : public NetNode
*
* @param lcl_trns Local Transceiver instance
*/
explicit LocalTransceiverIntf(std::shared_ptr<LocalTransceiver> lcl_trns)
: NetNode(ros_nodes::LOCAL_TRANSCEIVER), lcl_trns_(lcl_trns)
explicit LocalTransceiverIntf() : NetNode("local_transceiver_node")

{
static constexpr int ROS_Q_SIZE = 5;
static constexpr auto TIMER_INTERVAL = std::chrono::milliseconds(500);
timer_ = this->create_wall_timer(TIMER_INTERVAL, std::bind(&LocalTransceiverIntf::pub_cb, this));
pub_ = this->create_publisher<custom_interfaces::msg::Path>(ros_topics::GLOBAL_PATH, ROS_Q_SIZE);

// subscriber nodes
sub_wind_sensor = this->create_subscription<custom_interfaces::msg::WindSensors>(
ros_topics::WIND_SENSORS, ROS_Q_SIZE,
std::bind(&LocalTransceiverIntf::sub_wind_sensor_cb, this, std::placeholders::_1));
sub_batteries = this->create_subscription<custom_interfaces::msg::Batteries>(
ros_topics::BATTERIES, ROS_Q_SIZE,
std::bind(&LocalTransceiverIntf::sub_batteries_cb, this, std::placeholders::_1));
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>(
ros_topics::LOCAL_PATH, ROS_Q_SIZE,
std::bind(&LocalTransceiverIntf::sub_local_path_data_cb, this, std::placeholders::_1));
this->declare_parameter("enabled", true);
bool enabled_ = this->get_parameter("enabled").as_bool();

if (!enabled_) {
RCLCPP_INFO(this->get_logger(), "Local Transceiver is DISABLED");
} else {
this->declare_parameter("mode", SYSTEM_MODE::DEV);

rclcpp::Parameter mode_param = this->get_parameter("mode");
std::string mode = mode_param.as_string();
std::string default_port;

if (mode == SYSTEM_MODE::PROD) {
//TODO(Jng468) placeholder
} else if (mode == SYSTEM_MODE::DEV) {
default_port = LOCAL_TRANSCEIVER_TEST_PORT;
} else {
std::string msg = "Error, invalid system mode" + mode;
throw std::runtime_error(msg);
}

this->declare_parameter("port", default_port);
rclcpp::Parameter default_port_parm = this->get_parameter("port");
std::string port = default_port_parm.as_string();

RCLCPP_INFO(
this->get_logger(), "Running Local Transceiver in mode: %s, with port: %s.", mode.c_str(), port.c_str());
lcl_trns_ = std::make_unique<LocalTransceiver>(port, SATELLITE_BAUD_RATE);

static constexpr int ROS_Q_SIZE = 5;
static constexpr auto TIMER_INTERVAL = std::chrono::milliseconds(500);
timer_ = this->create_wall_timer(TIMER_INTERVAL, std::bind(&LocalTransceiverIntf::pub_cb, this));
pub_ = this->create_publisher<custom_interfaces::msg::Path>(ros_topics::GLOBAL_PATH, ROS_Q_SIZE);

// subscriber nodes
sub_wind_sensor = this->create_subscription<custom_interfaces::msg::WindSensors>(
ros_topics::WIND_SENSORS, ROS_Q_SIZE,
std::bind(&LocalTransceiverIntf::sub_wind_sensor_cb, this, std::placeholders::_1));
sub_batteries = this->create_subscription<custom_interfaces::msg::Batteries>(
ros_topics::BATTERIES, ROS_Q_SIZE,
std::bind(&LocalTransceiverIntf::sub_batteries_cb, this, std::placeholders::_1));
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>(
ros_topics::LOCAL_PATH, ROS_Q_SIZE,
std::bind(&LocalTransceiverIntf::sub_local_path_data_cb, this, std::placeholders::_1));
}
}

private:
// Local Transceiver instance
std::shared_ptr<LocalTransceiver> lcl_trns_;
// Publishing timer
rclcpp::TimerBase::SharedPtr timer_;
// String is a placeholder pub and sub msg type - we will definitely define custom message types
std::unique_ptr<LocalTransceiver> lcl_trns_; // Local Transceiver instance
rclcpp::TimerBase::SharedPtr timer_; // Publishing timer
rclcpp::Publisher<custom_interfaces::msg::Path>::SharedPtr pub_;

rclcpp::Subscription<custom_interfaces::msg::WindSensors>::SharedPtr sub_wind_sensor;
Expand All @@ -71,73 +98,45 @@ class LocalTransceiverIntf : public NetNode
* @brief Callback function to publish to onboard ROS network
*
*/
void pub_cb(/*place*/)
void pub_cb(/*placeholder*/)
{
// TODO(Jng468): complete, after receive is done
// std::string recent_data = lcl_trns_->receive(); //receives most recent data from remote server
// auto msg = custom_interfaces::msg::Path();
// pub_->publish(msg);
// TODO(Jng468): complete this, after receive is done
}

/**
* @brief Callback function to subscribe to the onboard ROS network for wind sensors
*/
void sub_wind_sensor_cb(custom_interfaces::msg::WindSensors in_msg)
{
custom_interfaces::msg::WindSensors data = in_msg;
lcl_trns_->updateSensor(data);
}
void sub_wind_sensor_cb(custom_interfaces::msg::WindSensors in_msg) { lcl_trns_->updateSensor(in_msg); }

/**
* @brief Callback function to subscribe to the onboard ROS network for batteries
*/
void sub_batteries_cb(custom_interfaces::msg::Batteries in_msg)
{
custom_interfaces::msg::Batteries data = in_msg;
lcl_trns_->updateSensor(data);
}
void sub_batteries_cb(custom_interfaces::msg::Batteries in_msg) { lcl_trns_->updateSensor(in_msg); }

/**
* @brief Callback function to subscribe to the onboard ROS network for generic sensors
*/
void sub_data_sensors_cb(custom_interfaces::msg::GenericSensors in_msg)
{
custom_interfaces::msg::GenericSensors data = in_msg;
lcl_trns_->updateSensor(data);
}
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)
{
custom_interfaces::msg::AISShips data = in_msg;
lcl_trns_->updateSensor(data);
}
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
*/
void sub_gps_cb(custom_interfaces::msg::GPS in_msg)
{
custom_interfaces::msg::GPS data = in_msg;
lcl_trns_->updateSensor(data);
}
void sub_gps_cb(custom_interfaces::msg::GPS in_msg) { lcl_trns_->updateSensor(in_msg); }

void sub_local_path_data_cb(custom_interfaces::msg::LPathData in_msg)
{
custom_interfaces::msg::LPathData data = in_msg;
lcl_trns_->updateSensor(data);
}
void sub_local_path_data_cb(custom_interfaces::msg::LPathData in_msg) { lcl_trns_->updateSensor(in_msg); }
};

int main(int argc, char * argv[])
{
bool err = false;
rclcpp::init(argc, argv);
std::shared_ptr<LocalTransceiver> lcl_trns = std::make_shared<LocalTransceiver>("PLACEHOLDER", SATELLITE_BAUD_RATE);
try {
std::shared_ptr<LocalTransceiverIntf> node = std::make_shared<LocalTransceiverIntf>(lcl_trns);
std::shared_ptr<LocalTransceiverIntf> node = std::make_shared<LocalTransceiverIntf>();
try {
rclcpp::spin(node);
} catch (std::exception & e) {
Expand Down

0 comments on commit 092d097

Please sign in to comment.