Skip to content

Commit

Permalink
Dynamic pressure, move thrusters from Fall 2023 (#1205)
Browse files Browse the repository at this point in the history
  • Loading branch information
cbrxyz committed Jun 15, 2024
1 parent fa15e29 commit ebf43b2
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 5 deletions.
26 changes: 25 additions & 1 deletion SubjuGator/drivers/nav_tube_driver/src/nav_tube_driver.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
#include <bits/stdint-uintn.h>
#include <endian.h>
#include <mil_msgs/DepthStamped.h>
#include <nav_msgs/Odometry.h>
#include <ros/callback_queue.h>
#include <ros/ros.h>

#include <boost/asio.hpp>
Expand All @@ -22,6 +24,8 @@ class NavTubeDriver
ros::NodeHandle private_nh_;

ros::Publisher pub_;
ros::Subscriber odom_sub_;
nav_msgs::Odometry recent_odom_msg_;

std::string ip_;
int port_;
Expand Down Expand Up @@ -59,11 +63,13 @@ class NavTubeDriver
~NavTubeDriver();

void run();
void odom_callback(const nav_msgs::OdometryConstPtr& msg);
};

NavTubeDriver::NavTubeDriver(ros::NodeHandle nh, ros::NodeHandle private_nh) : nh_(nh), private_nh_(private_nh)
{
pub_ = nh.advertise<mil_msgs::DepthStamped>("depth", 10);
odom_sub_ = nh.subscribe<nav_msgs::Odometry>("odom", 10, &NavTubeDriver::odom_callback, this);
ip_ = private_nh.param<std::string>("ip", std::string("192.168.37.61"));
port_ = private_nh.param<int>("port", 33056);
frame_id_ = private_nh.param<std::string>("frame_id", "/depth");
Expand All @@ -85,6 +91,11 @@ NavTubeDriver::NavTubeDriver(ros::NodeHandle nh, ros::NodeHandle private_nh) : n
reinterpret_cast<uint16_t*>(&heartbeat_packet[2])[0] = nw_ordering;
}

void NavTubeDriver::odom_callback(const nav_msgs::OdometryConstPtr& ptr)
{
recent_odom_msg_ = *ptr;
}

NavTubeDriver::~NavTubeDriver()
{
{
Expand Down Expand Up @@ -194,7 +205,18 @@ void NavTubeDriver::read_messages(boost::shared_ptr<tcp::socket> socket)

uint64_t bits = be64toh(*reinterpret_cast<uint64_t*>(&backing[2]));
double pressure = *reinterpret_cast<double*>(&bits);
msg.depth = pressure;
if (recent_odom_msg_.header.seq)
{
// Accounts for the dynamic pressure applied to the pressure sensor
// when the sub is moving forwards or backwards
double velocity = recent_odom_msg_.twist.twist.linear.x;
double vel_effect = (abs(velocity) * velocity) / (1000 * 9.81);
msg.depth = pressure + vel_effect;
}
else
{
msg.depth = pressure;
}

pub_.publish(msg);
buffer = boost::asio::buffer(backing, sizeof(backing));
Expand All @@ -205,6 +227,8 @@ void NavTubeDriver::read_messages(boost::shared_ptr<tcp::socket> socket)

buffer = boost::asio::buffer(buffer + bytes_read);
prev = ros::Time::now();

ros::spinOnce();
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ thrusters:
FLH: {
node_id: 4,
position: [0.2678, 0.2795, 0.0],
direction: [0.866, -0.5, 0.0],
direction: [-0.866, 0.5, 0.0],
thrust_bounds: [-81.85, 99.7],
calib: {
# yamllint disable-line rule:line-length
Expand All @@ -56,7 +56,7 @@ thrusters:
FRH: {
node_id: 0,
position: [0.2678, -0.2795, 0.0],
direction: [0.866, 0.5, 0.0],
direction: [-0.866, -0.5, 0.0],
thrust_bounds: [-81.85, 99.7],
calib: {
# yamllint disable-line rule:line-length
Expand All @@ -80,7 +80,7 @@ thrusters:
BLH: {
node_id: 3,
position: [-0.2678, 0.2795, 0.0],
direction: [0.866, 0.5, 0.0],
direction: [-0.866, -0.5, 0.0],
thrust_bounds: [-81.85, 99.7],
calib: {
# yamllint disable-line rule:line-length
Expand All @@ -104,7 +104,7 @@ thrusters:
BRH: {
node_id: 7,
position: [-0.2678, -0.2795, 0.0],
direction: [0.866, -0.5, 0.0],
direction: [-0.866, 0.5, 0.0],
thrust_bounds: [-81.85, 99.7],
calib: {
# yamllint disable-line rule:line-length
Expand Down

0 comments on commit ebf43b2

Please sign in to comment.