Public Types | Public Member Functions | Static Public Member Functions | Private Attributes | Static Private Attributes
miniQ Class Reference

#include <miniQ.h>

List of all members.

Public Types

enum  _miniQaction {
  MQ_ACTION_GET_VERSION = 1, MQ_ACTION_DRIVE = 2, MQ_ACTION_DRIVE_DIRECT = 3, MQ_ACTION_GET_ODOMETRY = 4,
  MQ_ACTION_GET_ENCODER_PULSES = 5, MQ_ACTION_GET_WHEEL_VELOCITIES = 6, MQ_ACTION_GET_GAS_SENSOR = 7, MQ_ACTION_GET_IR_BUMPER = 8,
  MQ_ACTION_GET_LINE_SENSOR = 9, MQ_ACTION_GET_BATTERY = 10, MQ_ACTION_GET_DEBUG = 11, MQ_ACTION_SET_DEBUG = 12,
  MQ_ACTION_SET_PID_GAINS = 13, MQ_ACTION_GET_PID_GAINS = 14, MQ_ACTION_SET_ODOMETRY_CALIBRATION = 15, MQ_ACTION_GET_ODOMETRY_CALIBRATION = 16,
  MQ_ACTION_SET_ID = 17, MQ_ACTION_GET_ID = 18, MQ_ACTION_SET_MODE = 19, MQ_ACTION_GET_MODE = 20,
  MQ_ACTION_SET_GAS_CALIBRATION = 21, MQ_ACTION_GET_GAS_CALIBRATION = 22, MQ_ACTION_SET_BATTERY_TYPE = 23, MQ_ACTION_GET_BATTERY_TYPE = 24,
  MQ_ACTION_SET_TIMEOUT = 25, MQ_ACTION_GET_TIMEOUT = 26, MQ_ACTION_GET_GROUP_1 = 27, MQ_ACTION_GET_GROUP_2 = 28,
  MQ_ACTION_COUNT = 29
}
 miniQ actions More...
enum  _miniQPID { LeftStartingPID = 0, LeftRunningPID = 1, RightStartingPID = 2, RightRunningPID = 3 }
typedef enum miniQ::_miniQaction miniQaction
 miniQ actions
typedef enum miniQ::_miniQPID miniQPID

Public Member Functions

bool checkVersion ()
 This function asks the firmware version from the miniQ robot.
double getAngularVelocity ()
 Getter for the robot angular velocity.
double getGas ()
 Getter for the gas sensor reading.
int getID ()
double getLeftWheelVelocity ()
 Getter for the left wheel velocity.
double getLinearVelocity ()
 Getter for the robot linear velocity.
double getRawGas ()
 Getter for the gas sensor reading.
double getRightWheelVelocity ()
 Getter for the right wheel velocity.
double getX ()
double getY ()
double getYaw ()
 miniQ ()
bool setBatteryType (int battery_type)
bool setGasSensorCallibration (double a, double b)
void setId (int id)
bool setMode (int mode)
bool setOdometryCallibration (double odometry_d, double odometry_yaw)
bool setPIDGains (int kp, int ki, int kd, miniQPID pid)
void setPWM (int left_pwm, int left_dir, int right_pwm, int right_dir)
bool setTimeout (double timeout)
void setVelocities (double linear_velocity, double angular_velocity)
 This function allows to send velocity commands to the velocity controllers.
bool update ()
 This function communicates with the robot to update the odometry and gas sensor data.
bool updateVelocities ()
 This function pushes the velocities in memory to the robot.
bool updateWheelVelocities ()
 ~miniQ ()

Static Public Member Functions

static bool openPort (char *port, int baudrate)
 This function opens the virtual comm to the miniQ robot.
static int scanForId (int id)

Private Attributes

double angular_velocity_
 Angular velocity.
double gas_
 Gas.
double gas_raw_
 Raw gas.
int id_
 Robot id.
double left_wheel_velocity_
 Left wheel velocity.
double linear_velocity_
 Velocity in x.
double right_wheel_velocity_
 Right wheel velocity.
double x_
 Position in x.
double y_
 Position in y.
double yaw_
 Yaw.

Static Private Attributes

static cereal::CerealPort serial_port

Detailed Description

Definition at line 44 of file miniQ.h.


Member Typedef Documentation

miniQ actions


Member Enumeration Documentation

miniQ actions

Enumerator:
MQ_ACTION_GET_VERSION 
MQ_ACTION_DRIVE 
MQ_ACTION_DRIVE_DIRECT 
MQ_ACTION_GET_ODOMETRY 
MQ_ACTION_GET_ENCODER_PULSES 
MQ_ACTION_GET_WHEEL_VELOCITIES 
MQ_ACTION_GET_GAS_SENSOR 
MQ_ACTION_GET_IR_BUMPER 
MQ_ACTION_GET_LINE_SENSOR 
MQ_ACTION_GET_BATTERY 
MQ_ACTION_GET_DEBUG 
MQ_ACTION_SET_DEBUG 
MQ_ACTION_SET_PID_GAINS 
MQ_ACTION_GET_PID_GAINS 
MQ_ACTION_SET_ODOMETRY_CALIBRATION 
MQ_ACTION_GET_ODOMETRY_CALIBRATION 
MQ_ACTION_SET_ID 
MQ_ACTION_GET_ID 
MQ_ACTION_SET_MODE 
MQ_ACTION_GET_MODE 
MQ_ACTION_SET_GAS_CALIBRATION 
MQ_ACTION_GET_GAS_CALIBRATION 
MQ_ACTION_SET_BATTERY_TYPE 
MQ_ACTION_GET_BATTERY_TYPE 
MQ_ACTION_SET_TIMEOUT 
MQ_ACTION_GET_TIMEOUT 
MQ_ACTION_GET_GROUP_1 
MQ_ACTION_GET_GROUP_2 
MQ_ACTION_COUNT 

