Public Member Functions | Private Member Functions | Private Attributes
BaseController Class Reference

#include <BaseController.h>

List of all members.

Public Member Functions

 BaseController (RobotState *state, CanListener *canListener1)
double calculateAdapter (double required_velocity, double real_velocity, double adapter)
void run ()
void setTargetVelocity (const geometry_msgs::Twist &twist)

Private Member Functions

float calculateVelocity (bool left, float speed, float velocity_old)
bool enableMotor (int ax10420)
int initAX10420 ()
void writeDataToCan (float vleft, float vright, float max_speed)

Private Attributes

CanListenercanListener
geometry_msgs::Twist cmd
boost::mutex mutex
RobotStatestate

Detailed Description

Copyright (c) 2016, Aumann Florian, Borella Jocelyn, Dehmani Souheil, Marek Felix, Meißner Pascal, Reckling Reno

This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.

This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.

You should have received a copy of the GNU General Public License along with this program. If not, see <http://www.gnu.org/licenses/>. Get drive/velocity commends from ros. Transfrom and send them to CAN.

Definition at line 31 of file BaseController.h.


Constructor & Destructor Documentation

BaseController::BaseController ( RobotState state,
CanListener canListener1 
) [inline]

Definition at line 52 of file BaseController.h.


Member Function Documentation

double BaseController::calculateAdapter ( double  required_velocity,
double  real_velocity,
double  adapter 
)

Calculate the adaptation, which needed if required velocity and real velocity is different.

Parameters:
required_velocitycalculate velocity from ROS and adjusted for CAN. [cm/s]
real_velocityvelocity from the CAN (CanListener). [cm/s]
adapteradaptation value which is updated.

Definition at line 226 of file BaseController.cpp.

float BaseController::calculateVelocity ( bool  left,
float  speed,
float  velocity_old 
) [private]

Definition at line 107 of file BaseController.cpp.

bool BaseController::enableMotor ( int  ax10420) [private]

Definition at line 87 of file BaseController.cpp.

int BaseController::initAX10420 ( ) [private]

Definition at line 45 of file BaseController.cpp.

This function handles all the mild_base_driving bus/motor/relais board related stuff. Gets the messages from ros and transform them to can-commands.

Definition at line 128 of file BaseController.cpp.

void BaseController::setTargetVelocity ( const geometry_msgs::Twist &  twist)

This function is triggered when a Twist message is received.

Definition at line 256 of file BaseController.cpp.

void BaseController::writeDataToCan ( float  vleft,
float  vright,
float  max_speed 
) [private]

Definition at line 60 of file BaseController.cpp.


Member Data Documentation

Definition at line 36 of file BaseController.h.

geometry_msgs::Twist BaseController::cmd [private]

Definition at line 39 of file BaseController.h.

boost::mutex BaseController::mutex [private]

Definition at line 37 of file BaseController.h.

Definition at line 35 of file BaseController.h.


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


asr_mild_base_driving
Author(s): Aumann Florian, Borella Jocelyn, Dehmani Souheil, Marek Felix, Meißner Pascal, Reckling Reno
autogenerated on Thu Jun 6 2019 22:02:58