Public Member Functions | Private Member Functions | Private Attributes | List of all members
xbot::DiffDrive Class Reference

#include <diff_drive.hpp>

Public Member Functions

 DiffDrive ()
 
void getWheelJointStates (float &wheel_left_angle, float &wheel_left_angle_rate, float &wheel_right_angle, float &wheel_right_angle_rate)
 
const ecl::DifferentialDrive::Kinematicskinematics ()
 
std::vector< float > pointVelocity () const
 
void reset ()
 
void setVelocityCommands (const float &vx, const float &wz)
 
void update (const unsigned int &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. More...
 
void velocityCommands (const float &vx, const float &wz)
 
void velocityCommands (const std::vector< float > &cmd)
 
std::vector< float > velocityCommands ()
 
float wheel_bias () const
 

Private Member Functions

short bound (const float &value)
 

Private Attributes

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

Detailed Description

Definition at line 37 of file diff_drive.hpp.

Constructor & Destructor Documentation

xbot::DiffDrive::DiffDrive ( )

Definition at line 25 of file diff_drive.cpp.

Member Function Documentation

short xbot::DiffDrive::bound ( const float &  value)
private

Definition at line 165 of file diff_drive.cpp.

void xbot::DiffDrive::getWheelJointStates ( float &  wheel_left_angle,
float &  wheel_left_angle_rate,
float &  wheel_right_angle,
float &  wheel_right_angle_rate 
)

Definition at line 122 of file diff_drive.cpp.

const ecl::DifferentialDrive::Kinematics& xbot::DiffDrive::kinematics ( )
inline

Definition at line 40 of file diff_drive.hpp.

std::vector< float > xbot::DiffDrive::pointVelocity ( ) const

Definition at line 153 of file diff_drive.cpp.

void xbot::DiffDrive::reset ( )

Definition at line 113 of file diff_drive.cpp.

void xbot::DiffDrive::setVelocityCommands ( const float &  vx,
const float &  wz 
)

Definition at line 134 of file diff_drive.cpp.

void xbot::DiffDrive::update ( const unsigned int &  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 54 of file diff_drive.cpp.

void xbot::DiffDrive::velocityCommands ( const float &  vx,
const float &  wz 
)

Definition at line 143 of file diff_drive.cpp.

void xbot::DiffDrive::velocityCommands ( const std::vector< float > &  cmd)
inline

Definition at line 51 of file diff_drive.hpp.

std::vector< float > xbot::DiffDrive::velocityCommands ( )

Definition at line 155 of file diff_drive.cpp.

float xbot::DiffDrive::wheel_bias ( ) const
inline

Definition at line 62 of file diff_drive.hpp.

Member Data Documentation

float xbot::DiffDrive::angular_velocity
private

Definition at line 74 of file diff_drive.hpp.

float xbot::DiffDrive::bias
private

Definition at line 76 of file diff_drive.hpp.

ecl::DifferentialDrive::Kinematics xbot::DiffDrive::diff_drive_kinematics
private

Definition at line 81 of file diff_drive.hpp.

int xbot::DiffDrive::imu_heading_offset
private

Definition at line 78 of file diff_drive.hpp.

float xbot::DiffDrive::last_diff_time
private

Definition at line 67 of file diff_drive.hpp.

float xbot::DiffDrive::last_rad_left
private

Definition at line 70 of file diff_drive.hpp.

float xbot::DiffDrive::last_rad_right
private

Definition at line 70 of file diff_drive.hpp.

unsigned short xbot::DiffDrive::last_tick_left
private

Definition at line 69 of file diff_drive.hpp.

unsigned short xbot::DiffDrive::last_tick_right
private

Definition at line 69 of file diff_drive.hpp.

unsigned int xbot::DiffDrive::last_timestamp
private

Definition at line 65 of file diff_drive.hpp.

float xbot::DiffDrive::last_velocity_left
private

Definition at line 66 of file diff_drive.hpp.

float xbot::DiffDrive::last_velocity_right
private

Definition at line 66 of file diff_drive.hpp.

float xbot::DiffDrive::linear_velocity
private

Definition at line 75 of file diff_drive.hpp.

std::vector<float> xbot::DiffDrive::point_velocity
private

Definition at line 73 of file diff_drive.hpp.

ecl::Mutex xbot::DiffDrive::state_mutex
private

Definition at line 82 of file diff_drive.hpp.

const float xbot::DiffDrive::tick_to_rad
private

Definition at line 79 of file diff_drive.hpp.

ecl::Mutex xbot::DiffDrive::velocity_mutex
private

Definition at line 82 of file diff_drive.hpp.

float xbot::DiffDrive::wheel_radius
private

Definition at line 77 of file diff_drive.hpp.


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


xbot_driver
Author(s): Roc, wangpeng@droid.ac.cn
autogenerated on Sat Oct 10 2020 03:27:38