Public Member Functions | Private Member Functions | Private Attributes
kobuki::DiffDrive Class Reference

#include <diff_drive.hpp>

List of all members.

Public Member Functions

double angularVelocity () const
 DiffDrive ()
void getWheelJointStates (double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle, double &wheel_right_angle_rate)
const
ecl::DifferentialDrive::Kinematics
kinematics ()
double linearVelocity () const
std::vector< double > pointVelocity () const
void reset (const double &current_heading)
void setVelocityCommands (const double &vx, const double &wz)
void update (const uint16_t &time_stamp, const uint16_t &left_encoder, const uint16_t &right_encoder, ecl::Pose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
 Updates the odometry from firmware stamps and encoders.
void velocityCommands (const double &vx, const double &wz)
void velocityCommands (const short &cmd_speed, const short &cmd_radius)
void velocityCommands (const std::vector< double > &cmd)
void velocityCommands (const std::vector< short > &cmd)
std::vector< short > velocityCommands ()
double wheel_bias () const

Private Member Functions

short bound (const double &value)

Private Attributes

double bias
ecl::DifferentialDrive::Kinematics diff_drive_kinematics
int imu_heading_offset
double last_diff_time
double last_rad_left
double last_rad_right
unsigned short last_tick_left
unsigned short last_tick_right
unsigned short last_timestamp
double last_velocity_left
double last_velocity_right
std::vector< double > point_velocity
double radius
double speed
ecl::Mutex state_mutex
const double tick_to_rad
ecl::Mutex velocity_mutex
double wheel_radius

Detailed Description

Definition at line 36 of file diff_drive.hpp.


Constructor & Destructor Documentation

Definition at line 25 of file diff_drive.cpp.


Member Function Documentation

double kobuki::DiffDrive::angularVelocity ( ) const [inline]

Definition at line 60 of file diff_drive.hpp.

short kobuki::DiffDrive::bound ( const double &  value) [private]

Definition at line 183 of file diff_drive.cpp.

void kobuki::DiffDrive::getWheelJointStates ( double &  wheel_left_angle,
double &  wheel_left_angle_rate,
double &  wheel_right_angle,
double &  wheel_right_angle_rate 
)

Definition at line 116 of file diff_drive.cpp.

Definition at line 39 of file diff_drive.hpp.

double kobuki::DiffDrive::linearVelocity ( ) const [inline]

Definition at line 59 of file diff_drive.hpp.

std::vector<double> kobuki::DiffDrive::pointVelocity ( ) const [inline]

Definition at line 61 of file diff_drive.hpp.

void kobuki::DiffDrive::reset ( const double &  current_heading)

Definition at line 106 of file diff_drive.cpp.

void kobuki::DiffDrive::setVelocityCommands ( const double &  vx,
const double &  wz 
)

Definition at line 126 of file diff_drive.cpp.

void kobuki::DiffDrive::update ( const uint16_t &  time_stamp,
const uint16_t &  left_encoder,
const uint16_t &  right_encoder,
ecl::Pose2D< double > &  pose_update,
ecl::linear_algebra::Vector3d &  pose_update_rates 
)

Updates the odometry from firmware stamps and encoders.

Really horrible - could do with an overhaul.

Parameters:
time_stamp
left_encoder
right_encoder
pose_update
pose_update_rates

Definition at line 53 of file diff_drive.cpp.

void kobuki::DiffDrive::velocityCommands ( const double &  vx,
const double &  wz 
)

Definition at line 133 of file diff_drive.cpp.

void kobuki::DiffDrive::velocityCommands ( const short &  cmd_speed,
const short &  cmd_radius 
)

Definition at line 166 of file diff_drive.cpp.

void kobuki::DiffDrive::velocityCommands ( const std::vector< double > &  cmd) [inline]

Definition at line 51 of file diff_drive.hpp.

void kobuki::DiffDrive::velocityCommands ( const std::vector< short > &  cmd) [inline]

Definition at line 52 of file diff_drive.hpp.

std::vector< short > kobuki::DiffDrive::velocityCommands ( )

Definition at line 174 of file diff_drive.cpp.

double kobuki::DiffDrive::wheel_bias ( ) const [inline]

Definition at line 66 of file diff_drive.hpp.


Member Data Documentation

double kobuki::DiffDrive::bias [private]

Definition at line 80 of file diff_drive.hpp.

Definition at line 85 of file diff_drive.hpp.

Definition at line 82 of file diff_drive.hpp.

Definition at line 71 of file diff_drive.hpp.

Definition at line 74 of file diff_drive.hpp.

Definition at line 74 of file diff_drive.hpp.

unsigned short kobuki::DiffDrive::last_tick_left [private]

Definition at line 73 of file diff_drive.hpp.

unsigned short kobuki::DiffDrive::last_tick_right [private]

Definition at line 73 of file diff_drive.hpp.

unsigned short kobuki::DiffDrive::last_timestamp [private]

Definition at line 69 of file diff_drive.hpp.

Definition at line 70 of file diff_drive.hpp.

Definition at line 70 of file diff_drive.hpp.

std::vector<double> kobuki::DiffDrive::point_velocity [private]

Definition at line 77 of file diff_drive.hpp.

double kobuki::DiffDrive::radius [private]

Definition at line 78 of file diff_drive.hpp.

double kobuki::DiffDrive::speed [private]

Definition at line 79 of file diff_drive.hpp.

ecl::Mutex kobuki::DiffDrive::state_mutex [private]

Definition at line 86 of file diff_drive.hpp.

const double kobuki::DiffDrive::tick_to_rad [private]

Definition at line 83 of file diff_drive.hpp.

ecl::Mutex kobuki::DiffDrive::velocity_mutex [private]

Definition at line 86 of file diff_drive.hpp.

Definition at line 81 of file diff_drive.hpp.


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


kobuki_driver
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Mon Oct 6 2014 01:31:10