Updated mining readouts for addition of science cam controls. Working science cam controls. Fixed missing soil probe transports.

This commit is contained in:
2018-08-12 01:25:20 -07:00
parent 03cdd2e3a6
commit a4f04eda7e
8 changed files with 466 additions and 354 deletions

View File

@@ -1,6 +1,7 @@
////////// Includes ////////// ////////// Includes //////////
#include "HX711.h" #include "HX711.h"
#include <ModbusRtu.h> #include <ModbusRtu.h>
#include <camera.h>
////////// Hardware / Data Enumerations ////////// ////////// Hardware / Data Enumerations //////////
enum HARDWARE { enum HARDWARE {
@@ -65,13 +66,12 @@ enum MODBUS_REGISTERS {
ZOOM_OUT = 11, ZOOM_OUT = 11,
FULL_ZOOM_IN = 12, FULL_ZOOM_IN = 12,
FULL_ZOOM_OUT = 13, FULL_ZOOM_OUT = 13,
FOCUS = 14, SHOOT = 14,
SHOOT = 15,
// Outputs // Outputs
CURRENT_POSITION_LIFT = 16, CURRENT_POSITION_LIFT = 15,
CURRENT_POSITION_TILT = 17, CURRENT_POSITION_TILT = 16,
MEASURED_WEIGHT = 18 MEASURED_WEIGHT = 17
}; };
enum CAMERA_VIEW_MODES { enum CAMERA_VIEW_MODES {
@@ -92,7 +92,7 @@ float last_calibration_factor = -120000; //for the scale
// modbus stuff // modbus stuff
const uint8_t node_id = 2; const uint8_t node_id = 2;
const uint8_t mobus_serial_port_number = 2; const uint8_t mobus_serial_port_number = 2;
uint16_t modbus_data[] = {0, 0, 0, 0, 9999, 9999, 0, 0, 895, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; uint16_t modbus_data[] = {0, 0, 0, 0, 9999, 9999, 0, 0, 895, 0, 0, 0, 0, 0, 0, 0, 0, 0};
uint8_t num_modbus_registers = 0; uint8_t num_modbus_registers = 0;
int8_t poll_state = 0; int8_t poll_state = 0;
bool communication_good = false; bool communication_good = false;
@@ -107,10 +107,11 @@ uint8_t message_count = 0;
////////// Class Instantiations ////////// ////////// Class Instantiations //////////
HX711 scale(HARDWARE::SCALE_DOUT, HARDWARE::SCALE_CLK); HX711 scale(HARDWARE::SCALE_DOUT, HARDWARE::SCALE_CLK);
Modbus slave(node_id, mobus_serial_port_number, HARDWARE::RS485_EN); Modbus slave(node_id, mobus_serial_port_number, HARDWARE::RS485_EN);
camera science_camera(HARDWARE::CAMERA_CONTROL);
void setup() { void setup() {
Serial.begin(9600); // debug Serial.begin(9600); // debug
while(!Serial); // while(!Serial);
setup_hardware(); setup_hardware();
num_modbus_registers = sizeof(modbus_data) / sizeof(modbus_data[0]); num_modbus_registers = sizeof(modbus_data) / sizeof(modbus_data[0]);
@@ -291,33 +292,23 @@ void apply_camera_commands(){
////// Zoom controls, process all, even if conflicting /////// ////// Zoom controls, process all, even if conflicting ///////
if(modbus_data[MODBUS_REGISTERS::ZOOM_IN]){ if(modbus_data[MODBUS_REGISTERS::ZOOM_IN]){
Serial.println("ZOOM IN"); science_camera.slowZoomIn();
modbus_data[MODBUS_REGISTERS::ZOOM_IN] = 0; modbus_data[MODBUS_REGISTERS::ZOOM_IN] = 0;
}else if(modbus_data[MODBUS_REGISTERS::ZOOM_OUT]){ }else if(modbus_data[MODBUS_REGISTERS::ZOOM_OUT]){
Serial.println("ZOOM OUT"); science_camera.slowZoomOut();
modbus_data[MODBUS_REGISTERS::ZOOM_OUT] = 0; modbus_data[MODBUS_REGISTERS::ZOOM_OUT] = 0;
}else if(modbus_data[MODBUS_REGISTERS::FULL_ZOOM_IN]){ }else if(modbus_data[MODBUS_REGISTERS::FULL_ZOOM_IN]){
Serial.println("FULL ZOOM IN"); science_camera.fullZoomIn();
modbus_data[MODBUS_REGISTERS::FULL_ZOOM_IN] = 0; modbus_data[MODBUS_REGISTERS::FULL_ZOOM_IN] = 0;
} }else if(modbus_data[MODBUS_REGISTERS::FULL_ZOOM_OUT]){
science_camera.fullZoomOut();
if(modbus_data[MODBUS_REGISTERS::FULL_ZOOM_OUT]){
Serial.println("FULL ZOOM OUT");
modbus_data[MODBUS_REGISTERS::FULL_ZOOM_OUT] = 0; modbus_data[MODBUS_REGISTERS::FULL_ZOOM_OUT] = 0;
} } else if(modbus_data[MODBUS_REGISTERS::SHOOT]){
science_camera.shoot();
////// Focus and shoot controls ///////
if(modbus_data[MODBUS_REGISTERS::FOCUS]){
Serial.println("FOCUS");
modbus_data[MODBUS_REGISTERS::FOCUS] = 0;
}
if(modbus_data[MODBUS_REGISTERS::SHOOT]){
Serial.println("SHOOT");
modbus_data[MODBUS_REGISTERS::SHOOT] = 0; modbus_data[MODBUS_REGISTERS::SHOOT] = 0;
} }
///// camera process here ///// camera process here
science_camera.update();
} }
//---Set Motor Output---// //---Set Motor Output---//

View File

@@ -32,6 +32,15 @@ MEASURE_POSITION_TILT = 1023
SCOOP_POSITION_LIFT = 228 SCOOP_POSITION_LIFT = 228
SCOOP_POSITION_TILT = 215 SCOOP_POSITION_TILT = 215
PANORAMA_POSITION_LIFT = 535
PANORAMA_POSITION_TILT = 995
SAMPLE_POSITION_LIFT = 220
SAMPLE_POSITION_TILT = 240
PROBE_POSITION_LIFT = 950
PROBE_POSITION_TILT = 440
##################################### #####################################
# UbiquitiRadioSettings Class Definition # UbiquitiRadioSettings Class Definition
@@ -58,10 +67,7 @@ class Mining(QtCore.QObject):
self.left_screen = self.shared_objects["screens"]["left_screen"] self.left_screen = self.shared_objects["screens"]["left_screen"]
self.mining_qlcdnumber = self.left_screen.mining_qlcdnumber # type:QtWidgets.QLCDNumber self.mining_qlcdnumber = self.left_screen.mining_qlcdnumber # type:QtWidgets.QLCDNumber
self.mining_tare_button = self.left_screen.mining_tare_button # type:QtWidgets.QPushButton self.mining_zero_button = self.left_screen.mining_zero_button # type:QtWidgets.QPushButton
self.mining_measure_button = self.left_screen.mining_measure_button # type:QtWidgets.QPushButton
self.mining_cal_factor_spinbox = self.left_screen.mining_cal_factor_spinbox # type:QtWidgets.QSpinBox
self.mining_set_cal_factor_button = self.left_screen.mining_set_cal_factor_button # type:QtWidgets.QPushButton
self.lift_position_progress_bar = self.left_screen.lift_position_progress_bar # type:QtWidgets.QProgressBar self.lift_position_progress_bar = self.left_screen.lift_position_progress_bar # type:QtWidgets.QProgressBar
self.tilt_position_progress_bar = self.left_screen.tilt_position_progress_bar # type:QtWidgets.QProgressBar self.tilt_position_progress_bar = self.left_screen.tilt_position_progress_bar # type:QtWidgets.QProgressBar
@@ -69,6 +75,10 @@ class Mining(QtCore.QObject):
self.mining_transport_move_button = self.left_screen.mining_transport_move_button # type:QtWidgets.QPushButton self.mining_transport_move_button = self.left_screen.mining_transport_move_button # type:QtWidgets.QPushButton
self.mining_scoop_move_button = self.left_screen.mining_scoop_move_button # type:QtWidgets.QPushButton self.mining_scoop_move_button = self.left_screen.mining_scoop_move_button # type:QtWidgets.QPushButton
self.mining_panorama_button = self.left_screen.mining_panorama_button # type:QtWidgets.QPushButton
self.mining_sample_button = self.left_screen.mining_sample_button # type:QtWidgets.QPushButton
self.mining_probe_button = self.left_screen.mining_probe_button # type:QtWidgets.QPushButton
self.science_temp_lcd_number = self.left_screen.science_temp_lcd_number # type:QtWidgets.QLCDNumber self.science_temp_lcd_number = self.left_screen.science_temp_lcd_number # type:QtWidgets.QLCDNumber
self.science_moisture_lcd_number = self.left_screen.science_moisture_lcd_number # type:QtWidgets.QLCDNumber self.science_moisture_lcd_number = self.left_screen.science_moisture_lcd_number # type:QtWidgets.QLCDNumber
self.science_loss_tangent_lcd_number = self.left_screen.science_loss_tangent_lcd_number # type:QtWidgets.QLCDNumber self.science_loss_tangent_lcd_number = self.left_screen.science_loss_tangent_lcd_number # type:QtWidgets.QLCDNumber
@@ -81,11 +91,10 @@ class Mining(QtCore.QObject):
self.cam_zoom_in_button = self.left_screen.cam_zoom_in_button # type:QtWidgets.QPushButton self.cam_zoom_in_button = self.left_screen.cam_zoom_in_button # type:QtWidgets.QPushButton
self.cam_zoom_out_button = self.left_screen.cam_zoom_out_button # type:QtWidgets.QPushButton self.cam_zoom_out_button = self.left_screen.cam_zoom_out_button # type:QtWidgets.QPushButton
self.cam_lcd_output_button = self.left_screen.cam_lcd_output_button # type:QtWidgets.QPushButton self.cam_full_zoom_in_button = self.left_screen.cam_full_zoom_in_button # type:QtWidgets.QPushButton
self.cam_lcd_output_button = self.left_screen.cam_lcd_output_button # type:QtWidgets.QPushButton self.cam_full_zoom_out_button = self.left_screen.cam_full_zoom_out_button # type:QtWidgets.QPushButton
self.cam_lcd_output_button = self.left_screen.cam_lcd_output_button # type:QtWidgets.QPushButton self.cam_shoot_button = self.left_screen.cam_shoot_button # type:QtWidgets.QPushButton
self.cam_lcd_output_button = self.left_screen.cam_lcd_output_button # type:QtWidgets.QPushButton
# ########## Get the settings instance ########## # ########## Get the settings instance ##########
self.settings = QtCore.QSettings() self.settings = QtCore.QSettings()
@@ -106,17 +115,22 @@ class Mining(QtCore.QObject):
self.mining_control_publisher = rospy.Publisher(MINING_CONTROL_TOPIC, MiningControlMessage, queue_size=1) self.mining_control_publisher = rospy.Publisher(MINING_CONTROL_TOPIC, MiningControlMessage, queue_size=1)
self.camera_control_publisher = rospy.Publisher(CAMERA_CONTROL_TOPIC, CameraControlMessage, queue_size=1) self.camera_control_publisher = rospy.Publisher(CAMERA_CONTROL_TOPIC, CameraControlMessage, queue_size=1)
self.current_scale_measurement = 0
self.scale_zero_offset = 0
self.connect_signals_and_slots() self.connect_signals_and_slots()
def connect_signals_and_slots(self): def connect_signals_and_slots(self):
self.mining_set_cal_factor_button.clicked.connect(self.on_mining_set_cal_factor_clicked__slot) self.mining_zero_button.clicked.connect(self.on_mining_zero_clicked__slot)
self.mining_tare_button.clicked.connect(self.on_mining_tare_clicked__slot)
self.mining_measure_button.clicked.connect(self.on_mining_measure_clicked__slot)
self.mining_measure_move_button.clicked.connect(self.on_mining_move_measure_clicked__slot) self.mining_measure_move_button.clicked.connect(self.on_mining_move_measure_clicked__slot)
self.mining_transport_move_button.clicked.connect(self.on_mining_move_transport_clicked__slot) self.mining_transport_move_button.clicked.connect(self.on_mining_move_transport_clicked__slot)
self.mining_scoop_move_button.clicked.connect(self.on_mining_move_scoop_clicked__slot) self.mining_scoop_move_button.clicked.connect(self.on_mining_move_scoop_clicked__slot)
self.mining_panorama_button.clicked.connect(self.on_mining_move_panorama_clicked__slot)
self.mining_sample_button.clicked.connect(self.on_mining_move_sample_clicked__slot)
self.mining_probe_button.clicked.connect(self.on_mining_move_probe_clicked__slot)
self.tilt_position_update_ready__signal.connect(self.tilt_position_progress_bar.setValue) self.tilt_position_update_ready__signal.connect(self.tilt_position_progress_bar.setValue)
self.lift_position_update_ready__signal.connect(self.lift_position_progress_bar.setValue) self.lift_position_update_ready__signal.connect(self.lift_position_progress_bar.setValue)
@@ -132,32 +146,14 @@ class Mining(QtCore.QObject):
self.cam_lcd_output_button.clicked.connect(self.on_cam_lcd_button_clicked__slot) self.cam_lcd_output_button.clicked.connect(self.on_cam_lcd_button_clicked__slot)
self.cam_network_output_button.clicked.connect(self.on_cam_network_button_clicked__slot) self.cam_network_output_button.clicked.connect(self.on_cam_network_button_clicked__slot)
def on_mining_set_cal_factor_clicked__slot(self): self.cam_zoom_in_button.clicked.connect(self.on_cam_zoom_in_button_clicked__slot)
message = MiningControlMessage() self.cam_zoom_out_button.clicked.connect(self.on_cam_zoom_out_button_clicked__slot)
self.cam_full_zoom_in_button.clicked.connect(self.on_cam_full_zoom_in_button_clicked__slot)
self.cam_full_zoom_out_button.clicked.connect(self.on_cam_full_zoom_out_button_clicked__slot)
self.cam_shoot_button.clicked.connect(self.on_cam_shoot_button_clicked__slot)
message.tilt_set_absolute = 1024 def on_mining_zero_clicked__slot(self):
message.lift_set_absolute = 1024 self.scale_zero_offset = -self.current_scale_measurement
message.cal_factor = self.mining_cal_factor_spinbox.value()
self.mining_control_publisher.publish(message)
def on_mining_tare_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = 1024
message.lift_set_absolute = 1024
message.cal_factor = -1
message.tare = 1
self.mining_control_publisher.publish(message)
def on_mining_measure_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = 1024
message.lift_set_absolute = 1024
message.cal_factor = -1
message.measure = True
self.mining_control_publisher.publish(message)
def on_mining_move_transport_clicked__slot(self): def on_mining_move_transport_clicked__slot(self):
message = MiningControlMessage() message = MiningControlMessage()
@@ -183,6 +179,30 @@ class Mining(QtCore.QObject):
self.mining_control_publisher.publish(message) self.mining_control_publisher.publish(message)
def on_mining_move_panorama_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = PANORAMA_POSITION_TILT
message.lift_set_absolute = PANORAMA_POSITION_LIFT
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def on_mining_move_sample_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = SAMPLE_POSITION_TILT
message.lift_set_absolute = SAMPLE_POSITION_LIFT
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def on_mining_move_probe_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = PROBE_POSITION_TILT
message.lift_set_absolute = PROBE_POSITION_LIFT
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def on_cam_lcd_button_clicked__slot(self): def on_cam_lcd_button_clicked__slot(self):
message = CameraControlMessage() message = CameraControlMessage()
message.camera_mode = 1 message.camera_mode = 1
@@ -193,11 +213,35 @@ class Mining(QtCore.QObject):
message.camera_mode = 2 message.camera_mode = 2
self.camera_control_publisher.publish(message) self.camera_control_publisher.publish(message)
def on_cam_zoom_in_button_clicked__slot(self):
message = CameraControlMessage()
message.zoom_in = 1
self.camera_control_publisher.publish(message)
def on_cam_zoom_out_button_clicked__slot(self):
message = CameraControlMessage()
message.zoom_out = 1
self.camera_control_publisher.publish(message)
def on_cam_full_zoom_in_button_clicked__slot(self):
message = CameraControlMessage()
message.full_zoom_in = 1
self.camera_control_publisher.publish(message)
def on_cam_full_zoom_out_button_clicked__slot(self):
message = CameraControlMessage()
message.full_zoom_out = 1
self.camera_control_publisher.publish(message)
def on_cam_shoot_button_clicked__slot(self):
message = CameraControlMessage()
message.shoot = 1
self.camera_control_publisher.publish(message)
def mining_status_message_received__callback(self, status): def mining_status_message_received__callback(self, status):
status = status # type:MiningStatusMessage status = status # type:MiningStatusMessage
self.tilt_position_update_ready__signal.emit(status.tilt_position) self.tilt_position_update_ready__signal.emit(status.tilt_position)
self.lift_position_update_ready__signal.emit(status.lift_position) self.lift_position_update_ready__signal.emit(status.lift_position)
# self.weight_measurement_update_ready__signal.emit(status.measured_weight)
def on_soil_probe_message_received__callback(self, data): def on_soil_probe_message_received__callback(self, data):
self.temp_update_ready__signal.emit(data.temp_c) self.temp_update_ready__signal.emit(data.temp_c)
@@ -208,4 +252,6 @@ class Mining(QtCore.QObject):
self.imaginary_dielectric_update_ready__signal.emit(data.imaginary_dielectric_permittivity) self.imaginary_dielectric_update_ready__signal.emit(data.imaginary_dielectric_permittivity)
def on_scale_measurement_received__callback(self, data): def on_scale_measurement_received__callback(self, data):
self.weight_measurement_update_ready__signal.emit(data.data * 1000) grams = data.data * 1000
self.current_scale_measurement = grams
self.weight_measurement_update_ready__signal.emit(grams + self.scale_zero_offset)

View File

@@ -1390,145 +1390,8 @@ N/A</string>
</size> </size>
</property> </property>
<property name="currentIndex"> <property name="currentIndex">
<number>0</number> <number>2</number>
</property> </property>
<widget class="QWidget" name="tab_6">
<attribute name="title">
<string>Science Cam</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_20">
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout_26">
<item>
<widget class="QLabel" name="label_72">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Video Output</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_21">
<item>
<widget class="QPushButton" name="cam_lcd_output_button">
<property name="text">
<string>LCD</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="cam_network_output_button">
<property name="text">
<string>Network</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item row="0" column="1">
<spacer name="horizontalSpacer_20">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>422</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="0">
<layout class="QVBoxLayout" name="verticalLayout_27">
<item>
<widget class="QLabel" name="label_73">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Controls</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<layout class="QFormLayout" name="formLayout">
<item row="0" column="0">
<widget class="QPushButton" name="cam_zoom_in_button">
<property name="text">
<string>Zoom In</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QPushButton" name="cam_zoom_out_button">
<property name="text">
<string>Zoom Out</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="cam_full_zoom_in_button">
<property name="text">
<string>Full Zoom In</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QPushButton" name="cam_full_zoom_out_button">
<property name="text">
<string>Full Zoom Out</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QPushButton" name="cam_focus_button">
<property name="text">
<string>Focus</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QPushButton" name="cam_shoot_button">
<property name="text">
<string>Shoot</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item row="2" column="0">
<spacer name="verticalSpacer_8">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>331</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<widget class="QWidget" name="tab_5"> <widget class="QWidget" name="tab_5">
<attribute name="title"> <attribute name="title">
<string>RDF</string> <string>RDF</string>
@@ -2017,7 +1880,14 @@ N/A</string>
<string>Mining / Science</string> <string>Mining / Science</string>
</attribute> </attribute>
<layout class="QGridLayout" name="gridLayout_8"> <layout class="QGridLayout" name="gridLayout_8">
<item row="5" column="0"> <item row="2" column="0">
<widget class="Line" name="line_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="3" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_12"> <layout class="QHBoxLayout" name="horizontalLayout_12">
<item> <item>
<widget class="QLabel" name="label_15"> <widget class="QLabel" name="label_15">
@@ -2048,7 +1918,7 @@ N/A</string>
</item> </item>
</layout> </layout>
</item> </item>
<item row="6" column="0"> <item row="4" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_11"> <layout class="QHBoxLayout" name="horizontalLayout_11">
<item> <item>
<widget class="QLabel" name="label_14"> <widget class="QLabel" name="label_14">
@@ -2083,7 +1953,7 @@ N/A</string>
<widget class="QLabel" name="label_13"> <widget class="QLabel" name="label_13">
<property name="font"> <property name="font">
<font> <font>
<pointsize>16</pointsize> <pointsize>14</pointsize>
<weight>75</weight> <weight>75</weight>
<bold>true</bold> <bold>true</bold>
</font> </font>
@@ -2092,101 +1962,10 @@ N/A</string>
<string>Scoop Measurement</string> <string>Scoop Measurement</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignCenter</set> <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="mining_tare_button">
<property name="text">
<string>Tare</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="mining_measure_button">
<property name="text">
<string>Measure</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="3" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
<spacer name="horizontalSpacer_10">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QSpinBox" name="mining_cal_factor_spinbox">
<property name="maximum">
<number>65535</number>
</property>
<property name="value">
<number>114</number>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="mining_set_cal_factor_button">
<property name="text">
<string>Set Cal Factor</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="1" column="0"> <item row="1" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_10"> <layout class="QHBoxLayout" name="horizontalLayout_10">
<item> <item>
@@ -2213,13 +1992,13 @@ N/A</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>300</width> <width>300</width>
<height>75</height> <height>45</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>300</width> <width>300</width>
<height>75</height> <height>45</height>
</size> </size>
</property> </property>
<property name="font"> <property name="font">
@@ -2242,7 +2021,7 @@ N/A</string>
<widget class="QLabel" name="label_5"> <widget class="QLabel" name="label_5">
<property name="font"> <property name="font">
<font> <font>
<pointsize>19</pointsize> <pointsize>12</pointsize>
<weight>75</weight> <weight>75</weight>
<bold>true</bold> <bold>true</bold>
</font> </font>
@@ -2265,6 +2044,13 @@ N/A</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item>
<widget class="QPushButton" name="mining_zero_button">
<property name="text">
<string>Zero</string>
</property>
</widget>
</item>
</layout> </layout>
</item> </item>
<item row="10" column="0"> <item row="10" column="0">
@@ -2280,27 +2066,20 @@ N/A</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="4" column="0"> <item row="5" column="0">
<widget class="Line" name="line_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="7" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_13"> <layout class="QHBoxLayout" name="horizontalLayout_13">
<item> <item>
<spacer name="horizontalSpacer_13"> <widget class="QLabel" name="label_35">
<property name="orientation"> <property name="font">
<enum>Qt::Horizontal</enum> <font>
<weight>75</weight>
<bold>true</bold>
</font>
</property> </property>
<property name="sizeHint" stdset="0"> <property name="text">
<size> <string>Mining</string>
<width>40</width>
<height>20</height>
</size>
</property> </property>
</spacer> </widget>
</item> </item>
<item> <item>
<widget class="QPushButton" name="mining_transport_move_button"> <widget class="QPushButton" name="mining_transport_move_button">
@@ -2324,7 +2103,7 @@ N/A</string>
</widget> </widget>
</item> </item>
<item> <item>
<spacer name="horizontalSpacer_14"> <spacer name="horizontalSpacer_13">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
</property> </property>
@@ -2336,16 +2115,50 @@ N/A</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item>
<widget class="QLabel" name="label_36">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Science</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="mining_panorama_button">
<property name="text">
<string>Panaroma</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="mining_sample_button">
<property name="text">
<string>Sample</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="mining_probe_button">
<property name="text">
<string>Probe</string>
</property>
</widget>
</item>
</layout> </layout>
</item> </item>
<item row="8" column="0"> <item row="6" column="0">
<widget class="Line" name="line_9"> <widget class="Line" name="line_9">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
</property> </property>
</widget> </widget>
</item> </item>
<item row="9" column="0"> <item row="7" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_16"> <layout class="QHBoxLayout" name="horizontalLayout_16">
<item> <item>
<layout class="QVBoxLayout" name="verticalLayout_10"> <layout class="QVBoxLayout" name="verticalLayout_10">
@@ -2353,7 +2166,7 @@ N/A</string>
<widget class="QLabel" name="label_20"> <widget class="QLabel" name="label_20">
<property name="font"> <property name="font">
<font> <font>
<pointsize>16</pointsize> <pointsize>14</pointsize>
<weight>75</weight> <weight>75</weight>
<bold>true</bold> <bold>true</bold>
</font> </font>
@@ -2362,7 +2175,7 @@ N/A</string>
<string>Science Probe Data</string> <string>Science Probe Data</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignCenter</set> <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
@@ -2374,7 +2187,7 @@ N/A</string>
<widget class="QLabel" name="label_21"> <widget class="QLabel" name="label_21">
<property name="font"> <property name="font">
<font> <font>
<pointsize>10</pointsize> <pointsize>9</pointsize>
<weight>75</weight> <weight>75</weight>
<bold>true</bold> <bold>true</bold>
</font> </font>
@@ -2389,7 +2202,13 @@ N/A</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>35</height> <height>30</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
</size> </size>
</property> </property>
</widget> </widget>
@@ -2402,7 +2221,7 @@ N/A</string>
<widget class="QLabel" name="moisture_label"> <widget class="QLabel" name="moisture_label">
<property name="font"> <property name="font">
<font> <font>
<pointsize>10</pointsize> <pointsize>9</pointsize>
<weight>75</weight> <weight>75</weight>
<bold>true</bold> <bold>true</bold>
</font> </font>
@@ -2417,7 +2236,13 @@ N/A</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>35</height> <height>30</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
</size> </size>
</property> </property>
</widget> </widget>
@@ -2430,7 +2255,7 @@ N/A</string>
<widget class="QLabel" name="tangent_label"> <widget class="QLabel" name="tangent_label">
<property name="font"> <property name="font">
<font> <font>
<pointsize>10</pointsize> <pointsize>9</pointsize>
<weight>75</weight> <weight>75</weight>
<bold>true</bold> <bold>true</bold>
</font> </font>
@@ -2445,7 +2270,13 @@ N/A</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>35</height> <height>30</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
</size> </size>
</property> </property>
</widget> </widget>
@@ -2458,15 +2289,14 @@ N/A</string>
<widget class="QLabel" name="conductivity_label"> <widget class="QLabel" name="conductivity_label">
<property name="font"> <property name="font">
<font> <font>
<pointsize>10</pointsize> <pointsize>9</pointsize>
<weight>75</weight> <weight>75</weight>
<bold>true</bold> <bold>true</bold>
</font> </font>
</property> </property>
<property name="text"> <property name="text">
<string>Soil <string>Soil
Electrical Electrical Conductivity</string>
Conductivity</string>
</property> </property>
</widget> </widget>
</item> </item>
@@ -2475,7 +2305,13 @@ Conductivity</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>35</height> <height>30</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
</size> </size>
</property> </property>
</widget> </widget>
@@ -2488,15 +2324,14 @@ Conductivity</string>
<widget class="QLabel" name="real_dielectric_label"> <widget class="QLabel" name="real_dielectric_label">
<property name="font"> <property name="font">
<font> <font>
<pointsize>10</pointsize> <pointsize>9</pointsize>
<weight>75</weight> <weight>75</weight>
<bold>true</bold> <bold>true</bold>
</font> </font>
</property> </property>
<property name="text"> <property name="text">
<string>Real <string>Real
Dielectric Dielectric Permittivity</string>
Permittivity</string>
</property> </property>
</widget> </widget>
</item> </item>
@@ -2505,7 +2340,13 @@ Permittivity</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>35</height> <height>30</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
</size> </size>
</property> </property>
</widget> </widget>
@@ -2518,15 +2359,14 @@ Permittivity</string>
<widget class="QLabel" name="imaginary_label"> <widget class="QLabel" name="imaginary_label">
<property name="font"> <property name="font">
<font> <font>
<pointsize>10</pointsize> <pointsize>9</pointsize>
<weight>75</weight> <weight>75</weight>
<bold>true</bold> <bold>true</bold>
</font> </font>
</property> </property>
<property name="text"> <property name="text">
<string>Imaginary <string>Imaginary
Dielectric Dielectric Permittivity</string>
Permittivity</string>
</property> </property>
</widget> </widget>
</item> </item>
@@ -2535,7 +2375,13 @@ Permittivity</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>35</height> <height>30</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
</size> </size>
</property> </property>
</widget> </widget>
@@ -2548,6 +2394,232 @@ Permittivity</string>
</item> </item>
</layout> </layout>
</item> </item>
<item row="8" column="0">
<widget class="Line" name="line_13">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="9" column="0">
<layout class="QVBoxLayout" name="verticalLayout_26">
<item>
<widget class="QLabel" name="label_34">
<property name="font">
<font>
<pointsize>14</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Camera Controls</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<layout class="QVBoxLayout" name="verticalLayout_27">
<item>
<layout class="QVBoxLayout" name="verticalLayout_28">
<item>
<widget class="QLabel" name="label_72">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Video Output</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_29">
<item>
<widget class="QPushButton" name="cam_network_output_button">
<property name="minimumSize">
<size>
<width>95</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Network</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="cam_lcd_output_button">
<property name="minimumSize">
<size>
<width>95</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>LCD</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_9">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_30">
<item>
<layout class="QVBoxLayout" name="verticalLayout_31">
<item>
<widget class="QLabel" name="label_73">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Controls</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
<layout class="QVBoxLayout" name="verticalLayout_32">
<item>
<widget class="QPushButton" name="cam_zoom_in_button">
<property name="minimumSize">
<size>
<width>95</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Zoom In</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="cam_full_zoom_in_button">
<property name="minimumSize">
<size>
<width>95</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Full Zoom In</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_33">
<item>
<widget class="QPushButton" name="cam_zoom_out_button">
<property name="minimumSize">
<size>
<width>95</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Zoom Out</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="cam_full_zoom_out_button">
<property name="minimumSize">
<size>
<width>95</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Full Zoom Out</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QPushButton" name="cam_shoot_button">
<property name="minimumSize">
<size>
<width>95</width>
<height>50</height>
</size>
</property>
<property name="text">
<string>Shoot</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_10">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</item>
</layout> </layout>
</widget> </widget>
<widget class="QWidget" name="tab"> <widget class="QWidget" name="tab">

View File

@@ -4,5 +4,4 @@ bool zoom_in
bool zoom_out bool zoom_out
bool full_zoom_in bool full_zoom_in
bool full_zoom_out bool full_zoom_out
bool focus
bool shoot bool shoot

View File

@@ -101,12 +101,11 @@ MINING_MODBUS_REGISTERS = {
"ZOOM_OUT": 11, "ZOOM_OUT": 11,
"FULL_ZOOM_IN": 12, "FULL_ZOOM_IN": 12,
"FULL_ZOOM_OUT": 13, "FULL_ZOOM_OUT": 13,
"FOCUS": 14, "SHOOT": 14,
"SHOOT": 15,
"CURRENT_POSITION_LIFT": 16, "CURRENT_POSITION_LIFT": 15,
"CURRENT_POSITION_TILT": 17, "CURRENT_POSITION_TILT": 16,
"MEASURED_WEIGHT": 18 "MEASURED_WEIGHT": 17
} }
@@ -300,12 +299,11 @@ class EffectorsControl(object):
self.mining_registers[MINING_MODBUS_REGISTERS["TARE"]] = 0 self.mining_registers[MINING_MODBUS_REGISTERS["TARE"]] = 0
self.mining_registers[MINING_MODBUS_REGISTERS["CHANGE_VIEW_MODE"]] = self.camera_control_message.camera_mode self.mining_registers[MINING_MODBUS_REGISTERS["CHANGE_VIEW_MODE"]] = self.camera_control_message.camera_mode
self.mining_registers[MINING_MODBUS_REGISTERS["ZOOM_IN"]] = 0 self.mining_registers[MINING_MODBUS_REGISTERS["ZOOM_IN"]] = self.camera_control_message.zoom_in
self.mining_registers[MINING_MODBUS_REGISTERS["ZOOM_OUT"]] = 0 self.mining_registers[MINING_MODBUS_REGISTERS["ZOOM_OUT"]] = self.camera_control_message.zoom_out
self.mining_registers[MINING_MODBUS_REGISTERS["FULL_ZOOM_IN"]] = 0 self.mining_registers[MINING_MODBUS_REGISTERS["FULL_ZOOM_IN"]] = self.camera_control_message.full_zoom_in
self.mining_registers[MINING_MODBUS_REGISTERS["FULL_ZOOM_OUT"]] = 0 self.mining_registers[MINING_MODBUS_REGISTERS["FULL_ZOOM_OUT"]] = self.camera_control_message.full_zoom_out
self.mining_registers[MINING_MODBUS_REGISTERS["FOCUS"]] = 0 self.mining_registers[MINING_MODBUS_REGISTERS["SHOOT"]] = self.camera_control_message.shoot
self.mining_registers[MINING_MODBUS_REGISTERS["SHOOT"]] = 0
self.mining_node.write_registers(0, self.mining_registers) self.mining_node.write_registers(0, self.mining_registers)
self.modbus_nodes_seen_time = time() self.modbus_nodes_seen_time = time()

View File

@@ -12,11 +12,17 @@ publisher = rospy.Publisher(TOPIC, CameraControlMessage, queue_size=1)
time.sleep(2) time.sleep(2)
message = CameraControlMessage() # message = CameraControlMessage()
message.camera_mode = 2 # message.full_zoom_in = 1
# publisher.publish(message)
time.sleep(2)
message = CameraControlMessage()
message.shoot = 1
publisher.publish(message) publisher.publish(message)
time.sleep(5) time.sleep(5)
# message = MiningControlMessage() # message = MiningControlMessage()

View File

@@ -49,7 +49,6 @@ class EmergencyScale(object):
message = Float64() message = Float64()
message.data = float(value) message.data = float(value)
self.publisher.publish(message) self.publisher.publish(message)
print
except: except:
print "No data" print "No data"

View File

@@ -157,6 +157,7 @@
{name: "/rover_odometry/imu/data", compress: false, rate: 10.0}, {name: "/rover_odometry/imu/data", compress: false, rate: 10.0},
{name: "/rover_control/mining/status", compress: false, rate: 5.0}, {name: "/rover_control/mining/status", compress: false, rate: 5.0},
{name: "/rover_control/gripper/status", compress: false, rate: 5.0}, {name: "/rover_control/gripper/status", compress: false, rate: 5.0},
{name: "/rover_science/soil_probe/data", compress: false, rate: 5.0},
{name: "/rover_science/rdf/data", compress: false, rate: 50.0}, {name: "/rover_science/rdf/data", compress: false, rate: 50.0},
{name: "/rover_control/scale/measurement", compress: false, rate: 20.0} {name: "/rover_control/scale/measurement", compress: false, rate: 20.0}
] ]