Skip to content

Commit

Permalink
Merge branch 'humble' into jballoffet/inject-encoder-dependencies
Browse files Browse the repository at this point in the history
  • Loading branch information
jballoffet authored Feb 6, 2024
2 parents 217fc8d + 4064e50 commit d16ef8b
Show file tree
Hide file tree
Showing 5 changed files with 66 additions and 37 deletions.
5 changes: 3 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,16 +28,17 @@ _Note: For videos go to [Media](#selfie-media) section._
- :hammer_and_pick: [`andino_firmware`](./andino_firmware): Contains the code be run in the microcontroller for interfacing low level hardware with the SBC.
- :gear: [`andino_base`](./andino_base): [ROS Control hardware interface](https://control.ros.org/master/doc/ros2_control/hardware_interface/doc/writing_new_hardware_interface.html) is implemented.
- :control_knobs: [`andino_control`](./andino_control/): It launches the [`controller_manager`](https://control.ros.org/humble/doc/ros2_control/controller_manager/doc/userdoc.html) along with the [ros2 controllers](https://control.ros.org/master/doc/ros2_controllers/doc/controllers_index.html): [diff_drive_controller](https://control.ros.org/master/doc/ros2_controllers/diff_drive_controller/doc/userdoc.html) and the [joint_state_broadcaster](https://control.ros.org/master/doc/ros2_controllers/joint_state_broadcaster/doc/userdoc.html).
- :computer: [`andino_gz_classic`](./andino_gz_classic/): Gazebo simulation of the `andino` robot.
- :computer: [`andino_gz_classic`](./andino_gz_classic/): [Gazebo Classic](https://classic.gazebosim.org/) simulation of the `andino` robot.
- :world_map: [`andino_slam`](./andino_slam/): Provides support for SLAM with your `andino` robot.
- :compass: [`andino_navigation`](./andino_navigation/): Navigation stack based on `nav2`.

## :paperclips: Related projects

Other projects built upon Andino! :rocket:

- :test_tube: [`andino_integration_tests`](https://github.com/Ekumen-OS/andino_integration_tests): Extension to the Andino robot showing how to build integration tests.
- :computer: [`andino_gz`](https://github.com/Ekumen-OS/andino_gz): [Gazebo](https://gazebosim.org/home)(non-classic) simulation of the `andino` robot.
- :lady_beetle: [`andino_webots`](https://github.com/Ekumen-OS/andino_webots): [Webots](https://github.com/cyberbotics/webots) simulation of the Andino robot fully integrated with ROS 2.
- :test_tube: [`andino_integration_tests`](https://github.com/Ekumen-OS/andino_integration_tests): Extension to the Andino robot showing how to build integration tests.

## :pick: Robot Assembly

Expand Down
24 changes: 17 additions & 7 deletions andino_firmware/src/app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,21 +68,30 @@

#include "commands.h"
#include "constants.h"
#include "digital_out_arduino.h"
#include "encoder.h"
#include "hw.h"
#include "interrupt_in_arduino.h"
#include "motor.h"
#include "pid.h"
#include "pwm_out_arduino.h"
#include "shell.h"

namespace andino {

Shell App::shell_;

Motor App::left_motor_(Hw::kLeftMotorEnableGpioPin, Hw::kLeftMotorForwardGpioPin,
Hw::kLeftMotorBackwardGpioPin);
Motor App::right_motor_(Hw::kRightMotorEnableGpioPin, Hw::kRightMotorForwardGpioPin,
Hw::kRightMotorBackwardGpioPin);
DigitalOutArduino App::left_motor_enable_digital_out_(Hw::kLeftMotorEnableGpioPin);
PwmOutArduino App::left_motor_forward_pwm_out_(Hw::kLeftMotorForwardGpioPin);
PwmOutArduino App::left_motor_backward_pwm_out_(Hw::kLeftMotorBackwardGpioPin);
Motor App::left_motor_(&left_motor_enable_digital_out_, &left_motor_forward_pwm_out_,
&left_motor_backward_pwm_out_);

DigitalOutArduino App::right_motor_enable_digital_out_(Hw::kRightMotorEnableGpioPin);
PwmOutArduino App::right_motor_forward_pwm_out_(Hw::kRightMotorForwardGpioPin);
PwmOutArduino App::right_motor_backward_pwm_out_(Hw::kRightMotorBackwardGpioPin);
Motor App::right_motor_(&right_motor_enable_digital_out_, &right_motor_forward_pwm_out_,
&right_motor_backward_pwm_out_);

InterruptInArduino App::left_encoder_channel_a_interrupt_in_(Hw::kLeftEncoderChannelAGpioPin);
InterruptInArduino App::left_encoder_channel_b_interrupt_in_(Hw::kLeftEncoderChannelBGpioPin);
Expand Down Expand Up @@ -112,9 +121,10 @@ void App::setup() {
left_encoder_.begin();
right_encoder_.begin();

// Enable motors.
left_motor_.set_state(true);
right_motor_.set_state(true);
left_motor_.begin();
left_motor_.enable(true);
right_motor_.begin();
right_motor_.enable(true);

left_pid_controller_.reset(left_encoder_.read());
right_pid_controller_.reset(right_encoder_.read());
Expand Down
12 changes: 11 additions & 1 deletion andino_firmware/src/app.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,12 @@
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#pragma once

#include "digital_out_arduino.h"
#include "encoder.h"
#include "interrupt_in_arduino.h"
#include "motor.h"
#include "pid.h"
#include "pwm_out_arduino.h"
#include "shell.h"

namespace andino {
Expand Down Expand Up @@ -83,8 +85,16 @@ class App {
/// Application command shell.
static Shell shell_;

/// Motors (one per wheel).
/// Left wheel motor.
static DigitalOutArduino left_motor_enable_digital_out_;
static PwmOutArduino left_motor_forward_pwm_out_;
static PwmOutArduino left_motor_backward_pwm_out_;
static Motor left_motor_;

/// Right wheel motor.
static DigitalOutArduino right_motor_enable_digital_out_;
static PwmOutArduino right_motor_forward_pwm_out_;
static PwmOutArduino right_motor_backward_pwm_out_;
static Motor right_motor_;

/// Left wheel encoder.
Expand Down
23 changes: 12 additions & 11 deletions andino_firmware/src/motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,18 +64,19 @@
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#include "motor.h"

#include <Arduino.h>
#include "digital_out.h"
#include "pwm_out.h"

namespace andino {

void Motor::set_state(bool enabled) {
if (enabled) {
digitalWrite(enable_gpio_pin_, HIGH);
} else {
digitalWrite(enable_gpio_pin_, LOW);
}
void Motor::begin() {
enable_digital_out_->begin();
forward_pwm_out_->begin();
backward_pwm_out_->begin();
}

void Motor::enable(bool enabled) { enable_digital_out_->write(enabled ? 1 : 0); }

void Motor::set_speed(int speed) {
bool forward = true;

Expand All @@ -89,11 +90,11 @@ void Motor::set_speed(int speed) {

// The motor speed is controlled by sending a PWM wave to the corresponding pin.
if (forward) {
analogWrite(forward_gpio_pin_, speed);
analogWrite(backward_gpio_pin_, 0);
forward_pwm_out_->write(speed);
backward_pwm_out_->write(0);
} else {
analogWrite(backward_gpio_pin_, speed);
analogWrite(forward_gpio_pin_, 0);
backward_pwm_out_->write(speed);
forward_pwm_out_->write(0);
}
}

Expand Down
39 changes: 23 additions & 16 deletions andino_firmware/src/motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,9 @@
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#pragma once

#include "digital_out.h"
#include "pwm_out.h"

namespace andino {

/// @brief This class allows to control a DC motor by enabling it and setting its speed. The
Expand All @@ -73,18 +76,22 @@ class Motor {
public:
/// @brief Constructs a new Motor object.
///
/// @param enable_gpio_pin Motor enable GPIO pin.
/// @param forward_gpio_pin Motor forward GPIO pin.
/// @param backward_gpio_pin Motor backward GPIO pin.
Motor(int enable_gpio_pin, int forward_gpio_pin, int backward_gpio_pin)
: enable_gpio_pin_(enable_gpio_pin),
forward_gpio_pin_(forward_gpio_pin),
backward_gpio_pin_(backward_gpio_pin) {}
/// @param enable_digital_out Digital output connected to motor enable pin.
/// @param forward_pwm_out PWM output connected to motor forward pin.
/// @param backward_pwm_out PWM output connected to motor backward pin.
Motor(const DigitalOut* enable_digital_out, const PwmOut* forward_pwm_out,
const PwmOut* backward_pwm_out)
: enable_digital_out_(enable_digital_out),
forward_pwm_out_(forward_pwm_out),
backward_pwm_out_(backward_pwm_out) {}

/// @brief Initializes the motor.
void begin();

/// @brief Sets the motor state.
/// @brief Enables the motor.
///
/// @param enabled Motor state.
void set_state(bool enabled);
/// @param enabled True to enable the motor, false otherwise.
void enable(bool enabled);

/// @brief Sets the motor speed.
///
Expand All @@ -98,14 +105,14 @@ class Motor {
/// Maximum speed value.
static constexpr int kMaxSpeed{255};

/// Motor enable GPIO pin.
int enable_gpio_pin_;
/// Digital output connected to motor enable pin.
const DigitalOut* enable_digital_out_;

/// Motor forward GPIO pin.
int forward_gpio_pin_;
/// PWM output connected to motor forward pin.
const PwmOut* forward_pwm_out_;

/// Motor backward GPIO pin.
int backward_gpio_pin_;
/// PWM output connected to motor backward pin.
const PwmOut* backward_pwm_out_;
};

} // namespace andino

0 comments on commit d16ef8b

Please sign in to comment.