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
11 changes: 6 additions & 5 deletions idf/taskboard/main/hal/PbHubController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ struct PbHubController
const bool value)
{
uint8_t data = value;
read_operation(channel, Operation::WRITE_IO0, reinterpret_cast<uint8_t*>(&data), sizeof(data));
write_operation(channel, Operation::WRITE_IO0, reinterpret_cast<uint8_t*>(&data), sizeof(data));
}

/**
Expand All @@ -157,7 +157,7 @@ struct PbHubController
const bool value)
{
uint8_t data = value;
read_operation(channel, Operation::WRITE_IO1, reinterpret_cast<uint8_t*>(&data), sizeof(data));
write_operation(channel, Operation::WRITE_IO1, reinterpret_cast<uint8_t*>(&data), sizeof(data));
}

/**
Expand All @@ -171,7 +171,7 @@ struct PbHubController
const uint8_t value)
{
uint8_t data = value;
read_operation(channel, Operation::PWM_IO0, reinterpret_cast<uint8_t*>(&data), sizeof(data));
write_operation(channel, Operation::PWM_IO0, reinterpret_cast<uint8_t*>(&data), sizeof(data));
}

/**
Expand All @@ -185,7 +185,7 @@ struct PbHubController
const uint8_t value)
{
uint8_t data = value;
read_operation(channel, Operation::PWM_IO1, reinterpret_cast<uint8_t*>(&data), sizeof(data));
write_operation(channel, Operation::PWM_IO1, reinterpret_cast<uint8_t*>(&data), sizeof(data));
}

protected:
Expand Down Expand Up @@ -260,5 +260,6 @@ struct PbHubController

private:

const uint8_t i2c_addr_ = 0; ///< I2C address of PbHub device
// const uint8_t i2c_addr_ = 0; ///< I2C address of PbHub device
const uint8_t i2c_addr_ = DEFAULT_I2C_ADDR; ///< I2C address of PbHub device
};
36 changes: 28 additions & 8 deletions idf/taskboard/main/hal/board/TaskBoardDriver_TBv2025.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,24 +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_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);
});
Actuator* goal_2_led = new Actuator("GOAL_2_LED", [&](Actuator::State state)
{
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);
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO0(PbHubController::Channel::CHANNEL_5, state == Actuator::State::LED_ON);
});
Actuator* goal_3_led = new Actuator("GOAL_3_LED", [&](Actuator::State state)
{
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_IO0(PbHubController::Channel::CHANNEL_4, state == Actuator::State::LED_ON);
});
Actuator* goal_4_led = new Actuator("GOAL_4_LED", [&](Actuator::State state)
{
hardware_low_level_controller_.pb_hub_controller_1.write_PWM_IO1(PbHubController::Channel::CHANNEL_5, state == Actuator::State::LED_ON);
});
Actuator* blue_button_led = new Actuator("BLUE_BUTTON_LED", [&](Actuator::State state)
{
hardware_low_level_controller_.pb_hub_controller_2.write_PWM_IO0(PbHubController::Channel::CHANNEL_0, state == Actuator::State::LED_ON);
});
Actuator* red_button_led = new Actuator("RED_BUTTON_LED", [&](Actuator::State state)
{
hardware_low_level_controller_.pb_hub_controller_2.write_PWM_IO0(PbHubController::Channel::CHANNEL_1, 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);
// gpio_set_level(GPIO_NUM_27, state == Actuator::State::ON);
gpio_set_level(GPIO_NUM_27, 1);
});
Actuator* all_goal_leds = new Actuator("ALL_GOAL_LEDS", [&](Actuator::State state)
{
Expand All @@ -290,6 +298,8 @@ struct TaskBoardDriver_v1 :
actuators_.push_back(goal_2_led);
actuators_.push_back(goal_3_led);
actuators_.push_back(goal_4_led);
actuators_.push_back(blue_button_led);
actuators_.push_back(red_button_led);
actuators_.push_back(ball_drop_solenoid);
actuators_.push_back(all_goal_leds);

Expand Down Expand Up @@ -348,28 +358,38 @@ struct TaskBoardDriver_v1 :

std::vector<const TaskStepBase*>* main_steps = new std::vector<const TaskStepBase*>
{
new TaskStepActuator(*all_goal_leds, Actuator::State::LED_ON),
new TaskStepActuator(*blue_button_led, Actuator::State::LED_ON),
new TaskStepEqual(*get_sensor_by_name("BLUE_BUTTON_LEFT"), SensorMeasurement(true)),
new TaskStepActuator(*blue_button_led, Actuator::State::OFF),
new TaskStepEqual(*get_sensor_by_name("BLUE_BUTTON_LEFT"), SensorMeasurement(false)),
new TaskStepActuator(*red_button_led, Actuator::State::LED_ON),
new TaskStepEqual(*get_sensor_by_name("BLUE_BUTTON_RIGHT"), SensorMeasurement(true)),
new TaskStepActuator(*red_button_led, Actuator::State::OFF),
new TaskStepActuator(*all_goal_leds, Actuator::State::OFF),
new TaskStepActuator(*goal_4_led, Actuator::State::LED_ON),
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), // PS: task needs to be fixed touches aren't registered
new TaskStepActuator(*goal_2_led, Actuator::State::ON),
new TaskStepActuator(*goal_2_led, Actuator::State::LED_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 TaskStepActuator(*blue_button_led, Actuator::State::LED_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 TaskStepActuator(*blue_button_led, Actuator::State::OFF),
// do something here to assess if the ball has reached goal 1, maybe wait a fixed amount of time and return success if goal 1 is not made
new TaskStepActuator(*goal_1_led, Actuator::State::LED_ON),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_1"), SensorMeasurement(true)),
new TaskStepActuator(*goal_1_led, Actuator::State::OFF),
new TaskStepActuator(*goal_2_led, Actuator::State::LED_ON),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_2"), SensorMeasurement(true)),
new TaskStepActuator(*goal_2_led, Actuator::State::OFF),
new TaskStepActuator(*goal_3_led, Actuator::State::LED_ON),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_3"), SensorMeasurement(true)),
new TaskStepActuator(*goal_3_led, Actuator::State::OFF),
new TaskStepActuator(*goal_4_led, Actuator::State::LED_ON),
new TaskStepEqual(*get_sensor_by_name("BALL_GOAL_4"), SensorMeasurement(true)),
new TaskStepActuator(*goal_4_led, Actuator::State::OFF),

Expand Down
17 changes: 4 additions & 13 deletions idf/taskboard/main/main_core0.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,10 +125,6 @@ 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 Down Expand Up @@ -372,7 +368,6 @@ 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 Down Expand Up @@ -402,14 +397,10 @@ extern "C" void app_main(
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);
}
// briefly turn on then off the solenoid
gpio_set_level(GPIO_NUM_19, 1);
vTaskDelay(pdMS_TO_TICKS(500));
gpio_set_level(GPIO_NUM_19, 0);

// Button debounce delay
while (BUTTON_C.read() == true)
Expand Down
3 changes: 2 additions & 1 deletion idf/taskboard/main/sensor/Actuator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@ struct Actuator
enum State
{
OFF = 0,
ON = 1
ON = 1,
LED_ON = 255 // tried 10000, 1000, 255 but LED is still dim or flickering
};

/// @brief Function type for setting actuator state
Expand Down