$search

SpeedControlPID Class Reference

#include <speed.h>

Inheritance diagram for SpeedControlPID:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void adjust (float speed, float error, float *brake_req, float *throttle_req)
virtual void configure (art_pilot::PilotConfig &newconfig)
virtual void reset (void)
 SpeedControlPID ()
virtual ~SpeedControlPID ()

Private Attributes

boost::shared_ptr< Pidbrake_pid_
bool braking_
boost::shared_ptr< Pidthrottle_pid_

Detailed Description

PID speed controller class

Definition at line 98 of file speed.h.


Constructor & Destructor Documentation

SpeedControlPID::SpeedControlPID (  ) 

PID speed control constructor.

Allocate brake and throttle PID classes with default parameters, then configure control constants.

Throttle gains came from Jesse Tannahill's pilot prototype. Brake gains selected by experiment.

Definition at line 186 of file speed.cc.

SpeedControlPID::~SpeedControlPID (  )  [virtual]

PID speed control destructor.

Definition at line 196 of file speed.cc.


Member Function Documentation

void SpeedControlPID::adjust ( float  speed,
float  error,
float *  brake_req,
float *  throttle_req 
) [virtual]

Adjust speed to match goal.

Generate brake and throttle changes directly from separate PID controllers. Uses a state machine to avoid applying simultaneous brake and throttle.

Parameters:
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).

Implements SpeedControl.

Definition at line 212 of file speed.cc.

void SpeedControlPID::configure ( art_pilot::PilotConfig &  newconfig  )  [virtual]

Configure controller parameters.

Implements SpeedControl.

Definition at line 266 of file speed.cc.

void SpeedControlPID::reset ( void   )  [virtual]

Reset speed controller.

Implements SpeedControl.

Definition at line 277 of file speed.cc.


Member Data Documentation

boost::shared_ptr<Pid> SpeedControlPID::brake_pid_ [private]

Definition at line 114 of file speed.h.

bool SpeedControlPID::braking_ [private]

Definition at line 112 of file speed.h.

boost::shared_ptr<Pid> SpeedControlPID::throttle_pid_ [private]

Definition at line 115 of file speed.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


art_pilot
Author(s): Austin Robot Technology, Jack O'Quin
autogenerated on Fri Mar 1 14:14:15 2013