-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathrpmsubscriber.cpp
148 lines (123 loc) · 4.76 KB
/
rpmsubscriber.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
/*------------------------------RPM, CURRENT, VOLTAGE SUBSCRIBER------------------------------*/
RpmSubscriber::RpmSubscriber(QObject*)
{
connect(this, SIGNAL(receivedrpm(double)), this, SLOT(updaterpm(double)));
connect(this, SIGNAL(receivedcurrent(double)), this, SLOT(updatecurrent(double)));
connect(this, SIGNAL(receivedvoltage(double)), this, SLOT(updatevoltage(double)));
connect(this, SIGNAL(receivedthrottle(double)), this, SLOT(updatethrottle(double)));
connect(this, SIGNAL(receivedpressure(double)), this, SLOT(updatepressure(double)));
connect(this, SIGNAL(receiveddepth(double)), this, SLOT(updatedepth(double)));
connect(this, SIGNAL(receivedzpath(double)), this, SLOT(updatezpath(double)));
connect(this, SIGNAL(receivedinflow(double)), this, SLOT(updateinflow(double)));
connect(this, SIGNAL(receivedoutflow(double)), this, SLOT(updateoutflow(double)));
connect(this, SIGNAL(receivedinletpump(double)), this, SLOT(updateinletpump(double)));
connect(this, SIGNAL(receivedoutletpump(double)), this, SLOT(updateoutletpump(double)));
rpm_sub = nh.subscribe("/rpm_bldc", 1, &RpmSubscriber::rpmCallback,this);
current_sub = nh.subscribe("/current", 1, &RpmSubscriber::currentCallback,this);
voltage_sub = nh.subscribe("/voltage", 1, &RpmSubscriber::voltageCallback,this);
throttle_sub = nh.subscribe("/throttle", 1, &RpmSubscriber::throttleCallback,this);
pressure_sub = nh.subscribe("/pressure_ballast", 1, &RpmSubscriber::pressureCallback,this);
depth = nh.subscribe("/depth", 1, &RpmSubscriber::depthCallback,this);
zpath = nh.subscribe("/zpos", 1, &RpmSubscriber::zpathCallback,this);
inflow_sub = nh.subscribe("/flow_in", 1, &RpmSubscriber::inflowCallback,this);
outflow_sub = nh.subscribe("/flow_out", 1, &RpmSubscriber::outflowCallback,this);
inletpump_sub = nh.subscribe("/inlet_pump", 1, &RpmSubscriber::inletpumpCallback,this);
outletpump_sub = nh.subscribe("/outlet_pump", 1, &RpmSubscriber::outletpumpCallback,this);
}
void RpmSubscriber::rpmCallback(const std_msgs::UInt32::ConstPtr& msg)
{
if (msg->data <= 100 or msg->data >=4500){
if (rpm_count>2){
receivedrpm(zero_rpm);
prev_rpm = zero_rpm;
rpm_count = 0;
}
else{
receivedrpm(prev_rpm);
rpm_count= rpm_count + 1;
//qDebug(rpm_count);
}
}
else {
receivedrpm(msg->data);
prev_rpm = msg->data;
rpm_count = 0;
}
//receivedcurrent(msg->data);
//receivedvoltage(msg->data);
//receivedthrottle(msg->data);
}
void RpmSubscriber::currentCallback(const std_msgs::Float32::ConstPtr &msg){
receivedcurrent(msg->data);
}
void RpmSubscriber::voltageCallback(const std_msgs::Float32::ConstPtr &msg){
receivedvoltage(msg->data);
}
void RpmSubscriber::throttleCallback(const std_msgs::Int16::ConstPtr &msg){
receivedthrottle(msg->data);
}
void RpmSubscriber::pressureCallback(const std_msgs::Float32::ConstPtr &msg){
receivedpressure(msg->data);
}
void RpmSubscriber::depthCallback(const std_msgs::Float32::ConstPtr &msg){
receiveddepth(msg->data);
}
void RpmSubscriber::zpathCallback(const std_msgs::Float32::ConstPtr &msg){
receivedzpath(msg->data);
}
void RpmSubscriber::inflowCallback(const std_msgs::Float32::ConstPtr &msg){
receivedinflow(msg->data);
}
void RpmSubscriber::outflowCallback(const std_msgs::Float32::ConstPtr &msg){
receivedoutflow(msg->data);
}
void RpmSubscriber::inletpumpCallback(const std_msgs::Int32::ConstPtr &msg){
receivedinletpump(msg->data);
}
void RpmSubscriber::outletpumpCallback(const std_msgs::Int32::ConstPtr &msg){
receivedoutletpump(msg->data);
}
void RpmSubscriber::updaterpm(double data){
m_rpm = data ;
emit rpmChanged();
}
void RpmSubscriber::updatecurrent(double data){
m_current = data * AMPS;
emit currentChanged();
}
void RpmSubscriber::updatevoltage(double data){
m_voltage = data * VOLTS;
emit voltageChanged();
}
void RpmSubscriber::updatethrottle(double data){
m_throttle = data;
emit throttleChanged();
}
void RpmSubscriber::updatepressure(double data){
m_pressure = data;
emit pressureChanged();
}
void RpmSubscriber::updatedepth(double data){
m_depth = data;
emit depthChanged();
}
void RpmSubscriber::updatezpath(double data){
m_zpath = data;
emit zPathChanged();
}
void RpmSubscriber::updateinflow(double data){
m_inflow = data;
emit inflowChanged();
}
void RpmSubscriber::updateoutflow(double data){
m_outflow = data;
emit outflowChanged();
}
void RpmSubscriber::updateinletpump(double data){
m_inletpump = data;
emit inletpumpChanged();
}
void RpmSubscriber::updateoutletpump(double data){
m_outletpump = data;
emit outletpumpChanged();
}