Skip to content

Commit 542f477

Browse files
committed
addd source code for using depth sensor without display
1 parent 59117f0 commit 542f477

File tree

1 file changed

+72
-0
lines changed

1 file changed

+72
-0
lines changed

Display/src/depth_no_display.cpp

Lines changed: 72 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
#include "SPI.h"
2+
#include "Adafruit_GFX.h"
3+
#include "Adafruit_ILI9341.h"
4+
#include <Wire.h>
5+
#include "MS5837.h"
6+
#include <ros.h>
7+
#include <auv_msgs/ThrusterMicroseconds.h>
8+
#include <std_msgs/Float32.h>
9+
#include <std_msgs/Float64.h>
10+
#include <std_msgs/Int32.h>
11+
#include <std_msgs/String.h>
12+
//#include <cmath>
13+
#include <math.h>
14+
15+
// Define pin configurations
16+
#define TFT_DC 9
17+
#define TFT_CS 10
18+
19+
// Define rotation constants
20+
#define ILI9341_ROTATION_0 0
21+
#define ILI9341_ROTATION_90 1
22+
#define ILI9341_ROTATION_180 2
23+
#define ILI9341_ROTATION_270 3
24+
25+
// Initialize sensor object
26+
MS5837 sensor;
27+
28+
// Initialize ROS node handle
29+
ros::NodeHandle nh;
30+
31+
// Define publisher message variable
32+
std_msgs::Float64 depth_msg;
33+
34+
// Define publishers and subscribers
35+
// Publishes depth
36+
// Subscribes to battery voltages, thruster microseconds, device statuses, status message, and tether status
37+
ros::Publisher DEPTH("/sensors/depth/z", &depth_msg);
38+
39+
// Function to calculate and publish depth
40+
void publish_depth() {
41+
depth_msg.data = sensor.depth();
42+
DEPTH.publish(&depth_msg);
43+
}
44+
45+
void setup() {
46+
// Initialize I2C communication with sensor
47+
Wire.begin();
48+
sensor.init();
49+
delay(1000);
50+
51+
sensor.setModel(MS5837::MS5837_30BA);
52+
sensor.setFluidDensity(997);
53+
54+
// Initialize ROS node handle
55+
nh.initNode();
56+
57+
// Advertise ROS publisher
58+
nh.advertise(DEPTH);
59+
60+
}
61+
62+
void loop() {
63+
// Handle ROS communication
64+
nh.spinOnce();
65+
66+
// Read sensor data and publish depth
67+
sensor.read();
68+
publish_depth();
69+
70+
// Delay for stability
71+
delay(10);
72+
}

0 commit comments

Comments
 (0)