Skip to content

Commit

Permalink
lint
Browse files Browse the repository at this point in the history
  • Loading branch information
MaxxWilson committed Mar 1, 2025
1 parent ea0d2c2 commit 1561d25
Show file tree
Hide file tree
Showing 4 changed files with 325 additions and 317 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,11 @@ namespace ghost_tank
{

// SyncActionNode (synchronous action) with an input port.
class MoveToPoseBoomerang : public BT::StatefulActionNode {
class MoveToPoseBoomerang : public BT::StatefulActionNode
{
public:
// If your Node has ports, you must use this constructor signature
MoveToPoseBoomerang(const std::string& name, const BT::NodeConfig& config);
// If your Node has ports, you must use this constructor signature
MoveToPoseBoomerang(const std::string & name, const BT::NodeConfig & config);

// It is mandatory to define this STATIC method.
static BT::PortsList providedPorts();
Expand All @@ -73,12 +74,12 @@ class MoveToPoseBoomerang : public BT::StatefulActionNode {
std::chrono::time_point<std::chrono::system_clock> plan_time_;
std::shared_ptr<rclcpp::Node> node_ptr_;
std::shared_ptr<Boomerang> boomerang_;
BT::Blackboard::Ptr blackboard_;
BT::Blackboard::Ptr blackboard_;

bool started_;
int past_index_;
std::shared_ptr<PDControl> pd_control_ptr_;
ghost_planners::RobotTrajectory robot_trajectory_;
ghost_planners::RobotTrajectory robot_trajectory_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr trajectory_viz_pub_;
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr curr_angle_pub;
rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr des_angle_pub;
Expand Down
16 changes: 8 additions & 8 deletions 11_Robots/ghost_tank/include/ghost_tank/tank_robot_plugin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,21 +81,21 @@ class TankRobotPlugin : public ghost_ros_interfaces::V5RobotBase
// Teleop
bool runAutonFromDriver(std::shared_ptr<ghost_v5_interfaces::devices::JoystickDeviceData> joy_data, double current_time);
void toggleBagRecorder(std::shared_ptr<ghost_v5_interfaces::devices::JoystickDeviceData> joy_data);

/**
* @brief Handles intaking logic
*
*
* Holding R2 alone intakes the Ground Pickup, and aligns the next conveyor hook for intaking rings
* Holding R alone outtakes the Ground Pickup
* Holding R1 intakes the Conveyor
* Holding L1 alone outtakes the Conveyor
* Holding R2 and L1 will initiate the ejector sequence for the current ring
*
* @param R2
* @param R1
* @param L1
* @param R
* @param current_time
*
* @param R2
* @param R1
* @param L1
* @param R
* @param current_time
*/
void updateIntake(bool R2, bool R1, bool L1, bool R, double current_time);
void updateClamp(std::shared_ptr<ghost_v5_interfaces::devices::JoystickDeviceData> joy_data);
Expand Down
Loading

0 comments on commit 1561d25

Please sign in to comment.