Skip to content
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
28 changes: 28 additions & 0 deletions idf/taskboard/main/hal/PbHubController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,34 @@ struct PbHubController
read_operation(channel, Operation::WRITE_IO1, reinterpret_cast<uint8_t*>(&data), sizeof(data));
}

/**
* @brief Writes PWM value to IO0 pin
*
* @param channel Channel to write to
* @param value range 0 - 255
*/
void write_PWM_IO0(
const Channel channel,
const uint8_t value)
{
uint8_t data = value;
read_operation(channel, Operation::PWM_IO0, reinterpret_cast<uint8_t*>(&data), sizeof(data));
}

/**
* @brief Writes PWM value to IO1 pin
*
* @param channel Channel to write to
* @param value range 0 - 255
*/
void write_PWM_IO1(
const Channel channel,
const uint8_t value)
{
uint8_t data = value;
read_operation(channel, Operation::PWM_IO1, reinterpret_cast<uint8_t*>(&data), sizeof(data));
}

protected:

/**
Expand Down
53 changes: 28 additions & 25 deletions idf/taskboard/main/hal/board/TaskBoardDriver_TBv2025.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,35 +117,35 @@ struct TaskBoardDriver_v1 :
Sensor* blue_button_left = new Sensor("BLUE_BUTTON_LEFT", [&]()
{
bool value =
hardware_low_level_controller_.pb_hub_controller_1.read_digital_IO0(PbHubController::Channel::
CHANNEL_4);
hardware_low_level_controller_.pb_hub_controller_2.read_digital_IO1(PbHubController::Channel::
CHANNEL_0);

return SensorMeasurement(!value); // Button is inverted
});

Sensor* red_button_left = new Sensor("RED_BUTTON_LEFT", [&]()
{
bool value =
hardware_low_level_controller_.pb_hub_controller_1.read_digital_IO1(PbHubController::Channel::
CHANNEL_4);
hardware_low_level_controller_.pb_hub_controller_2.read_digital_IO1(PbHubController::Channel::
CHANNEL_0);

return SensorMeasurement(!value); // Button is inverted
});

Sensor* blue_button_right = new Sensor("BLUE_BUTTON_RIGHT", [&]()
{
bool value =
hardware_low_level_controller_.pb_hub_controller_1.read_digital_IO0(PbHubController::Channel::
CHANNEL_5);
hardware_low_level_controller_.pb_hub_controller_2.read_digital_IO1(PbHubController::Channel::
CHANNEL_1);

return SensorMeasurement(!value); // Button is inverted
});

Sensor* red_button_right = new Sensor("RED_BUTTON_RIGHT", [&]()
{
bool value =
hardware_low_level_controller_.pb_hub_controller_1.read_digital_IO1(PbHubController::Channel::
CHANNEL_5);
hardware_low_level_controller_.pb_hub_controller_2.read_digital_IO1(PbHubController::Channel::
CHANNEL_1);

return SensorMeasurement(!value); // Button is inverted
});
Expand Down Expand Up @@ -258,31 +258,32 @@ struct TaskBoardDriver_v1 :
// Initialize actuators
Actuator* goal_1_led = new Actuator("GOAL_1_LED", [&](Actuator::State state)
{
hardware_low_level_controller_.pb_hub_controller_2.write_digital_IO0(PbHubController::Channel::CHANNEL_0, state == Actuator::State::ON);
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO0(PbHubController::Channel::CHANNEL_4, state == Actuator::State::LED_ON);
});
Actuator* goal_2_led = new Actuator("GOAL_2_LED", [&](Actuator::State state)
{
hardware_low_level_controller_.pb_hub_controller_2.write_digital_IO0(PbHubController::Channel::CHANNEL_1, state == Actuator::State::ON);
ESP_LOGI("app_main", "setting value goal_2_led");
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO1(PbHubController::Channel::CHANNEL_4, state == Actuator::State::LED_ON);
});
Actuator* goal_3_led = new Actuator("GOAL_3_LED", [&](Actuator::State state)
{
hardware_low_level_controller_.pb_hub_controller_2.write_digital_IO0(PbHubController::Channel::CHANNEL_2, state == Actuator::State::ON);
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO0(PbHubController::Channel::CHANNEL_5, state == Actuator::State::LED_ON);
});
Actuator* goal_4_led = new Actuator("GOAL_4_LED", [&](Actuator::State state)
{
hardware_low_level_controller_.pb_hub_controller_2.write_digital_IO0(PbHubController::Channel::CHANNEL_3, state == Actuator::State::ON);
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO1(PbHubController::Channel::CHANNEL_5, state == Actuator::State::LED_ON);
});

Actuator* ball_drop_solenoid = new Actuator("BALL_DROP_SOLENOID", [&](Actuator::State state)
{
gpio_set_level(GPIO_NUM_27, state == Actuator::State::ON);
});
Actuator* all_goal_leds = new Actuator("ALL_GOAL_LEDS", [&](Actuator::State state)
{
hardware_low_level_controller_.pb_hub_controller_2.write_digital_IO0(PbHubController::Channel::CHANNEL_0, state == Actuator::State::ON);
hardware_low_level_controller_.pb_hub_controller_2.write_digital_IO0(PbHubController::Channel::CHANNEL_1, state == Actuator::State::ON);
hardware_low_level_controller_.pb_hub_controller_2.write_digital_IO0(PbHubController::Channel::CHANNEL_2, state == Actuator::State::ON);
hardware_low_level_controller_.pb_hub_controller_2.write_digital_IO0(PbHubController::Channel::CHANNEL_3, state == Actuator::State::ON);
ESP_LOGI("app_main", "setting values to all goal_leds");
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO0(PbHubController::Channel::CHANNEL_4, state == Actuator::State::LED_ON);
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO1(PbHubController::Channel::CHANNEL_4, state == Actuator::State::LED_ON);
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO0(PbHubController::Channel::CHANNEL_5, state == Actuator::State::LED_ON);
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO1(PbHubController::Channel::CHANNEL_5, state == Actuator::State::LED_ON);
});

actuators_.push_back(goal_1_led);
Expand Down Expand Up @@ -339,37 +340,39 @@ struct TaskBoardDriver_v1 :
new TaskStepActuator(*all_goal_leds, Actuator::State::OFF),
new TaskStepActuator(*ball_drop_solenoid, Actuator::State::OFF),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_1"), SensorMeasurement(true)),
new TaskStepEqual(*get_sensor_by_name("BLUE_BUTTON_RIGHT"), SensorMeasurement(true)),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_4"), SensorMeasurement(true)),
new TaskStepEqual(*get_sensor_by_name("RED_BUTTON_RIGHT"), SensorMeasurement(true)),
};

default_precondition_task_ = new SimultaneousConditionTask(*precondition_steps, "Precondition Task");

std::vector<const TaskStepBase*>* main_steps = new std::vector<const TaskStepBase*>
{
new TaskStepActuator(*all_goal_leds, Actuator::State::LED_ON),
new TaskStepEqual(*get_sensor_by_name("BLUE_BUTTON_LEFT"), SensorMeasurement(true)),
new TaskStepEqual(*get_sensor_by_name("BLUE_BUTTON_LEFT"), SensorMeasurement(false)),
new TaskStepEqual(*get_sensor_by_name("BLUE_BUTTON_RIGHT"), SensorMeasurement(true)),
new TaskStepActuator(*all_goal_leds, Actuator::State::OFF),
new TaskStepTraceShapeFromPool(*get_sensor_by_name("TOUCH_SCREEN"), shape_pool),
new TaskStepTraceShapeFromPool(*get_sensor_by_name("TOUCH_SCREEN"), shape_pool),
new TaskStepTraceShapeFromPool(*get_sensor_by_name("TOUCH_SCREEN"), shape_pool),
new TaskStepTouchGoalFromPool(*get_sensor_by_name("TOUCH_SCREEN"), touch_goal_pool),
new TaskStepTouchGoalFromPool(*get_sensor_by_name("TOUCH_SCREEN"), touch_goal_pool),
new TaskStepTouchGoalFromPool(*get_sensor_by_name("TOUCH_SCREEN"), touch_goal_pool),
new TaskStepTouchGoalFromPool(*get_sensor_by_name("TOUCH_SCREEN"), touch_goal_pool),
new TaskStepTouchGoalFromPool(*get_sensor_by_name("TOUCH_SCREEN"), touch_goal_pool),
new TaskStepTouchGoalFromPool(*get_sensor_by_name("TOUCH_SCREEN"), touch_goal_pool), // PS: task needs to be fixed touches aren't registered
new TaskStepActuator(*goal_2_led, Actuator::State::ON),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_2"), SensorMeasurement(true)),
new TaskStepActuator(*goal_2_led, Actuator::State::OFF),
new TaskStepActuator(*ball_drop_solenoid, Actuator::State::ON),
new TaskStepEqualDuringRandom(*get_sensor_by_name("BLUE_BUTTON_LEFT"), SensorMeasurement(true), 0.0, 3000L, 8000L),
new TaskStepActuator(*ball_drop_solenoid, Actuator::State::OFF),
new TaskStepActuator(*all_goal_leds, Actuator::State::ON),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_1"), SensorMeasurement(true)),
new TaskStepActuator(*goal_1_led, Actuator::State::OFF),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_2"), SensorMeasurement(true)),
new TaskStepActuator(*goal_2_led, Actuator::State::OFF),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_3"), SensorMeasurement(true)),
new TaskStepActuator(*goal_3_led, Actuator::State::OFF),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_4"), SensorMeasurement(true)),
new TaskStepActuator(*goal_4_led, Actuator::State::OFF),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_2"), SensorMeasurement(true)),
new TaskStepActuator(*goal_2_led, Actuator::State::OFF),

};

default_task_ = new SequentialTask(*main_steps, "Default Task");
Expand Down
50 changes: 50 additions & 0 deletions idf/taskboard/main/main_core0.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,30 @@ void websockets_task(
extern "C" void app_main(
void)
{
// Cycle the solenoid at start up
esp_err_t ret_output;
ret_output = gpio_reset_pin(GPIO_NUM_19);
if (ret_output != ESP_OK) {
ESP_LOGE("GPIO", "Failed to reset pin 19");
return;
}
ret_output = gpio_set_direction(GPIO_NUM_19, GPIO_MODE_OUTPUT);
if (ret_output != ESP_OK) {
ESP_LOGE("GPIO", "Failed to set pin 19 direction");
return;
}
ret_output = gpio_set_level(GPIO_NUM_19, 1);
if (ret_output != ESP_OK) {
ESP_LOGE("GPIO", "Failed to set pin 19 level");
return;
}
vTaskDelay(pdMS_TO_TICKS(1000));
ret_output = gpio_set_level(GPIO_NUM_19, 0);
if (ret_output != ESP_OK) {
ESP_LOGE("GPIO", "Failed to set pin 19 level");
return;
}

// ------------------------
// System Initialization
// ------------------------
Expand Down Expand Up @@ -101,6 +125,10 @@ extern "C" void app_main(
screen_controller.clear();
screen_controller.print("-> TaskExecutor started");

screen_controller.turn_on_gate_LED_clue();
vTaskDelay(pdMS_TO_TICKS(1000));
screen_controller.turn_off_gate_LED_clue();

// Initialize micro-ROS for ROS communication
MicroROSController micro_ros_controller;

Expand All @@ -117,6 +145,7 @@ extern "C" void app_main(
// Get references to buttons
const SensorReader& BUTTON_A = *task_board_driver.get_sensor_by_name("ON_BOARD_BUTTON_A");
const SensorReader& BUTTON_B = *task_board_driver.get_sensor_by_name("ON_BOARD_BUTTON_B");
const SensorReader& BUTTON_C = *task_board_driver.get_sensor_by_name("ON_BOARD_BUTTON_C");
const SensorReader& BUTTON_PWR = *task_board_driver.get_sensor_by_name("ON_BOARD_BUTTON_PWR");
const SensorReader& RED_BUTTON = nullptr != task_board_driver.get_sensor_by_name("RED_BUTTON") ?
*task_board_driver.get_sensor_by_name("RED_BUTTON") :
Expand Down Expand Up @@ -343,6 +372,7 @@ extern "C" void app_main(
{
ESP_LOGI("app_main", "Button A pressed, cancelling current task");
task_executor.cancel_task();
gpio_set_level(GPIO_NUM_19, 0); // force off the solenoid

// Update screen with cancellation message
screen_controller.clear();
Expand All @@ -368,6 +398,26 @@ extern "C" void app_main(
task_board_driver.update();
}
}
// Handle Button C press - Toggle solenoid
else if (BUTTON_C.read() == true)
{
ESP_LOGI("app_main", "Button C pressed, toggle solenoid");
if (!gpio_get_level(GPIO_NUM_19))
{
gpio_set_level(GPIO_NUM_19, 1);
// TAKE CARE THAT THE SOLENOID IS NOT LEFT ON LONGER THAN 5 SECONDS OR IT GETS VERY HOT
// TODO: ADD TIMER TO TURN SOLENOID OFF AFTER TURNING IT ON.
} else {
gpio_set_level(GPIO_NUM_19, 0);
}

// Button debounce delay
while (BUTTON_C.read() == true)
{
vTaskDelay(pdMS_TO_TICKS(10));
task_board_driver.update();
}
}

// If notifed by Micro-ROS task, cancel current task
uint32_t value;
Expand Down
Loading