Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Sv 13 driving mode switching #12

Open
wants to merge 8 commits into
base: master
Choose a base branch
from
246 changes: 246 additions & 0 deletions qt-gui.workspace.user.5a83cd3

Large diffs are not rendered by default.

199 changes: 173 additions & 26 deletions src/gui/resources/main_window.qml
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ Window {
anchors.topMargin: 0
anchors.bottom: parent.bottom
anchors.bottomMargin: 0

ROSVideoComponent {
// @disable-check M16
objectName: "videoStream"
Expand Down Expand Up @@ -68,7 +67,6 @@ Window {
font.pixelSize: 12
}
}

}

Item {
Expand Down Expand Up @@ -99,8 +97,8 @@ Window {
// @disable-check M16
topic: qsTr("/rover/signal")
}

}

Item{
id: camera_switching_container
width: 50
Expand Down Expand Up @@ -133,9 +131,7 @@ Window {
// @disable-check M16
topic: qsTr("/owr/control/availableFeeds")

// @disable-check M16
focus: true

//focus:true;
Shortcut {
sequence: "0"
onActivated: camera_switching.camera_number = 0
Expand Down Expand Up @@ -169,41 +165,158 @@ Window {
onActivated: camera_switching.camera_number = 7
}

ROSJoystickListener {
// @disable-check M16
objectName: "bot_joystick"
// @disable-check M16
topic: "/joy"
}

}

Item {
id: driving_mode_switching_container
anchors.bottomMargin: -94
anchors.leftMargin: -494
anchors.topMargin: 164
anchors.right: parent.right
anchors.rightMargin: 538
anchors.top: parent.top
anchors.left: logo.right
anchors.bottom: video_pane.top
ROSDrivingModeSwitching {
// @disable-check M16
objectName: "driving_mode_switching"
id: driving_mode_switching
// @disable-check M16`
anchors.bottom: parent.bottom
// @disable-check M16
anchors.bottomMargin: 0
// @disable-check M16
anchors.top: parent.top
// @disable-check M16
anchors.left: parent.left
// @disable-check M16
anchors.right: parent.right
// @disable-check M16
topic: qsTr("/rover/driving_mode_switching")
}

}

Rectangle{
x:80
y:100
width:360
height:20
focus: true;
Keys.enabled: true;
Keys.forwardTo: [box_front,box_crab,box_four,ROSTimer];

//rectangle for front wheel steering
Rectangle{
x:200
y:180
width:120
height:20
id: box_front
border.color: "black"
color:"white"
Text {
text: "front"
anchors.horizontalCenter:parent.horizontalCenter
anchors.verticalCenter: parent.verticalCenter
font.pointSize:12
font.bold:true
}
}

//rectangle for crab wheel steering
Rectangle{
x:320
y:180
width:120
height:20
id: box_crab
border.color:"black"
color:"white"
Text {

text: "crab"
anchors.centerIn: parent
font.pointSize:12
font.bold:true
}
}



//rectangle for four wheel steering
Rectangle{
x:440
y:180
width:120
height:20
id: box_four
border.color: "black"
color:"white"
Text {
text: "four"
anchors.horizontalCenter:parent.horizontalCenter
anchors.verticalCenter: parent.verticalCenter
font.pointSize:12
font.bold:true
}
// @disable-check M16
onButton_down: {
var start_number = camera_switching.camera_number;
//focus: true

// handle the case where no camera is selected
if(start_number < 0) {
start_number = 0;
}
//key press response
Keys.onPressed: {


switch(event.key){
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

De-indent this line a bit

//if A is pressed
//change color to red

case Qt.Key_A:
box_front.color = "red"
box_crab.color = "white";
box_four.color="white"
driving_mode_switching.sendmessage();
break;

if(button === 4) { // Left Buffer
camera_switching.camera_number = (start_number - 1) % 8;
} else if(button === 5) { // Right Buffer
camera_switching.camera_number = (start_number + 1) % 8;
//if r is pressed
//change color to red
case Qt.Key_S:
box_front.color = "white"
box_crab.color = "red";
box_four.color="white"
driving_mode_switching.sendmessage();
break;

case Qt.Key_D:
box_front.color="white"
box_crab.color = "white"
box_four.color = "red"
driving_mode_switching.sendmessage();
break;
default:
return;
}
event.accepted = true;
//Keys.enable = false;
}
}
}
}

DriveModeWidget {

DriveModeWidget {
id: drive_mode
anchors.right: parent.right
anchors.rightMargin: 0
anchors.left: signal_strength_container.left
anchors.leftMargin: 0
anchors.top: signal_strength_container.bottom
anchors.topMargin: 10
}
}


VoltageMeterWidget {
VoltageMeterWidget {
id: voltage_meter
anchors.right: parent.right
anchors.rightMargin: 0
Expand All @@ -213,7 +326,8 @@ Window {
anchors.topMargin: 30
}

ROSTimer {

ROSTimer {
// @disable-check M16
objectName: "timerDisplay"
id: timerDisplay
Expand All @@ -232,5 +346,38 @@ Window {
// @disable-check M16
height: 80


}

ROSJoystickListener {
// @disable-check M16
objectName: "bot_joystick"
// @disable-check M16
topic: "/joy"
// @disable-check M16
onButton_down: {
var start_number = camera_switching.camera_number;

// handle the case where no camera is selected
if(start_number < 0) {
start_number = 0;
}

if(button === 4) { // Left Buffer
camera_switching.camera_number = (start_number - 1) % 8;
} else if(button === 5) { // Right Buffer
camera_switching.camera_number = (start_number + 1) % 8;
}
}
}


}

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Unnecessary blank lines








9 changes: 7 additions & 2 deletions src/gui/src/main_application.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
#include <QDebug>
#include "ros_video_components/ros_video_component.hpp"
#include "ros_video_components/ros_signal_strength.hpp"
#include "ros_video_components/ros_driving_mode_switching.hpp"
#include "ros_video_components/ros_voltage_meter.hpp"
#include "ros_video_components/ros_camera_switching.hpp"
#include "ros_video_components/ros_timer.hpp"
Expand All @@ -14,6 +15,7 @@ Main_Application::Main_Application() {}
void Main_Application::run() {
qmlRegisterType<ROS_Video_Component>("bluesat.owr", 1, 0, "ROSVideoComponent");
qmlRegisterType<ROS_Signal_Strength>("bluesat.owr", 1, 0, "ROSSignalStrength");
qmlRegisterType<ROS_Driving_Mode_Switching>("bluesat.owr", 1, 0, "ROSDrivingModeSwitching");
qmlRegisterType<ROS_Voltage_Meter>("bluesat.owr", 1, 0, "ROSVoltageMeter");
qmlRegisterType<ROS_Camera_Switching>("bluesat.owr", 1, 0, "ROSCameraSwitching");
qmlRegisterType<ROSTimer>("bluesat.owr", 1, 0, "ROSTimer");
Expand All @@ -36,6 +38,9 @@ void Main_Application::run() {
ROS_Signal_Strength * signal_strength = this->rootObjects()[0]->findChild<ROS_Signal_Strength*>(QString("signal_strength"));
signal_strength->setup(&nh);

ROS_Driving_Mode_Switching* driving_mode_switching = this->rootObjects()[0]->findChild<ROS_Driving_Mode_Switching*>(QString("driving_mode_switching"));
driving_mode_switching ->setup(&nh);

ROS_Voltage_Meter * voltage_meter = this->rootObjects()[0]->findChild<ROS_Voltage_Meter*>(QString("voltage_meter"));
voltage_meter->setup(&nh);

Expand All @@ -51,11 +56,11 @@ void Main_Application::run() {
// setup the timer
ROSTimer * stopwatch = this->rootObjects()[0]->findChild<ROSTimer *>(QString("timerDisplay"));
// the following code section is for debugging
/*

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why did you comment the stopwatch in?

if (stopwatch != NULL) {
connect(stopwatch, SIGNAL(valueChanged(QString)), this, SLOT(handle(QString)));
}
*/

}

void Main_Application::main_loop() {
Expand Down
Loading