Class Kobuki
Defined in File kobuki.hpp
Class Documentation
-
class Kobuki
The core kobuki driver class.
This connects to the outside world via sigslots and get accessors.
Public Functions
-
Kobuki()
-
~Kobuki()
-
void init(Parameters ¶meters)
-
inline bool isAlive() const
Whether the connection to the robot is alive and currently streaming.
-
inline bool isShutdown() const
Whether the worker thread is alive or not.
-
inline bool isEnabled() const
Whether the motor power is enabled or disabled.
-
bool enable()
Enable power to the motors.
-
bool disable()
Disable power to the motors.
-
inline void shutdown()
Gently terminate the worker thread.
-
void spin()
-
void fixPayload(ecl::PushAndPop<unsigned char> &byteStream)
-
void lockDataAccess()
-
void unlockDataAccess()
-
ecl::Angle<double> getHeading() const
-
double getAngularVelocity() const
-
inline VersionInfo versionInfo() const
-
inline CoreSensors::Data getCoreSensorData() const
-
inline ThreeAxisGyro::Data getRawInertiaData() const
-
inline ControllerInfo::Data getControllerInfoData() const
-
void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle, double &wheel_right_angle_rate)
-
void updateOdometry(ecl::linear_algebra::Vector3d &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
-
void resetOdometry()
-
void setBaseControl(const double &linear_velocity, const double &angular_velocity)
-
void setDigitalOutput(const DigitalOutput &digital_output)
-
void setExternalPower(const DigitalOutput &digital_output)
-
void playSoundSequence(const enum SoundSequences &number)
-
bool setControllerGain(const unsigned char &type, const unsigned int &p_gain, const unsigned int &i_gain, const unsigned int &d_gain)
-
bool getControllerGain()
-
void printSigSlotConnections() const
-
Kobuki()