Smartcar Shield
Public Member Functions | List of all members
DistanceCar Class Reference

#include <DistanceCar.hpp>

Inheritance diagram for DistanceCar:
Inheritance graph
Collaboration diagram for DistanceCar:
Collaboration graph

Public Member Functions

 DistanceCar (Runtime &runtime, Control &control, Odometer &odometer)
 Constructs a car equipped with a distance sensor. More...
 
 DistanceCar (Runtime &runtime, Control &control, Odometer &odometerLeft, Odometer &odometerRight)
 Constructs a car equipped with a distance sensor. More...
 
long getDistance ()
 Gets the car's travelled distance. More...
 
void setSpeed (float speed) override
 Sets the car's speed in meters per second if cruise control is enabled otherwise as a percentage of the motor speed. More...
 
float getSpeed ()
 Gets the car's current speed in meters per second. More...
 
void enableCruiseControl (float proportional=smartcarlib::constants::car::kDefaultProportional, float integral=smartcarlib::constants::car::kDefaultIntegral, float derivative=smartcarlib::constants::car::kDefaultDerivative, unsigned long frequency=smartcarlib::constants::car::kDefaultPidFrequency)
 Enables the car to move with a stable speed using the odometers. More...
 
virtual void update ()
 Adjusts the cruise control speed. More...
 
void disableCruiseControl ()
 Disable cruise control. More...
 
void overrideMotorSpeed (int firstMotorSpeed, int secondMotorSpeed) override
 Sets the motor speed individually as a percentage of the motors` total power unless cruise control is enabled in which case has no effect. More...
 
- Public Member Functions inherited from SimpleCar
 SimpleCar (Control &control)
 Constructs a simple car. More...
 
void setSpeed (float speed) override
 Sets the car's driving speed as a percentage of the motors total speed where the sign indicates direction. More...
 
void setAngle (int angle) override
 Set the car's driving angle. More...
 
void overrideMotorSpeed (int firstMotorSpeed, int secondMotorSpeed) override
 Set the motor speed individually as a percentage of the motors` total power. More...
 
- Public Member Functions inherited from Car
virtual ~Car ()=default
 

Detailed Description

A class to programmatically represent a vehicle equipped with odometers

Definition at line 27 of file DistanceCar.hpp.

Constructor & Destructor Documentation

◆ DistanceCar() [1/2]

DistanceCar::DistanceCar ( Runtime runtime,
Control control,
Odometer odometer 
)

Constructs a car equipped with a distance sensor.

Parameters
runtimeThe runtime environment you want to run the class for
controlThe car's control
odometerThe odometer

Example:

ArduinoRuntime arduinoRuntime;
DifferentialControl control(leftMotor, rightMotor);
arduinoRuntime, smartcarlib::pins::v2::leftOdometerPin, []() { odometer.update(); }, 100);
DistanceCar car(arduinoRuntime, control, odometer);

Definition at line 17 of file DistanceCar.cpp.

◆ DistanceCar() [2/2]

DistanceCar::DistanceCar ( Runtime runtime,
Control control,
Odometer odometerLeft,
Odometer odometerRight 
)

Constructs a car equipped with a distance sensor.

Parameters
runtimeThe runtime environment you want to run the class for
controlThe car's control
odometerLeftThe left odometer
odometerRightThe right odometer

Example:

DifferentialControl control(leftMotor, rightMotor);
const auto pulsesPerMeter = 600;
DirectionlessOdometer leftOdometer(
smartcarlib::pins::v2::leftOdometerPin, []() { leftOdometer.update(); }, pulsesPerMeter);
DirectionlessOdometer rightOdometer(
smartcarlib::pins::v2::rightOdometerPin, []() { rightOdometer.update(); },
pulsesPerMeter);
DistanceCar car(control, gyroscope, leftOdometer, rightOdometer);

Definition at line 25 of file DistanceCar.cpp.

Member Function Documentation

◆ disableCruiseControl()

void DistanceCar::disableCruiseControl ( )

Disable cruise control.

Example:

car.disableCruiseControl();

Definition at line 183 of file DistanceCar.cpp.

