Skip to content

Commit

Permalink
Allow aborting Docking/Undocking
Browse files Browse the repository at this point in the history
Pressing "Home" when undocking aborts it, and pressing "play" when docking aborts it.

Uninterruptable docking can be a real problem if your mower is stuck trying to return to the dock and you want to tele-operate it.  This adds button controls, as well as actions which can be used from the GUI.
  • Loading branch information
jeremysalwen committed Aug 12, 2024
1 parent 671c109 commit 09218b1
Show file tree
Hide file tree
Showing 4 changed files with 145 additions and 8 deletions.
91 changes: 85 additions & 6 deletions src/mower_logic/src/mower_logic/behaviors/DockingBehavior.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,20 @@ extern mower_msgs::Status getStatus();
extern void stopMoving();
extern bool setGPS(bool enabled);

extern void registerActions(std::string prefix, const std::vector<xbot_msgs::ActionInfo> &actions);

DockingBehavior DockingBehavior::INSTANCE;

DockingBehavior::DockingBehavior() {
xbot_msgs::ActionInfo abort_docking_action;
abort_docking_action.action_id = "abort_docking";
abort_docking_action.enabled = true;
abort_docking_action.action_name = "Stop Docking";

actions.clear();
actions.push_back(abort_docking_action);
}

bool DockingBehavior::approach_docking_point() {
ROS_INFO_STREAM("Calculating approach path");

Expand All @@ -47,9 +59,27 @@ bool DockingBehavior::approach_docking_point() {
mbf_msgs::MoveBaseGoal moveBaseGoal;
moveBaseGoal.target_pose = docking_approach_point;
moveBaseGoal.controller = "FTCPlanner";
auto result = mbfClient->sendGoalAndWait(moveBaseGoal);
if (result.state_ != result.SUCCEEDED) {
return false;

mbfClient->sendGoal(moveBaseGoal);

ros::Rate r(10);
bool waitingForResult = true;

while (waitingForResult) {
r.sleep();
if (aborted) {
ROS_INFO_STREAM("Docking aborted.");
mbfClientExePath->cancelGoal();
stopMoving();
return false;
}

switch (mbfClientExePath->getState().state_) {
case actionlib::SimpleClientGoalState::ACTIVE:
case actionlib::SimpleClientGoalState::PENDING: break;
case actionlib::SimpleClientGoalState::SUCCEEDED: waitingForResult = false; break;
default: return false;
}
}
}

Expand All @@ -73,9 +103,26 @@ bool DockingBehavior::approach_docking_point() {
exePathGoal.controller = "FTCPlanner";
ROS_INFO_STREAM("Executing Docking Approach");

auto approachResult = mbfClientExePath->sendGoalAndWait(exePathGoal);
if (approachResult.state_ != approachResult.SUCCEEDED) {
return false;
mbfClientExePath->sendGoal(exePathGoal);

ros::Rate r(10);
bool waitingForResult = true;

while (waitingForResult) {
r.sleep();
if (aborted) {
ROS_INFO_STREAM("Docking aborted.");
mbfClientExePath->cancelGoal();
stopMoving();
return false;
}

switch (mbfClientExePath->getState().state_) {
case actionlib::SimpleClientGoalState::ACTIVE:
case actionlib::SimpleClientGoalState::PENDING: break;
case actionlib::SimpleClientGoalState::SUCCEEDED: waitingForResult = false; break;
default: return false;
}
}
}

Expand Down Expand Up @@ -179,12 +226,24 @@ Behavior *DockingBehavior::execute() {
}

while (!isGPSGood) {
if (aborted) {
ROS_INFO_STREAM("Docking aborted.");
stopMoving();
return &IdleBehavior::INSTANCE;
}

ROS_WARN_STREAM("Waiting for good GPS");
ros::Duration(1.0).sleep();
}

bool approachSuccess = approach_docking_point();

if (aborted) {
ROS_INFO_STREAM("Docking aborted.");
stopMoving();
return &IdleBehavior::INSTANCE;
}

if (!approachSuccess) {
ROS_ERROR("Error during docking approach.");

Expand All @@ -209,6 +268,12 @@ Behavior *DockingBehavior::execute() {

bool docked = dock_straight();

if (aborted) {
ROS_INFO_STREAM("Docking aborted.");
stopMoving();
return &IdleBehavior::INSTANCE;
}

if (!docked) {
ROS_ERROR("Error during docking.");

Expand Down Expand Up @@ -241,9 +306,18 @@ void DockingBehavior::enter() {
docking_pose_stamped.pose = get_docking_point_srv.response.docking_pose;
docking_pose_stamped.header.frame_id = "map";
docking_pose_stamped.header.stamp = ros::Time::now();

for (auto &a : actions) {
a.enabled = true;
}
registerActions("mower_logic:docking", actions);
}

void DockingBehavior::exit() {
for (auto &a : actions) {
a.enabled = false;
}
registerActions("mower_logic:docking", actions);
}

void DockingBehavior::reset() {
Expand All @@ -264,6 +338,7 @@ void DockingBehavior::command_home() {
}

void DockingBehavior::command_start() {
this->abort();
}

void DockingBehavior::command_s1() {
Expand All @@ -284,4 +359,8 @@ uint8_t DockingBehavior::get_state() {
}

void DockingBehavior::handle_action(std::string action) {
if (action == "mower_logic:docking/abort_docking") {
ROS_INFO_STREAM("Got abort docking command");
command_start();
}
}
5 changes: 5 additions & 0 deletions src/mower_logic/src/mower_logic/behaviors/DockingBehavior.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,15 @@
#include "mower_msgs/Status.h"
#include "ros/ros.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include "xbot_msgs/ActionInfo.h"

class DockingBehavior : public Behavior {
public:
static DockingBehavior INSTANCE;

private:
std::vector<xbot_msgs::ActionInfo> actions;

uint retryCount;
bool inApproachMode;
geometry_msgs::PoseStamped docking_pose_stamped;
Expand All @@ -46,6 +49,8 @@ class DockingBehavior : public Behavior {
bool dock_straight();

public:
DockingBehavior();

std::string state_name() override;

Behavior *execute() override;
Expand Down
52 changes: 50 additions & 2 deletions src/mower_logic/src/mower_logic/behaviors/UndockingBehavior.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,21 @@ extern void stopMoving();
extern bool isGpsGood();
extern bool setGPS(bool enabled);

extern void registerActions(std::string prefix, const std::vector<xbot_msgs::ActionInfo> &actions);

UndockingBehavior UndockingBehavior::INSTANCE(&MowingBehavior::INSTANCE);
UndockingBehavior UndockingBehavior::RETRY_INSTANCE(&DockingBehavior::INSTANCE);

UndockingBehavior::UndockingBehavior() {
xbot_msgs::ActionInfo abort_docking_action;
abort_docking_action.action_id = "abort_undocking";
abort_docking_action.enabled = true;
abort_docking_action.action_name = "Stop Undocking";

actions.clear();
actions.push_back(abort_docking_action);
}

std::string UndockingBehavior::state_name() {
return "UNDOCKING";
}
Expand Down Expand Up @@ -63,9 +75,31 @@ Behavior *UndockingBehavior::execute() {
exePathGoal.tolerance_from_action = true;
exePathGoal.controller = "DockingFTCPlanner";

auto result = mbfClientExePath->sendGoalAndWait(exePathGoal);
mbfClientExePath->sendGoal(exePathGoal);

bool success = result.state_ == actionlib::SimpleClientGoalState::SUCCEEDED;
ros::Rate r(10);
bool waitingForResult = true;
bool success = false;

while (waitingForResult) {
r.sleep();
if (aborted) {
ROS_INFO_STREAM("Undocking aborted.");
mbfClientExePath->cancelGoal();
stopMoving();
return &IdleBehavior::INSTANCE;
}

switch (mbfClientExePath->getState().state_) {
case actionlib::SimpleClientGoalState::ACTIVE:
case actionlib::SimpleClientGoalState::PENDING: break;
case actionlib::SimpleClientGoalState::SUCCEEDED:
waitingForResult = false;
success = true;
break;
default: waitingForResult = false; break;
}
}

// stop the bot for now
stopMoving();
Expand Down Expand Up @@ -103,9 +137,18 @@ void UndockingBehavior::enter() {
ROS_INFO_STREAM("Currently inside the docking station, we set the robot's pose to the docks pose.");
setRobotPose(docking_pose_stamped.pose);
}

for (auto &a : actions) {
a.enabled = true;
}
registerActions("mower_logic:undocking", actions);
}

void UndockingBehavior::exit() {
for (auto &a : actions) {
a.enabled = false;
}
registerActions("mower_logic:undocking", actions);
}

void UndockingBehavior::reset() {
Expand Down Expand Up @@ -152,6 +195,7 @@ UndockingBehavior::UndockingBehavior(Behavior *next) {
}

void UndockingBehavior::command_home() {
this->abort();
}

void UndockingBehavior::command_start() {
Expand All @@ -175,4 +219,8 @@ uint8_t UndockingBehavior::get_state() {
}

void UndockingBehavior::handle_action(std::string action) {
if (action == "mower_logic:undocking/abort_undocking") {
ROS_INFO_STREAM("Got abort undocking command");
command_home();
}
}
5 changes: 5 additions & 0 deletions src/mower_logic/src/mower_logic/behaviors/UndockingBehavior.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include "ros/ros.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include "xbot_msgs/AbsolutePose.h"
#include "xbot_msgs/ActionInfo.h"

class UndockingBehavior : public Behavior {
public:
Expand All @@ -38,13 +39,17 @@ class UndockingBehavior : public Behavior {
UndockingBehavior(Behavior* nextBehavior);

private:
std::vector<xbot_msgs::ActionInfo> actions;

Behavior* nextBehavior;
geometry_msgs::PoseStamped docking_pose_stamped;
bool gpsRequired;

bool waitForGPS();

public:
UndockingBehavior();

std::string state_name() override;

Behavior* execute() override;
Expand Down

0 comments on commit 09218b1

Please sign in to comment.