Skip to content
This repository has been archived by the owner on Dec 15, 2023. It is now read-only.

Commit

Permalink
Clear irrelevant logic from controller
Browse files Browse the repository at this point in the history
  • Loading branch information
minghongx committed May 15, 2023
1 parent a800acb commit b03eefa
Showing 1 changed file with 0 additions and 18 deletions.
18 changes: 0 additions & 18 deletions nodes/controller.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <numbers>

#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/bool.hpp>
#include <geometry_msgs/msg/twist.hpp>

#include <pybind11/pybind11.h>
Expand Down Expand Up @@ -51,9 +50,6 @@ class Controller : public rclcpp::Node {
// FIXME: QoS profile
cmd_vel_ = this->create_subscription<geometry_msgs::msg::Twist>(
"/cmd_vel", 10, std::bind(&Controller::cmd_vel, this, _1));

duck_detected_ = this->create_subscription<std_msgs::msg::Bool>(
"/duck_detected", 10, std::bind(&Controller::duck_detected, this, _1));
}

private:
Expand Down Expand Up @@ -93,19 +89,6 @@ class Controller : public rclcpp::Node {
rmotor.attr("throttle") = 0.0;
}

// TODO: Two fns for unsub and resub /cmd_vel
void
duck_detected(const std_msgs::msg::Bool::SharedPtr detected) {
if (detected->data == true) {
brake();
cmd_vel_.reset(); // Unsubscribe /cmd_vel
} else {
// Resubscribe /cmd_vel
cmd_vel_ = this->create_subscription<geometry_msgs::msg::Twist>(
"/cmd_vel", 10, std::bind(&Controller::cmd_vel, this, _1));
}
}

// https://adafruit.com/product/2927
// https://adafruit.com/product/3777
py::object MotorKit = py::module::import("adafruit_motorkit").attr("MotorKit");
Expand All @@ -115,7 +98,6 @@ class Controller : public rclcpp::Node {

rclcpp::TimerBase::SharedPtr cmd_vel_timeout_;
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_;
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr duck_detected_;
};


Expand Down

0 comments on commit b03eefa

Please sign in to comment.