Skip to content

Commit

Permalink
feat(base_component): add new base component and improve I2C class + …
Browse files Browse the repository at this point in the history
…example (#149)

* feat(base_component): add new base component
* Add base component which contains logger with some methods for setting logging level and tag for the logger
* Update i2c to subclass base component and add some extra methods for writing / reading with std::vector. Also added some logging to the i2c component
* Add i2c format helpers for logging the i2c bus which is initialized
* Add missing i2c destructor
* Update i2c example to test new i2c destructor
* Add i2c menu to i2c example for allowing interactive control / query of the i2c bus using cli component
* Update i2c and cli component to have s3 defualts file configuring the console output port to be usb serial/jtag

* added missing base component

* minor update to i2c menu to enable easier reuse

* minor update to deinit

* feat(i2c): change naming of new functions so that older std::bind based peripheral code still compiles

* doc: update

* doc: rebuild

* set logger verbosity to default level so that it doesnt have to be provided

* update to change BMI formatting

* update non-peripheral components to use new base_component class

* doc: rebuild

* fix(controller): fix typo from refactor to base component

* fix(base_component): make constructors with arguments explicit

* add explicit cast

* fix(rtsp): fix out of order BMI member use

* doc: rebuild
  • Loading branch information
finger563 authored Feb 12, 2024
1 parent 48e1e01 commit ae9724d
Show file tree
Hide file tree
Showing 168 changed files with 4,748 additions and 567 deletions.
2 changes: 1 addition & 1 deletion .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ BreakBeforeBinaryOperators: None
BreakBeforeBraces: Attach
BreakBeforeInheritanceComma: false
BreakBeforeTernaryOperators: true
BreakConstructorInitializersBeforeComma: false
BreakConstructorInitializersBeforeComma: true
BreakConstructorInitializers: BeforeColon
BreakAfterJavaFieldAnnotations: false
BreakStringLiterals: true
Expand Down
2 changes: 1 addition & 1 deletion components/adc/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
idf_component_register(
INCLUDE_DIRS "include"
REQUIRES logger task esp_adc)
REQUIRES base_component task esp_adc)
21 changes: 11 additions & 10 deletions components/adc/include/continuous_adc.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include "esp_adc/adc_continuous.h"

#include "adc_types.hpp"
#include "logger.hpp"
#include "base_component.hpp"
#include "task.hpp"

