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

Add manual mower control actions in AreaRecording mode #162

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
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
2 changes: 1 addition & 1 deletion .github/workflows/build-image.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ permissions:

jobs:
build:
runs-on: ubuntu-latest
runs-on: ubuntu-22.04
strategy:
matrix:
docker_build_arch: [ linux/arm64 , linux/amd64 ]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -217,8 +217,7 @@ bool AreaRecordingBehavior::needs_gps() {
}

bool AreaRecordingBehavior::mower_enabled() {
// No mower during docking
return false;
return manual_mowing;
}

void AreaRecordingBehavior::pose_received(const xbot_msgs::AbsolutePose::ConstPtr &msg) {
Expand Down Expand Up @@ -578,6 +577,12 @@ void AreaRecordingBehavior::handle_action(std::string action) {
} else if (action == "mower_logic:area_recording/collect_point") {
ROS_INFO_STREAM("Got collect point");
collect_point = true;
} else if (action == "mower_logic:area_recording/start_manual_mowing") {
ROS_INFO_STREAM("Starting manual mowing");
manual_mowing = true;
} else if (action == "mower_logic:area_recording/stop_manual_mowing") {
ROS_INFO_STREAM("Stopping manual mowing");
manual_mowing = false;
}
update_actions();
}
Expand Down Expand Up @@ -633,6 +638,16 @@ AreaRecordingBehavior::AreaRecordingBehavior() {
collect_point_action.enabled = false;
collect_point_action.action_name = "Collect point";

xbot_msgs::ActionInfo start_manual_mowing_action;
start_manual_mowing_action.action_id = "start_manual_mowing";
start_manual_mowing_action.enabled = false;
start_manual_mowing_action.action_name = "Start manual mowing";

xbot_msgs::ActionInfo stop_manual_mowing_action;
stop_manual_mowing_action.action_id = "stop_manual_mowing";
stop_manual_mowing_action.enabled = false;
stop_manual_mowing_action.action_name = "Stop manual mowing";

actions.clear();
actions.push_back(start_recording_action);
actions.push_back(stop_recording_action);
Expand All @@ -644,6 +659,8 @@ AreaRecordingBehavior::AreaRecordingBehavior() {
actions.push_back(auto_point_collecting_enable_action);
actions.push_back(auto_point_collecting_disable_action);
actions.push_back(collect_point_action);
actions.push_back(start_manual_mowing_action);
actions.push_back(stop_manual_mowing_action);
}

void AreaRecordingBehavior::update_actions() {
Expand Down Expand Up @@ -681,6 +698,10 @@ void AreaRecordingBehavior::update_actions() {
actions[6].enabled = true;
}
}
// start_manual_mowing
actions[10].enabled = !manual_mowing;
// stop manual mowing
actions[11].enabled = manual_mowing;

registerActions("mower_logic:area_recording", actions);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,8 @@ class AreaRecordingBehavior : public Behavior {
bool auto_point_collecting = true;
bool collect_point = false;

bool manual_mowing = false;

visualization_msgs::MarkerArray markers;
visualization_msgs::Marker marker;

Expand Down
Loading