Skip to content

Commit 4d66f3c

Browse files
committed
Don't accept manual waypoint input for rover's in autonomous mode
Added map to MapData indicating rover modes. When a user clicks in the map frame we consult that map and if the mode is not manual then the click is ignored. This addresses issue #116 by simply preventing that situation.
1 parent 7881f87 commit 4d66f3c

File tree

5 files changed

+56
-2
lines changed

5 files changed

+56
-2
lines changed

src/rqt_rover_gui/src/MapData.cpp

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -153,6 +153,7 @@ void MapData::clear()
153153
target_locations.clear();
154154
collection_points.clear();
155155
waypoint_path.clear();
156+
rover_mode.clear();
156157

157158
update_mutex.unlock();
158159
}
@@ -175,6 +176,7 @@ void MapData::clear(string rover)
175176
gps_rover_path.erase(rover);
176177
target_locations.erase(rover);
177178
collection_points.erase(rover);
179+
rover_mode.erase(rover);
178180

179181
update_mutex.unlock();
180182
}
@@ -344,6 +346,25 @@ float MapData::getMinEncoderY(string rover_name)
344346
return min_encoder_seen_y[rover_name];
345347
}
346348

349+
bool MapData::inManualMode(string rover_name)
350+
{
351+
return rover_mode[rover_name] == 0;
352+
}
353+
354+
void MapData::setAutonomousMode(string rover_name)
355+
{
356+
update_mutex.lock();
357+
rover_mode[rover_name] = 1;
358+
update_mutex.unlock();
359+
}
360+
361+
void MapData::setManualMode(string rover_name)
362+
{
363+
update_mutex.lock();
364+
rover_mode[rover_name] = 0;
365+
update_mutex.unlock();
366+
}
367+
347368
void MapData::lock()
348369
{
349370
update_mutex.lock();

src/rqt_rover_gui/src/MapData.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,10 @@ class MapData
6363
float getMinEncoderX(std::string rover_name);
6464
float getMinEncoderY(std::string rover_name);
6565

66+
bool inManualMode(std::string rover_name);
67+
void setAutonomousMode(std::string rover_name);
68+
void setManualMode(std::string rover_name);
69+
6670
~MapData();
6771

6872
private:
@@ -100,6 +104,7 @@ class MapData
100104
QMutex update_mutex; // To prevent race conditions when the data is being displayed by MapFrame
101105

102106
std::string currently_selected_rover;
107+
std::map<std::string, int> rover_mode;
103108

104109
int waypoint_id_counter = 0;
105110
};

src/rqt_rover_gui/src/MapFrame.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -624,6 +624,10 @@ void MapFrame::mouseReleaseEvent(QMouseEvent *event)
624624

625625
void MapFrame::mousePressEvent(QMouseEvent *event)
626626
{
627+
if(! map_data->inManualMode(rover_currently_selected))
628+
{
629+
return;
630+
}
627631

628632
float waypoint_click_tolerance = 0.25*(scale/10);
629633

@@ -896,6 +900,16 @@ void MapFrame::receiveCurrentRoverName( QString rover_name )
896900
}
897901
}
898902

903+
void MapFrame::enableWaypoints(string rover_name)
904+
{
905+
map_data->setManualMode(rover_name);
906+
}
907+
908+
void MapFrame::disableWaypoints(string rover_name)
909+
{
910+
map_data->setAutonomousMode(rover_name);
911+
}
912+
899913
MapFrame::~MapFrame()
900914
{
901915
// Safely erase map data - locks to make sure a frame isnt being drawn

src/rqt_rover_gui/src/MapFrame.h

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,10 @@ namespace rqt_rover_gui
8282
// Calculate scale and transform to keep all data in the map frame
8383
// Excludes manual trasform
8484
void setAutoTransform();
85-
85+
86+
void enableWaypoints(std::string rover);
87+
void disableWaypoints(std::string rover);
88+
8689
// Show a copy of the map in its own resizable window
8790
void popout();
8891

@@ -181,7 +184,12 @@ namespace rqt_rover_gui
181184
float max_seen_height = -std::numeric_limits<float>::max();
182185

183186
std::string rover_currently_selected; // This is the rover selected in the main GUI.
184-
187+
188+
enum mode {
189+
AUTONOMOUS,
190+
MANUAL
191+
};
192+
std::map<std::string, bool> rover_mode;
185193
};
186194

187195
}

src/rqt_rover_gui/src/rover_gui_plugin.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1273,6 +1273,9 @@ void RoverGUIPlugin::autonomousRadioButtonEventHandler(bool marked)
12731273

12741274
//Hide joystick frame
12751275
ui.joystick_frame->setHidden(true);
1276+
1277+
// disable waypoint input in map frame
1278+
ui.map_frame->disableWaypoints(selected_rover_name);
12761279
}
12771280

12781281
void RoverGUIPlugin::joystickRadioButtonEventHandler(bool marked)
@@ -1316,6 +1319,9 @@ void RoverGUIPlugin::joystickRadioButtonEventHandler(bool marked)
13161319

13171320
//Show joystick frame
13181321
ui.joystick_frame->setHidden(false);
1322+
1323+
// enable wayoint input in the map frame
1324+
ui.map_frame->enableWaypoints(selected_rover_name);
13191325
}
13201326

13211327
void RoverGUIPlugin::allAutonomousButtonEventHandler()

0 commit comments

Comments
 (0)