namespace espp {
Expand All @@ -27,7 +27,7 @@ namespace espp {
* \section adc_continuous_ex1 Continuous ADC Example
* \snippet adc_example.cpp continuous adc example
*/
class ContinuousAdc {
class ContinuousAdc : public espp::BaseComponent {
public:
/**
* @brief Configure the sample rate (globally applied to each channel),
Expand All @@ -50,12 +50,14 @@ class ContinuousAdc {
* @param config Config used to initialize the reader.
*/
explicit ContinuousAdc(const Config &config)
: sample_rate_hz_(config.sample_rate_hz), window_size_bytes_(config.window_size_bytes),
num_channels_(config.channels.size()), conv_mode_(config.convert_mode),
result_data_(window_size_bytes_, 0xcc),
logger_({.tag = "Continuous Adc",
.rate_limit = std::chrono::milliseconds(100),
.level = config.log_level}) {
: BaseComponent("ContinuousAdc", config.log_level)
, sample_rate_hz_(config.sample_rate_hz)
, window_size_bytes_(config.window_size_bytes)
, num_channels_(config.channels.size())
, conv_mode_(config.convert_mode)
, result_data_(window_size_bytes_, 0xcc) {
// set the rate limit for the logger
logger_.set_rate_limit(std::chrono::milliseconds(100));
// initialize the adc continuous subsystem
init(config.channels);
// and start the task
Expand Down Expand Up @@ -203,7 +205,7 @@ class ContinuousAdc {
#if !CONFIG_IDF_TARGET_ESP32
if (output_format_ == ADC_DIGI_OUTPUT_FORMAT_TYPE2) {
if (check_valid_data(p)) {
auto unit = p->type2.unit;
auto unit = (adc_unit_t)p->type2.unit;
auto channel = (adc_channel_t)p->type2.channel;
auto data = p->type2.data;
auto id = get_id(unit, channel);
Expand Down Expand Up @@ -398,7 +400,6 @@ class ContinuousAdc {
adc_digi_convert_mode_t conv_mode_;
adc_digi_output_format_t output_format_;
std::vector<uint8_t> result_data_;
Logger logger_;
std::unique_ptr<Task> task_;
TaskHandle_t task_handle_{NULL};
std::mutex data_mutex_;
Expand Down
7 changes: 3 additions & 4 deletions components/adc/include/oneshot_adc.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include "esp_adc/adc_oneshot.h"

#include "adc_types.hpp"
#include "logger.hpp"
#include "base_component.hpp"

namespace espp {
/**
Expand All @@ -22,7 +22,7 @@ namespace espp {
* \section adc_oneshot_ex1 Oneshot ADC Example
* \snippet adc_example.cpp oneshot adc example
*/
class OneshotAdc {
class OneshotAdc : public BaseComponent {
public:
/**
* @brief Configure the unit for which to read adc values from the provided
Expand All @@ -44,7 +44,7 @@ class OneshotAdc {
* @param config Config used to initialize the reader.
*/
explicit OneshotAdc(const Config &config)
: logger_({.tag = "Oneshot Adc", .level = config.log_level}) {
: BaseComponent("OneShotAdc", config.log_level) {
init(config);
}

Expand Down Expand Up @@ -185,6 +185,5 @@ class OneshotAdc {
adc_oneshot_unit_handle_t adc_handle_;
adc_cali_handle_t adc_cali_handle_;
std::atomic<bool> calibrated_{false};
Logger logger_;
};
} // namespace espp
3 changes: 3 additions & 0 deletions components/base_component/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
idf_component_register(
INCLUDE_DIRS "include"
REQUIRES logger)
51 changes: 51 additions & 0 deletions components/base_component/include/base_component.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
#pragma once

#include <chrono>
#include <string>

#include "logger.hpp"

namespace espp {
/// Base class for all components
/// Provides a logger and some basic logging configuration
class BaseComponent {
public:
/// Set the tag for the logger
/// \param tag The tag to use for the logger
void set_log_tag(const std::string_view &tag) { logger_.set_tag(tag); }

/// Set the log level for the logger
/// \param level The verbosity level to use for the logger
/// \sa Logger::Verbosity
/// \sa Logger::set_verbosity
void set_log_level(Logger::Verbosity level) { logger_.set_verbosity(level); }

/// Set the log verbosity for the logger
/// \param level The verbosity level to use for the logger
/// \note This is a convenience method that calls set_log_level
/// \sa set_log_level
/// \sa Logger::Verbosity
/// \sa Logger::set_verbosity
void set_log_verbosity(Logger::Verbosity level) { set_log_level(level); }

/// Set the rate limit for the logger
/// \param rate_limit The rate limit to use for the logger
/// \note Only calls to the logger that have _rate_limit suffix will be rate limited
/// \sa Logger::set_rate_limit
void set_log_rate_limit(std::chrono::duration<float> rate_limit) {
logger_.set_rate_limit(rate_limit);
}

protected:
BaseComponent() = default;

explicit BaseComponent(std::string_view tag, Logger::Verbosity level = Logger::Verbosity::WARN)
: logger_({.tag = tag, .level = level}) {}

explicit BaseComponent(const Logger::Config &logger_config)
: logger_(logger_config) {}

/// The logger for this component
Logger logger_ = espp::Logger({.tag = "BaseComponent", .level = Logger::Verbosity::INFO});
};
} // namespace espp
2 changes: 1 addition & 1 deletion components/bldc_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
idf_component_register(
INCLUDE_DIRS "include"
REQUIRES logger driver)
REQUIRES base_component driver)
20 changes: 12 additions & 8 deletions components/bldc_driver/include/bldc_driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include "driver/gpio.h"
#include "driver/mcpwm_prelude.h"

#include "logger.hpp"
#include "base_component.hpp"

namespace espp {
/**
Expand All @@ -16,7 +16,7 @@ namespace espp {
* https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/peripherals/mcpwm.html
* peripheral.
*/
class BldcDriver {
class BldcDriver : public BaseComponent {
public:
static constexpr size_t TIMER_RESOLUTION_HZ = 80 * 1000 * 1000; // 80 MHz
static constexpr size_t FREQUENCY_HZ = 20 * 1000; // 20 KHz
Expand Down Expand Up @@ -48,11 +48,16 @@ class BldcDriver {
* @param config Config used to initialize the driver.
*/
explicit BldcDriver(const Config &config)
: gpio_ah_((gpio_num_t)config.gpio_a_h), gpio_al_((gpio_num_t)config.gpio_a_l),
gpio_bh_((gpio_num_t)config.gpio_b_h), gpio_bl_((gpio_num_t)config.gpio_b_l),
gpio_ch_((gpio_num_t)config.gpio_c_h), gpio_cl_((gpio_num_t)config.gpio_c_l),
gpio_en_(config.gpio_enable), gpio_fault_(config.gpio_fault), dead_zone_(config.dead_zone),
logger_({.tag = "BLDC Driver", .level = config.log_level}) {
: BaseComponent("BldcDriver", config.log_level)
, gpio_ah_((gpio_num_t)config.gpio_a_h)
, gpio_al_((gpio_num_t)config.gpio_a_l)
, gpio_bh_((gpio_num_t)config.gpio_b_h)
, gpio_bl_((gpio_num_t)config.gpio_b_l)
, gpio_ch_((gpio_num_t)config.gpio_c_h)
, gpio_cl_((gpio_num_t)config.gpio_c_l)
, gpio_en_(config.gpio_enable)
, gpio_fault_(config.gpio_fault)
, dead_zone_(config.dead_zone) {
configure_power(config.power_supply_voltage, config.limit_voltage);
init(config);
}
Expand Down Expand Up @@ -411,6 +416,5 @@ class BldcDriver {
std::array<mcpwm_oper_handle_t, 3> operators_;
std::array<mcpwm_cmpr_handle_t, 3> comparators_;
std::array<mcpwm_gen_handle_t, 6> generators_;
Logger logger_;
};
} // namespace espp
2 changes: 1 addition & 1 deletion components/bldc_haptics/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
idf_component_register(
INCLUDE_DIRS "include"
REQUIRES logger math pid task bldc_motor
REQUIRES base_component math pid task bldc_motor
)
20 changes: 9 additions & 11 deletions components/bldc_haptics/include/bldc_haptics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
#include <deque>
#include <vector>

#include "base_component.hpp"
#include "bldc_motor.hpp"
#include "detent_config.hpp"
#include "haptic_config.hpp"
#include "logger.hpp"
#include "task.hpp"

namespace espp {
Expand Down Expand Up @@ -93,7 +93,7 @@ concept MotorConcept = requires {
/// \snippet bldc_haptics_example.cpp bldc_haptics_example_1
/// \section bldc_haptics_ex2 Example 2: Playing a haptic click / buzz
/// \snippet bldc_haptics_example.cpp bldc_haptics_example_2
template <MotorConcept M> class BldcHaptics {
template <MotorConcept M> class BldcHaptics : public BaseComponent {
public:
/// @brief Configuration for the haptic motor
struct Config {
Expand All @@ -113,19 +113,19 @@ template <MotorConcept M> class BldcHaptics {
/// @brief Constructor for the haptic motor
/// @param config Configuration for the haptic motor
explicit BldcHaptics(const Config &config)
: detent_pid_({.kp = 0, // will be set later (motor_task)
: BaseComponent("BldcHaptics", config.log_level)
, detent_pid_({.kp = 0, // will be set later (motor_task)
.ki = 0, // not configurable for now
.kd = 0, // will be set later (update_detent_config)
.integrator_min = 0, // not configurable for now
.integrator_max = 0, // not configurable for now
.output_min = -1, // go ahead and set some bounds (operates on current)
.output_max = 1}) // go ahead and set some bounds (operates on current)
,
kp_factor_(config.kp_factor), kd_factor_min_(config.kd_factor_min),
kd_factor_max_(config.kd_factor_max), motor_(config.motor),
logger_({.tag = "BldcHaptics",
.rate_limit = std::chrono::milliseconds(100),
.level = config.log_level}) {
, kp_factor_(config.kp_factor)
, kd_factor_min_(config.kd_factor_min)
, kd_factor_max_(config.kd_factor_max)
, motor_(config.motor) {
logger_.set_rate_limit(std::chrono::milliseconds(100));
logger_.info("Initializing haptic motor\n"
"\tkp_factor: {}\n"
"\tkd_factor_min: {}\n"
Expand Down Expand Up @@ -432,7 +432,5 @@ template <MotorConcept M> class BldcHaptics {
std::reference_wrapper<M> motor_; ///< Pointer to the motor to use for haptics

std::unique_ptr<Task> motor_task_; ///< Task which runs the haptic motor

Logger logger_; ///< Logger for the haptics
};
} // namespace espp
2 changes: 1 addition & 1 deletion components/bldc_motor/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
idf_component_register(
INCLUDE_DIRS "include"
REQUIRES logger math pid task
REQUIRES base_component math pid task
)
37 changes: 23 additions & 14 deletions components/bldc_motor/include/bldc_motor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@

#include <atomic>

#include "base_component.hpp"
#include "fast_math.hpp"
#include "logger.hpp"
#include "pid.hpp"
#include "task.hpp"

Expand Down Expand Up @@ -65,7 +65,7 @@ struct DummyCurrentSense {
* @snippet bldc_motor_example.cpp bldc_motor example
*/
template <DriverConcept D, SensorConcept S, CurrentSensorConcept CS = DummyCurrentSense>
class BldcMotor {
class BldcMotor : public BaseComponent {
public:
/**
* @brief Filter the raw input sample and return it.
Expand Down Expand Up @@ -130,17 +130,27 @@ class BldcMotor {
* necessary sensor calibration.
*/
explicit BldcMotor(const Config &config)
: num_pole_pairs_(config.num_pole_pairs), phase_resistance_(config.phase_resistance),
phase_inductance_(config.phase_inductance), kv_rating_(config.kv_rating * _SQRT2),
current_limit_(config.current_limit), velocity_limit_(config.velocity_limit),
sensor_direction_(config.sensor_direction), foc_type_(config.foc_type),
torque_control_type_(config.torque_controller), driver_(config.driver),
sensor_(config.sensor), current_sense_(config.current_sense),
pid_current_q_(config.current_pid_config), pid_current_d_(config.current_pid_config),
pid_velocity_(config.current_pid_config), pid_angle_(config.current_pid_config),
q_current_filter_(config.q_current_filter), d_current_filter_(config.d_current_filter),
velocity_filter_(config.velocity_filter), angle_filter_(config.angle_filter),
logger_({.tag = "BldcMotor", .level = config.log_level}) {
: BaseComponent("BldcMotor", config.log_level)
, num_pole_pairs_(config.num_pole_pairs)
, phase_resistance_(config.phase_resistance)
, phase_inductance_(config.phase_inductance)
, kv_rating_(config.kv_rating * _SQRT2)
, current_limit_(config.current_limit)
, velocity_limit_(config.velocity_limit)
, sensor_direction_(config.sensor_direction)
, foc_type_(config.foc_type)
, torque_control_type_(config.torque_controller)
, driver_(config.driver)
, sensor_(config.sensor)
, current_sense_(config.current_sense)
, pid_current_q_(config.current_pid_config)
, pid_current_d_(config.current_pid_config)
, pid_velocity_(config.current_pid_config)
, pid_angle_(config.current_pid_config)
, q_current_filter_(config.q_current_filter)
, d_current_filter_(config.d_current_filter)
, velocity_filter_(config.velocity_filter)
, angle_filter_(config.angle_filter) {
// initialize the voltage limit
voltage_limit_ = driver_->get_voltage_limit();
voltage_sensor_align_ = voltage_limit_ / 4.0f;
Expand Down Expand Up @@ -948,7 +958,6 @@ class BldcMotor {
filter_fn angle_filter_{nullptr};
std::atomic<bool> enabled_{false};
Status status_{Status::UNINITIALIZED};
Logger logger_;
};

} // namespace espp
2 changes: 1 addition & 1 deletion components/button/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
idf_component_register(
INCLUDE_DIRS "include"
REQUIRES driver logger task)
REQUIRES driver base_component task)
13 changes: 7 additions & 6 deletions components/button/include/button.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include "freertos/FreeRTOS.h"
#include "freertos/queue.h"

#include "logger.hpp"
#include "base_component.hpp"
#include "task.hpp"

namespace espp {
Expand All @@ -19,7 +19,7 @@ namespace espp {
///
/// \section button_ex1 Button Example
/// \snippet button_example.cpp button example
class Button {
class Button : public BaseComponent {
public:
/// \brief The event for the button
struct Event {
Expand Down Expand Up @@ -65,9 +65,11 @@ class Button {
/// \brief Construct a button
/// \param config The configuration for the button
explicit Button(const Config &config)
: gpio_num_(config.gpio_num), callback_(config.callback), active_level_(config.active_level),
event_queue_(xQueueCreate(10, sizeof(EventData))),
logger_({.tag = config.name, .level = config.log_level}) {
: BaseComponent(config.name, config.log_level)
, gpio_num_(config.gpio_num)
, callback_(config.callback)
, active_level_(config.active_level)
, event_queue_(xQueueCreate(10, sizeof(EventData))) {
// configure the GPIO for an interrupt
gpio_config_t io_conf;
memset(&io_conf, 0, sizeof(io_conf));
Expand Down Expand Up @@ -178,6 +180,5 @@ class Button {
HandlerArgs handler_args_;
std::atomic<bool> pressed_{false};
std::unique_ptr<espp::Task> task_;
espp::Logger logger_;
};
} // namespace espp
3 changes: 3 additions & 0 deletions components/cli/example/sdkconfig.defaults.esp32s3
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# on the ESP32S3, which has native USB, we need to set the console so that the
# CLI can be configured correctly:
CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y
Loading

0 comments on commit ae9724d

Please sign in to comment.