$search
#include <speed.h>
Public Member Functions | |
virtual void | adjust (float speed, float error, float *brake_req, float *throttle_req)=0 |
virtual void | configure (art_pilot::PilotConfig &newconfig)=0 |
virtual void | reset (void)=0 |
virtual void | set_brake_position (float position) |
virtual void | set_throttle_position (float position) |
SpeedControl () | |
Protected Attributes | |
float | brake_position_ |
ros::NodeHandle | node_ |
float | throttle_position_ |
Virtual base speed controller class
Definition at line 36 of file speed.h.
virtual void SpeedControl::adjust | ( | float | speed, | |
float | error, | |||
float * | brake_req, | |||
float * | throttle_req | |||
) | [pure virtual] |
Adjust speed to match goal.
speed | absolute value of current velocity in m/sec | |
error | immediate goal minus speed | |
brake_req | -> previous brake request (input), updated brake request (output). | |
throttle_req | -> previous throttle request (input), updated throttle request (output). |
Implemented in LearnedSpeedControl, SpeedControlMatrix, and SpeedControlPID.
virtual void SpeedControl::configure | ( | art_pilot::PilotConfig & | newconfig | ) | [pure virtual] |
Configure controller parameters.
Implemented in LearnedSpeedControl, SpeedControlMatrix, and SpeedControlPID.
virtual void SpeedControl::reset | ( | void | ) | [pure virtual] |
Reset speed controller.
Implemented in LearnedSpeedControl, SpeedControlMatrix, and SpeedControlPID.
virtual void SpeedControl::set_brake_position | ( | float | position | ) | [inline, virtual] |
virtual void SpeedControl::set_throttle_position | ( | float | position | ) | [inline, virtual] |
float SpeedControl::brake_position_ [protected] |
ros::NodeHandle SpeedControl::node_ [protected] |
float SpeedControl::throttle_position_ [protected] |