Classes | Public Member Functions | Protected Attributes | Private Attributes | Static Private Attributes
Odometry Class Reference

detect position by Odometry More...

#include <Odometry.h>

List of all members.

Classes

struct  BODY
 structure parameter related to BODY data More...
struct  CURRENT
 structure parameter related to CURRENT data More...

Public Member Functions

virtual void calcOdometry ()
 calc Current Position by Odometry
virtual void getLocalizedPosition ()
 get Localized Position data from INPORT
virtual bool getWheelAngleData ()
 get Current wheel's Angle data from INPORT
 Odometry (RTC::Manager *manager)
 constructor
virtual RTC::ReturnCode_t onActivated (RTC::UniqueId ec_id)
virtual RTC::ReturnCode_t onDeactivated (RTC::UniqueId ec_id)
virtual RTC::ReturnCode_t onExecute (RTC::UniqueId ec_id)
virtual RTC::ReturnCode_t onInitialize ()
virtual void outputData ()
 set DATA and write to OUTPORT
virtual void setCurrentToOld ()
 set current data to previous
 ~Odometry ()
 destructor

Protected Attributes

TimedDoubleSeq m_CurrentWheelAngle
InPort< TimedDoubleSeq > m_CurrentWheelAngleIn
int m_leftWheelID
double m_lengthOfAxle
IIS::TimedPose2D m_LocalizedPosition
InPort< IIS::TimedPose2D > m_LocalizedPositionIn
IIS::TimedPose2D m_OdometryPosition
OutPort< IIS::TimedPose2D > m_OdometryPositionOut
double m_radiusOfBodyArea
double m_radiusOfLeftWheel
double m_radiusOfRightWheel
int m_rightWheelID

Private Attributes

struct Odometry::BODY Body
struct Odometry::CURRENT Current
bool InitialAngleFlag
 InitialFlag [false:current wheel angle have not been initialized yet][true:current wheel angle have been already initialized].
bool InitialPositionFlag
 InitialFlag [false:current position have not been initialized yet][true:current position have been already initialized].
double RhoBorder
 if rho > RhoBorder -> staraight line
double RotationAngleBorder
 the border value used by approximation calculation
double timeStep
 timeStep([sec])

Static Private Attributes

static const int Dof = 2
 Degree of Freedom = 2(left/right wheel)

Detailed Description

detect position by Odometry

(1)get current Wheel Angle data from MotorControlRTC (2)get current Robot's position data from LocalizationRTC (3)calculate current position by Odometry (4)send current odometry position data to LocalizationRTC

[INPUT] (1) current Angle data (encoder data) (2) current position data [OUTPUT] (1) Odometry's position data

Definition at line 90 of file Odometry.h.


Constructor & Destructor Documentation

Odometry::Odometry ( RTC::Manager *  manager)

constructor

Parameters:
managerManeger Object

Definition at line 50 of file Odometry.cpp.

destructor

Definition at line 64 of file Odometry.cpp.


Member Function Documentation

void Odometry::calcOdometry ( ) [inline, virtual]

calc Current Position by Odometry

Returns:
void

Definition at line 440 of file Odometry.cpp.

void Odometry::getLocalizedPosition ( ) [inline, virtual]

get Localized Position data from INPORT

Returns:
void

Definition at line 342 of file Odometry.cpp.

bool Odometry::getWheelAngleData ( ) [inline, virtual]

get Current wheel's Angle data from INPORT

Returns:
bool (true:OK, false:NG)

Definition at line 387 of file Odometry.cpp.

RTC::ReturnCode_t Odometry::onActivated ( RTC::UniqueId  ec_id) [virtual]

(1) update INPORT's data (2) open files for debugging (3) initialize

Definition at line 148 of file Odometry.cpp.

RTC::ReturnCode_t Odometry::onDeactivated ( RTC::UniqueId  ec_id) [virtual]

(1)close files for debugging

Definition at line 223 of file Odometry.cpp.

RTC::ReturnCode_t Odometry::onExecute ( RTC::UniqueId  ec_id) [virtual]

(1)get current Wheel Angle data from MotorControlRTC (2)get current Robot's position data from LocalizationRTC (3)calculate current position by Odometry (4)send current odometry position data to LocalizationRTC

Definition at line 250 of file Odometry.cpp.

RTC::ReturnCode_t Odometry::onInitialize ( ) [virtual]

set Configuration parameters

Definition at line 72 of file Odometry.cpp.

void Odometry::outputData ( ) [inline, virtual]

set DATA and write to OUTPORT

Returns:
void

Definition at line 552 of file Odometry.cpp.

