Documentation and Videos

mu-Net Software Tutorials

Demo Videos

ROS Aqua-Net Demo

MOOS Aqua-Net Demo

Source Code

Appendix A. ROS-aquanet-adapter source code: start.cpp program

// This program initializes the aquanet stack of protocols and
// creates outbound/inbound topics for passing the data over aquanet
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <std_msgs/String.h>
#include <iomanip> // for std::setprecision and std::fixed

// Socket communication
#include<stdlib.h> //exit(0);
#include<arpa/inet.h>
#include<sys/socket.h>
#include <iostream>
#include <sstream>
#include <limits>
// thread-related stuff
#include <thread>
// Aqua-sockets
#include <sys/un.h>
#include "aquanet_include/aquanet_log.h"
#include "aquanet_include/aquanet_socket.h"
char log_file[BUFSIZE];
char* log_file_name = log_file;

// Define inbound and outbound topics for communication over aquanet-enabled nodes
std::string inbound_topic = "aquanet_inbound";
std::string outbound_topic = "aquanet_outbound";

ros::Publisher aquanet_inbound_publisher;

// Aquanet socket
int m_socket = -1;
struct sockaddr_aquanet m_to_addr;

// Store values from ROS-twist message and send them over aqua-socket
struct aqua_message
{
  double angular_value;
  double linear_value;
};

// A callback function. Executed each time a new velocity message arrives
void velMessageReceived(const geometry_msgs::Twist::ConstPtr& vel)
{
    ROS_INFO_STREAM(std::setprecision(2) << std::fixed << "position=(" << vel->linear.x << "," << vel->linear.y << ")" << " angle=" << vel->angular.z);

    // Send message to aqua-socket
    aqua_message values;
    values.angular_value = vel->angular.z;
    values.linear_value = vel->linear.x;

    // Send message via socket
    if (aqua_sendto(m_socket, &values, sizeof(values), 0, (struct sockaddr *) & m_to_addr, sizeof (m_to_addr)) < 0) {
        printf("failed to send to the socket");
        perror("m_socket closed");
        exit(1);
    }
}

// Receive thread
void receiveAqua(int recv_socket)
{
    struct sockaddr_aquanet remote_addr;
    int addr_size = sizeof (remote_addr);
    aqua_message received_values;
    int out_value = 0;
    while (true)
    {
        out_value = aqua_recvfrom(m_socket, &received_values, sizeof(received_values), 0, (struct sockaddr *) & remote_addr, &addr_size);
        if (out_value < 0) {
            printf(log_file_name, "failed to read from aqua_socket");
            break;
        }
        else if (out_value == 0)
        {
            // nothing was received during the socket timeout
            printf("socket timeout\n");
            continue;
        }

        // printf("Received packet from %s:%d\n", inet_ntoa(si_other.sin_addr), ntohs(si_other.sin_port));
        printf("Angular: %f\n" , received_values.angular_value);
        printf("Linear: %f\n" , received_values.linear_value);
        printf("--------------------\n");

        // Publish the messsages to the inbound topic
        geometry_msgs::Twist twist;
        twist.angular.z = 1.0*received_values.angular_value;
        twist.linear.x = 1.0*received_values.linear_value;
        aquanet_inbound_publisher.publish(twist);
    }
}

int main(int argc, char **argv)
{
    // Start aquanet stack
    system("cd /home/ubuntu/ros_catkin_ws/src/aquanet_adapter/aquanet_scripts && ./run_aquanet.sh");

    // Initialize the ROS system and become a node.
    ros::init(argc, argv, "aquanet_node");
    ros::NodeHandle nh;

    // Create socket
    if ((m_socket = aqua_socket(AF_AQUANET, SOCK_AQUANET, 0)) < 0) {
        printf("socket creation failed\n");
        perror("m_socket closed");
        exit(1);
    }

    // struct sockaddr_aquanet to_addr;
    m_to_addr.sin_family = AF_AQUANET;
    m_to_addr.sin_addr.s_addr = 1;
    m_to_addr.sin_addr.d_addr = 2;

    // Create a subscriber object.
    ros::Subscriber sub = nh.subscribe("aquanet_outbound/", 1, &velMessageReceived);
    aquanet_inbound_publisher = nh.advertise<geometry_msgs::Twist>("aquanet_inbound", 1);

    // Start the receive thread
    std::thread t1(receiveAqua, m_socket);

    // Let ROS take over.
    ros::spin();
}