Class DockDrive

Class Documentation

class DockDrive

Public Functions

DockDrive()
~DockDrive()
inline bool init()
inline bool isEnabled() const
inline bool canRun() const
inline void enable()
inline void disable()
void modeShift(const std::string &mode)
void update(const std::vector<unsigned char> &signal, const unsigned char &bumper, const unsigned char &charger, const ecl::linear_algebra::Vector3d &pose)
void velocityCommands(const double &vx, const double &wz)
inline double getVX() const
inline double getWZ() const
inline RobotDockingState::State getState() const
inline std::string getStateStr() const
inline std::string getDebugStr() const
inline void setMinAbsV(double mav)
inline void setMinAbsW(double maw)
inline std::string getDebugStream()

Protected Functions

void processBumpChargeEvent(const unsigned char &bumper, const unsigned char &charger)
void computePoseUpdate(ecl::linear_algebra::Vector3d &pose_update, const ecl::linear_algebra::Vector3d &pose)
void filterIRSensor(std::vector<unsigned char> &signal_filt, const std::vector<unsigned char> &signal)
void generateDebugMessage(const std::vector<unsigned char> &signal_filt, const unsigned char &bumper, const unsigned char &charger, const std::string &debug_str)
void updateVelocity(const std::vector<unsigned char> &signal_filt, const ecl::linear_algebra::Vector3d &pose_update, std::string &debug_str)
RobotDockingState::State determineRobotLocation(const std::vector<unsigned char> &signal_filt, const unsigned char &charger)
bool validateSignal(const std::vector<unsigned char> &signal_filt, const unsigned int state)
void idle(RobotDockingState::State &state, double &vx, double &wz)
void scan(RobotDockingState::State &state, double &vx, double &wz, const std::vector<unsigned char> &signal_filt, const ecl::linear_algebra::Vector3d &pose_update, std::string &debug_str)
void find_stream(RobotDockingState::State &state, double &vx, double &wz, const std::vector<unsigned char> &signal_filt)
void get_stream(RobotDockingState::State &state, double &vx, double &wz, const std::vector<unsigned char> &signal_filt)
void aligned(RobotDockingState::State &state, double &vx, double &wz, const std::vector<unsigned char> &signal_filt, std::string &debug_str)
void bumped(RobotDockingState::State &nstate, double &nvx, double &nwz, int &bump_count)