void Odometry::setCurrentToOld ( ) [inline, virtual]

set current data to previous

Returns:
void

Definition at line 524 of file Odometry.cpp.


Member Data Documentation

struct Odometry::BODY Odometry::Body [private]
const int Odometry::Dof = 2 [static, private]

Degree of Freedom = 2(left/right wheel)

Definition at line 285 of file Odometry.h.

InitialFlag [false:current wheel angle have not been initialized yet][true:current wheel angle have been already initialized].

Definition at line 334 of file Odometry.h.

InitialFlag [false:current position have not been initialized yet][true:current position have been already initialized].

Definition at line 333 of file Odometry.h.

TimedDoubleSeq Odometry::m_CurrentWheelAngle [protected]

Definition at line 236 of file Odometry.h.

InPort<TimedDoubleSeq> Odometry::m_CurrentWheelAngleIn [protected]

current Wheel Angle data for Odometry

  • Type: angle data: double, timeStamp:tm
  • Number: angle data:2, timeStamp:1
  • Semantics: current Wheel Angle data for Odometry [0]: left wheel's current data [1]: right wheel's current data
  • Unit: angle data : [rad], timeStamp: [sec],[nanosec]

Definition at line 246 of file Odometry.h.

int Odometry::m_leftWheelID [protected]

ID number of left wheel of mobile robot.

  • Name: leftWheelID leftWheelID
  • DefaultValue: 0
  • Unit: none
  • Constraint: none

Definition at line 192 of file Odometry.h.

double Odometry::m_lengthOfAxle [protected]

length of axle (from left wheel to right wheel)

  • Name: lengthOfAxle lengthOfAxle
  • DefaultValue: 0.441
  • Unit: [m]
  • Constraint: none

Definition at line 224 of file Odometry.h.

IIS::TimedPose2D Odometry::m_LocalizedPosition [protected]

Definition at line 247 of file Odometry.h.

InPort<IIS::TimedPose2D> Odometry::m_LocalizedPositionIn [protected]

current Localized Position data

  • Type: localized Position data: double, timeStamp:tm
  • Number: 4 (x,y, posture angle) , timeStamp:1 ,id[] ,error[]
  • Semantics: current Localized Position data (the position of center of rob ots model) [0]: X data [1]: Y data [2]: posture angle[rad]
  • Unit: X,Y data : [m], Angle : [rad], timeStamp: [sec],[nanosec]

Definition at line 260 of file Odometry.h.

IIS::TimedPose2D Odometry::m_OdometryPosition [protected]

Definition at line 267 of file Odometry.h.

OutPort<IIS::TimedPose2D> Odometry::m_OdometryPositionOut [protected]

current Odometry Position data

  • Type: Odometry Position data: double, timeStamp:tm
  • Number: 4 (x,y, posture angle) , timeStamp:1 ,id[] ,error[]
  • Semantics: current Odometry Position data (the position of center of robo ts model) [0]: X data [1]: Y data [2]: posture angle[rad]
  • Unit: X,Y data : [m], Angle : [rad], timeStamp: [sec],[nanosec]

Definition at line 279 of file Odometry.h.

double Odometry::m_radiusOfBodyArea [protected]

length of body radius (from center of Axle to corner of Body)

  • Name: radiusOfBodyArea radiusOfBodyArea
  • DefaultValue: 0.45
  • Unit: [m]

Definition at line 231 of file Odometry.h.

double Odometry::m_radiusOfLeftWheel [protected]

radius of left wheel of mobile robot

  • Name: radiusOfLeftWheel radiusOfLeftWheel
  • DefaultValue: 0.1
  • Unit: [m]
  • Constraint: none

Definition at line 208 of file Odometry.h.

double Odometry::m_radiusOfRightWheel [protected]

radius of right wheel of mobile robot

  • Name: radiusOfRightWheel radiusOfRightWheel
  • DefaultValue: 0.1
  • Unit: [m]
  • Constraint: none

Definition at line 216 of file Odometry.h.

int Odometry::m_rightWheelID [protected]

ID number of right wheel of mobile robot.

  • Name: rightWheelID rightWheelID
  • DefaultValue: 1
  • Unit: none
  • Constraint: none

Definition at line 200 of file Odometry.h.

double Odometry::RhoBorder [private]

if rho > RhoBorder -> staraight line

Definition at line 288 of file Odometry.h.

the border value used by approximation calculation

Definition at line 287 of file Odometry.h.

double Odometry::timeStep [private]

timeStep([sec])

Definition at line 332 of file Odometry.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


RS003
Author(s):
autogenerated on Tue Jul 23 2013 11:51:29