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

#include <CanListener.h>

List of all members.

Public Member Functions

 CanListener (RobotState *state)
double get_velocity_left ()
double get_velocity_right ()
void run ()

Public Attributes

struct can_frame frame

Private Member Functions

double calculateAverage (double velocity_average[], double velocity)
nav_msgs::Odometry getOdomMsg (ros::Time current_time)
geometry_msgs::TransformStamped getOdomTF (ros::Time current_time)
bool gettingData ()
void initalize ()
void movingForward (double d, double d_time)
void otherMovement (double d, double t, double d_time)
int overflowDetection (int ticks, int ticks_old)
void turningInPlace (double t, double d_time)

Private Attributes

int average_size
int counter
double impulses_per_mm_left
double impulses_per_mm_right
double left_average
double left_velocity_average [50]
double right_average
double right_velocity_average [50]
RobotStatestate
double wheel_distance

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/>. Gets velocity information from Can and publish them on ROS as odom information.

Definition at line 28 of file CanListener.h.


Constructor & Destructor Documentation

CanListener::CanListener ( RobotState state) [inline]

Definition at line 84 of file CanListener.h.


Member Function Documentation

double CanListener::calculateAverage ( double  velocity_average[],
double  velocity 
) [private]

Calculate average velocity over the last average_size velocities.

Definition at line 183 of file CanListener.cpp.

Definition at line 318 of file CanListener.cpp.

Return the velocity of the wheels, by an average (average_size).

Definition at line 314 of file CanListener.cpp.

nav_msgs::Odometry CanListener::getOdomMsg ( ros::Time  current_time) [private]

Create the odom message, which get published.

Definition at line 70 of file CanListener.cpp.

geometry_msgs::TransformStamped CanListener::getOdomTF ( ros::Time  current_time) [private]

Get the how the actual odom positin is transformed to origin.

Definition at line 49 of file CanListener.cpp.

bool CanListener::gettingData ( ) [private]

Return true if data from Can is received.

Definition at line 97 of file CanListener.cpp.

void CanListener::initalize ( ) [private]

Initalize global paramter.

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/>.

Definition at line 33 of file CanListener.cpp.

void CanListener::movingForward ( double  d,
double  d_time 
) [private]

Calculate position + orientation if moving forward.

Definition at line 134 of file CanListener.cpp.

void CanListener::otherMovement ( double  d,
double  t,
double  d_time 
) [private]

Calculate position + orientation if combined movment of rotation and translation.

Definition at line 158 of file CanListener.cpp.

int CanListener::overflowDetection ( int  ticks,
int  ticks_old 
) [private]

Detect overflow. If wheel rotate 360°.

Definition at line 117 of file CanListener.cpp.

void CanListener::run ( )

Get the velocity from Can, transform them and publish on ROS.

Definition at line 204 of file CanListener.cpp.

void CanListener::turningInPlace ( double  t,
double  d_time 
) [private]

Calculate position + orientation if rotate.

Definition at line 149 of file CanListener.cpp.


Member Data Documentation

Definition at line 41 of file CanListener.h.

int CanListener::counter [private]

Definition at line 44 of file CanListener.h.

struct can_frame CanListener::frame

Definition at line 96 of file CanListener.h.

Definition at line 35 of file CanListener.h.

Definition at line 36 of file CanListener.h.

double CanListener::left_average [private]

Definition at line 38 of file CanListener.h.

double CanListener::left_velocity_average[50] [private]

Definition at line 42 of file CanListener.h.

double CanListener::right_average [private]

Definition at line 39 of file CanListener.h.

Definition at line 43 of file CanListener.h.

Definition at line 34 of file CanListener.h.

double CanListener::wheel_distance [private]

Definition at line 37 of file CanListener.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