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

Handle IdleBehavior::DOCKED_INSTANCE in more places #120

Merged
merged 1 commit into from
Jul 8, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions src/mower_logic/src/mower_logic/behaviors/IdleBehavior.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ Behavior *IdleBehavior::execute() {
!last_config.manual_pause_mowing;

if (manual_start_mowing || ((automatic_mode || active_semiautomatic_task) && mower_ready)) {
// set the robot's position to the dock if we're actually docked
// set the robot's position to the dock if we're actually docked
if(last_status.v_charge > 5.0) {
if (PerimeterUndockingBehavior::configured(config))
return &PerimeterUndockingBehavior::INSTANCE;
Expand Down Expand Up @@ -158,7 +158,7 @@ void IdleBehavior::command_s1() {
}

void IdleBehavior::command_s2() {

}

bool IdleBehavior::redirect_joystick() {
Expand Down
13 changes: 6 additions & 7 deletions src/mower_logic/src/mower_logic/behaviors/PerimeterDocking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,15 +100,15 @@ Behavior* PerimeterSearchBehavior::execute() {
/* We expect to be currently outside the perimeter wire => negative signal */
calibrationLeft=calibrationRight=signCenter=
lastPerimeter.left<0 ? 1 : -1; // Determine polarity of the cable.

if (innerSignal()>-MIN_SIGNAL || outerSignal()>-MIN_SIGNAL) {
ROS_ERROR("Signal too weak.");
return shutdownConnections();
}
calibrationLeft/=fabs(lastPerimeter.left);
maxCenter=fabs(lastPerimeter.center);
calibrationRight/=fabs(lastPerimeter.right);

geometry_msgs::Twist vel;
/* Move straight until one of the signals changes to positive (inside) */
vel.angular.z=0;
Expand Down Expand Up @@ -177,7 +177,7 @@ Behavior* PerimeterUndockingBehavior::execute() {
// Determine polarity of the cable.
calibrationLeft=calibrationRight=signCenter=1;
if (innerSignal()<0) calibrationLeft=calibrationRight=signCenter=-1;

float maxLeft=lastPerimeter.left*calibrationLeft;
maxCenter=fabs(lastPerimeter.center);
float maxRight=lastPerimeter.right*calibrationRight;;
Expand All @@ -202,7 +202,7 @@ Behavior* PerimeterUndockingBehavior::execute() {
ROS_ERROR("Could not turn inwards");
return shutdownConnections();
}

if (maxLeft<MIN_SIGNAL || maxRight<MIN_SIGNAL) {
ROS_ERROR("Signal too weak.");
return shutdownConnections();
Expand All @@ -228,12 +228,12 @@ Behavior* PerimeterDockingBehavior::arrived() {
chargeSeen++;
if (chargeSeen>=2) {
chargeSeen=0;
return &IdleBehavior::INSTANCE;
return &IdleBehavior::DOCKED_INSTANCE;
}
} else {
chargeSeen=0;
}
return NULL;
return NULL;
}

Behavior* PerimeterFollowBehavior::execute() {
Expand Down Expand Up @@ -381,4 +381,3 @@ std::string PerimeterMoveToGpsBehavior::state_name() {
Behavior* PerimeterMoveToGpsBehavior::arrived() {
return travelled>=config.undock_distance-0.9 ? &MowingBehavior::INSTANCE : NULL;
}

9 changes: 4 additions & 5 deletions src/mower_logic/src/mower_logic/mower_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -396,7 +396,7 @@ void checkSafety(const ros::TimerEvent &timer_event) {
if (currentBehavior != nullptr) {
if (last_status.emergency) {
currentBehavior->requestPause(pauseType::PAUSE_EMERGENCY);
if (currentBehavior == &AreaRecordingBehavior::INSTANCE || currentBehavior == &IdleBehavior::INSTANCE) {
if (currentBehavior == &AreaRecordingBehavior::INSTANCE || currentBehavior == &IdleBehavior::INSTANCE || currentBehavior == &IdleBehavior::DOCKED_INSTANCE) {
if (last_status.v_charge > 10.0) {
// emergency and docked and idle or area recording, so it's safe to reset the emergency mode, reset it. It's safe since we won't start moving in this mode.
setEmergencyMode(false);
Expand Down Expand Up @@ -517,7 +517,8 @@ void checkSafety(const ros::TimerEvent &timer_event) {
dockingNeeded &&
currentBehavior != &DockingBehavior::INSTANCE &&
currentBehavior != &UndockingBehavior::RETRY_INSTANCE &&
currentBehavior != &IdleBehavior::INSTANCE
currentBehavior != &IdleBehavior::INSTANCE &&
currentBehavior != &IdleBehavior::DOCKED_INSTANCE
) {
ROS_INFO_STREAM(dockingReason.rdbuf());
abortExecution();
Expand Down Expand Up @@ -558,8 +559,7 @@ bool highLevelCommand(mower_msgs::HighLevelControlSrvRequest &req, mower_msgs::H
case mower_msgs::HighLevelControlSrvRequest::COMMAND_DELETE_MAPS: {
ROS_WARN_STREAM("COMMAND_DELETE_MAPS");
if (currentBehavior != &AreaRecordingBehavior::INSTANCE && currentBehavior != &IdleBehavior::INSTANCE &&
currentBehavior !=
nullptr) {
currentBehavior != &IdleBehavior::DOCKED_INSTANCE && currentBehavior != nullptr) {
ROS_ERROR_STREAM("Deleting maps is only allowed during IDLE or AreaRecording!");
return true;
}
Expand Down Expand Up @@ -861,4 +861,3 @@ int main(int argc, char **argv) {
delete (mbfClientExePath);
return 0;
}