Definition at line 49 of file miniQ.h.

Enumerator:
LeftStartingPID 
LeftRunningPID 
RightStartingPID 
RightRunningPID 

Definition at line 91 of file miniQ.h.


Constructor & Destructor Documentation

Definition at line 43 of file miniQ.cpp.

Definition at line 50 of file miniQ.cpp.


Member Function Documentation

This function asks the firmware version from the miniQ robot.

Returns:
True if the version is compatible, false otherwise.

Definition at line 65 of file miniQ.cpp.

double miniQ::getAngularVelocity ( ) [inline]

Getter for the robot angular velocity.

Returns:
The robot angular velocity.

Definition at line 190 of file miniQ.h.

double miniQ::getGas ( ) [inline]

Getter for the gas sensor reading.

Returns:
The gas sensor reading in ppm.

Definition at line 214 of file miniQ.h.

int miniQ::getID ( ) [inline]

Definition at line 227 of file miniQ.h.

double miniQ::getLeftWheelVelocity ( ) [inline]

Getter for the left wheel velocity.

Returns:
The left wheel velocity.

Definition at line 198 of file miniQ.h.

double miniQ::getLinearVelocity ( ) [inline]

Getter for the robot linear velocity.

Returns:
The robot linear velocity.

Definition at line 182 of file miniQ.h.

double miniQ::getRawGas ( ) [inline]

Getter for the gas sensor reading.

Returns:
The gas sensor reading in raw form.

Definition at line 222 of file miniQ.h.

double miniQ::getRightWheelVelocity ( ) [inline]

Getter for the right wheel velocity.

Returns:
The right wheel velocity.

Definition at line 206 of file miniQ.h.

double miniQ::getX ( ) [inline]

Definition at line 158 of file miniQ.h.

double miniQ::getY ( ) [inline]

Definition at line 166 of file miniQ.h.

double miniQ::getYaw ( ) [inline]

Definition at line 174 of file miniQ.h.

bool miniQ::openPort ( char *  port,
int  baudrate 
) [static]

This function opens the virtual comm to the miniQ robot.

Parameters:
portSerial port name.
baudrateThe name is self explanatory.
Returns:
True if port is open, false otherwise.

Definition at line 55 of file miniQ.cpp.

int miniQ::scanForId ( int  id) [static]

Definition at line 160 of file miniQ.cpp.

bool miniQ::setBatteryType ( int  battery_type)

Definition at line 191 of file miniQ.cpp.

bool miniQ::setGasSensorCallibration ( double  a,
double  b 
)

Definition at line 244 of file miniQ.cpp.

void miniQ::setId ( int  id)

Definition at line 155 of file miniQ.cpp.

bool miniQ::setMode ( int  mode)

Definition at line 181 of file miniQ.cpp.

bool miniQ::setOdometryCallibration ( double  odometry_d,
double  odometry_yaw 
)

Definition at line 234 of file miniQ.cpp.

bool miniQ::setPIDGains ( int  kp,
int  ki,
int  kd,
miniQPID  pid 
)

Definition at line 201 of file miniQ.cpp.

void miniQ::setPWM ( int  left_pwm,
int  left_dir,
int  right_pwm,
int  right_dir 
)

Definition at line 97 of file miniQ.cpp.

bool miniQ::setTimeout ( double  timeout)

Definition at line 254 of file miniQ.cpp.

void miniQ::setVelocities ( double  linear_velocity,
double  angular_velocity 
)

This function allows to send velocity commands to the velocity controllers.

Parameters:
linear_velocityLinear velocity to the robot in m/s.
angular_velocityAngular velocity to the robot in m/s.

Definition at line 91 of file miniQ.cpp.

bool miniQ::update ( )

This function communicates with the robot to update the odometry and gas sensor data.

Returns:
True if update was successful, false otherwise.

Definition at line 105 of file miniQ.cpp.

This function pushes the velocities in memory to the robot.

Returns:
True if update was successful, false otherwise.

Definition at line 140 of file miniQ.cpp.

Definition at line 264 of file miniQ.cpp.


Member Data Documentation

double miniQ::angular_velocity_ [private]

Angular velocity.

Definition at line 252 of file miniQ.h.

double miniQ::gas_ [private]

Gas.

Definition at line 259 of file miniQ.h.

double miniQ::gas_raw_ [private]

Raw gas.

Definition at line 261 of file miniQ.h.

int miniQ::id_ [private]

Robot id.

Definition at line 264 of file miniQ.h.

double miniQ::left_wheel_velocity_ [private]

Left wheel velocity.

Definition at line 254 of file miniQ.h.

double miniQ::linear_velocity_ [private]

Velocity in x.

Definition at line 250 of file miniQ.h.

double miniQ::right_wheel_velocity_ [private]

Right wheel velocity.

Definition at line 256 of file miniQ.h.

Definition at line 266 of file miniQ.h.

double miniQ::x_ [private]

Position in x.

Definition at line 244 of file miniQ.h.

double miniQ::y_ [private]

Position in y.

Definition at line 246 of file miniQ.h.

double miniQ::yaw_ [private]

Yaw.

Definition at line 248 of file miniQ.h.


The documentation for this class was generated from the following files:


lse_miniq_driver
Author(s): Gonçalo Cabrita
autogenerated on Mon Jan 6 2014 11:25:52