detect position by Odometry More...
#include <Odometry.h>
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) |
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.
Odometry::Odometry | ( | RTC::Manager * | manager | ) |
destructor
Definition at line 64 of file Odometry.cpp.
void Odometry::calcOdometry | ( | ) | [inline, virtual] |
void Odometry::getLocalizedPosition | ( | ) | [inline, virtual] |
bool Odometry::getWheelAngleData | ( | ) | [inline, virtual] |
get Current wheel's Angle data from INPORT
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] |
void Odometry::setCurrentToOld | ( | ) | [inline, virtual] |
struct Odometry::BODY Odometry::Body [private] |
struct Odometry::CURRENT Odometry::Current [private] |
const int Odometry::Dof = 2 [static, private] |
Degree of Freedom = 2(left/right wheel)
Definition at line 285 of file Odometry.h.
bool Odometry::InitialAngleFlag [private] |
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.
bool Odometry::InitialPositionFlag [private] |
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
Definition at line 246 of file Odometry.h.
int Odometry::m_leftWheelID [protected] |
ID number of left wheel of mobile robot.
Definition at line 192 of file Odometry.h.
double Odometry::m_lengthOfAxle [protected] |
length of axle (from left wheel to right wheel)
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
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
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)
Definition at line 231 of file Odometry.h.
double Odometry::m_radiusOfLeftWheel [protected] |
radius of left wheel of mobile robot
Definition at line 208 of file Odometry.h.
double Odometry::m_radiusOfRightWheel [protected] |
radius of right wheel of mobile robot
Definition at line 216 of file Odometry.h.
int Odometry::m_rightWheelID [protected] |
ID number of right wheel of mobile robot.
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.
double Odometry::RotationAngleBorder [private] |
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.