◆ enableCruiseControl()

void DistanceCar::enableCruiseControl ( float  proportional = smartcarlib::constants::car::kDefaultProportional,
float  integral = smartcarlib::constants::car::kDefaultIntegral,
float  derivative = smartcarlib::constants::car::kDefaultDerivative,
unsigned long  frequency = smartcarlib::constants::car::kDefaultPidFrequency 
)

Enables the car to move with a stable speed using the odometers.

Parameters
proportionalThe proportional value of the PID controller
integralThe integral value of the PID controller
derivativeThe derivative value of the PID controller
frequencyHow often to adjust the speed using update()

Example:

// Start adjusting the speed using a PID controller with
// P = 2, I = 0.1, D = 0.5 every 80 milliseconds
car.enableCruiseControl(2, 0.1, 0.5, 80);

Definition at line 188 of file DistanceCar.cpp.

◆ getDistance()

long DistanceCar::getDistance ( )

Gets the car's travelled distance.

Returns
The car's travelled distance

Example:

// After we have attached the odometers, we can get the travelled distance
long travelledDistance = car.getDistance();

Definition at line 36 of file DistanceCar.cpp.

Here is the call graph for this function:

◆ getSpeed()

float DistanceCar::getSpeed ( )

Gets the car's current speed in meters per second.

Returns
The car's speed

Example:

float currentSpeed = car.getSpeed();

Definition at line 177 of file DistanceCar.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ overrideMotorSpeed()

void DistanceCar::overrideMotorSpeed ( int  firstMotorSpeed,
int  secondMotorSpeed 
)
overridevirtual

Sets the motor speed individually as a percentage of the motors` total power unless cruise control is enabled in which case has no effect.

Use with caution.

Parameters
firstMotorSpeedThe speed of the motor passed as first argument argument to the car's control class [-100, 100]
secondMotorSpeedThe speed of the motor passed as second argument argument to the car's control class [-100, 100]

Example:

// Make the car spin around
car.overrideMotorSpeed(100, -100);

Implements Car.

Definition at line 210 of file DistanceCar.cpp.

Here is the call graph for this function:

◆ setSpeed()

void DistanceCar::setSpeed ( float  speed)
overridevirtual

Sets the car's speed in meters per second if cruise control is enabled otherwise as a percentage of the motor speed.

Sign in both cases determines direction.

Parameters
speedThe car's speed

Example (with cruise control):

car.enableCruiseControl();
float speedInMetersPerSecond = -0.8;
// Set speed to 0.8 meters per second backward
car.setSpeed(speedInMetersPerSecond);

Example (without cruise control):

float speedInPercentageOfMotorPower = 50;
// Set speed to half of the maximum motor speed forward
car.setSpeed(speedInPercentageOfMotorPower);

Implements Car.

Definition at line 42 of file DistanceCar.cpp.

Here is the call graph for this function:

◆ update()

void DistanceCar::update ( )
virtual

Adjusts the cruise control speed.

You must have this being executed as often as possible when having cruise control enabled. When cruise control is not enabled this has no effect.

Example:

void loop() {
// Update the car readings as often as possible
car.update();
// Other functionality
}

Reimplemented in SmartCar.

Definition at line 112 of file DistanceCar.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

The documentation for this class was generated from the following files:
DirectionlessOdometer
Definition: DirectionlessOdometer.hpp:14
DistanceCar
Definition: DistanceCar.hpp:27
smartcarlib::pins::v2::leftMotorPins
const BrushedMotorPins leftMotorPins
Definition: Smartcar.h:50
BrushedMotor
Definition: BrushedMotor.hpp:41
smartcarlib::pins::v2::rightOdometerPin
const uint8_t rightOdometerPin
Definition: Smartcar.h:53
ArduinoRuntime
Definition: ArduinoRuntime.hpp:11
DifferentialControl
Definition: DifferentialControl.hpp:11
smartcarlib::pins::v2::rightMotorPins
const BrushedMotorPins rightMotorPins
Definition: Smartcar.h:51
smartcarlib::pins::v2::leftOdometerPin
const uint8_t leftOdometerPin
Definition: Smartcar.h:52