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

MotorControl. More...

#include <MotorControl.h>

List of all members.

Classes

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

Public Member Functions

 MotorControl (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 ()
 ~MotorControl ()
 destructor

Protected Attributes

MotorSVC_impl m_BumpMotor
RTC::CorbaPort m_BumpProvPort
double m_DGainL
double m_DGainR
TimedDoubleSeq m_InCurrentWheelAngle
InPort< TimedDoubleSeq > m_InCurrentWheelAngleIn
TimedDoubleSeq m_InSimulatedPosition
InPort< TimedDoubleSeq > m_InSimulatedPositionIn
MotorSVC_impl m_InventGUIMotor
RTC::CorbaPort m_InventGUIProvPort
int m_leftWheelID
double m_lengthOfAxle
TimedDoubleSeq m_OutCurrentWheelAngle
OutPort< TimedDoubleSeq > m_OutCurrentWheelAngleOut
TimedDoubleSeq m_OutSimulatedPositionToInventGUI
OutPort< TimedDoubleSeq > m_OutSimulatedPositionToInventGUIOut
TimedDoubleSeq m_OutSimulatedPositionToLocalization
OutPort< TimedDoubleSeq > m_OutSimulatedPositionToLocalizationOut
double m_PGainL
double m_PGainR
double m_radiusOfBodyArea
double m_radiusOfLeftWheel
double m_radiusOfRightWheel
int m_rightWheelID
double m_SimulatedOffsetAngle
double m_SimulatedOffsetX
double m_SimulatedOffsetY
TimedVelocity m_TargetVelocity
InPort< TimedVelocity > m_TargetVelocityIn
TimedDoubleSeq m_Torque
OutPort< TimedDoubleSeq > m_TorqueOut

Private Attributes

struct MotorControl::BODY Body
int compSwitch
 FLAG (if inputed NweData from service Port)
bool InitializeFlag
 FLAG (initialize flag of Wheel Angle)
unsigned long nsec
 time [nano sec]
double qOld [Dof]
 for holding previous wheel angle's data
unsigned long sec
 time [sec]
double TimeStamp
 time stamp (sec + 1.0e-9*nsec);
double TimeStampOld
 previous time stamp
double timeStep
 timeStep([sec])

Static Private Attributes

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

Detailed Description

MotorControl.

(1)getting target trans/rot Velocity of robot's center data from DriveControl RTC (2)calculating Torque values (3)sending Torque data to Simulator or real Motor (4)getting current Angle data (encoder dadta) from Simulator or Real Robot (5)sending current Angle data to DriveControlRTC and OdometryRTC

[INPUT] (1) target Trans/Rot Velocity data (2) current Angle data (encoder data) [OUTPUT] (1) Torque data (2) current Angle data

[Calculating Torque values using current/target angle/AngVel values] [Torque] = Pgain * ([TargetAngle] - [CurrentAngle]) * Dgain * ([TargetAngVel]

Definition at line 104 of file MotorControl.h.


Constructor & Destructor Documentation

MotorControl::MotorControl ( RTC::Manager *  manager)

constructor

Parameters:
managerManeger Object

Definition at line 62 of file MotorControl.cpp.

destructor

Definition at line 82 of file MotorControl.cpp.


Member Function Documentation

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

(1) update INPORT's data (2) open files for debugging (3) initialize (4) get robot's parameter

Definition at line 187 of file MotorControl.cpp.

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

(1)close files for debugging

Definition at line 236 of file MotorControl.cpp.

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

(1)getting target trans/rot Velocity of robot's center data from DriveControl RTC (2)calculating Torque values (3)sending Torque data to Simulator or real Motor (4)getting current Angle data (encoder dadta) from Simulator or Real Robot (5)sending current Angle data to DriveControlRTC or OdometryRTC

Definition at line 256 of file MotorControl.cpp.

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

set Configuration parameters

Definition at line 92 of file MotorControl.cpp.


Member Data Documentation

int MotorControl::compSwitch [private]

FLAG (if inputed NweData from service Port)

Definition at line 568 of file MotorControl.h.

const int MotorControl::Dof = 2 [static, private]

Degree of Freedom = 2(left/right wheel)

Definition at line 559 of file MotorControl.h.

FLAG (initialize flag of Wheel Angle)

Definition at line 570 of file MotorControl.h.

If get BumpDetected information, set 0.0 values to Torque data for stopping MOTOR.

  • Argument: void
  • Return Value: void

Definition at line 540 of file MotorControl.h.

RTC::CorbaPort MotorControl::m_BumpProvPort [protected]

for BumpDetectionRTC Interface: (1) for receiving bump command

Definition at line 515 of file MotorControl.h.

double MotorControl::m_DGainL [protected]

Left Wheel's D gain value of PD control

  • Name: DGainL DGainL
  • DefaultValue: 2.0

Definition at line 323 of file MotorControl.h.

double MotorControl::m_DGainR [protected]

Right Wheel's D gain value of PD control

  • Name: DGainR DGainR
  • DefaultValue: 2.0

Definition at line 335 of file MotorControl.h.

TimedDoubleSeq MotorControl::m_InCurrentWheelAngle [protected]

Definition at line 418 of file MotorControl.h.

InPort<TimedDoubleSeq> MotorControl::m_InCurrentWheelAngleIn [protected]

current Wheel Angle data for PD control

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

Definition at line 428 of file MotorControl.h.

TimedDoubleSeq MotorControl::m_InSimulatedPosition [protected]

Definition at line 429 of file MotorControl.h.

InPort<TimedDoubleSeq> MotorControl::m_InSimulatedPositionIn [protected]

current Simulated Position data

  • Type: double
  • Number: 12 (x,y,z, posture angle matrix:9)
  • Semantics: current Simulated Position data (the position of center of rob ots model) [0]: X data [1]: Y data [2]: Z data [3]-[11]: 3x3 Matrix data (posture angle)
  • Unit: X,Y,Z data : [m]

Definition at line 442 of file MotorControl.h.

[Provider] (1) for changing GAIN parameters (2) for receiving start/finish etc.. commands

  • Argument: setPDGain() PGainL : P gain (LeftWheel) of PD control PGainR : P gain (RightWheel) of PD control DGainL : D gain (LeftWheel) of PD control DGainR : D gain (RightWheel) of PD control
  • Return Value: void

Definition at line 532 of file MotorControl.h.

RTC::CorbaPort MotorControl::m_InventGUIProvPort [protected]

for InventGUIRTC Interface: [Provider] (1) for changing GAIN parameters (2) for receiving start/finish etc.. commands

Definition at line 510 of file MotorControl.h.

int MotorControl::m_leftWheelID [protected]

ID number of left wheel of mobile robot.

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

Definition at line 361 of file MotorControl.h.

double MotorControl::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 393 of file MotorControl.h.

TimedDoubleSeq MotorControl::m_OutCurrentWheelAngle [protected]

Definition at line 474 of file MotorControl.h.

OutPort<TimedDoubleSeq> MotorControl::m_OutCurrentWheelAngleOut [protected]

current Wheel Angle data for sending to [OdometryRTC]

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

Definition at line 484 of file MotorControl.h.

Definition at line 449 of file MotorControl.h.

OutPort<TimedDoubleSeq> MotorControl::m_OutSimulatedPositionToInventGUIOut [protected]

current Simulated Position data

  • Type: simulated position data: double, timeStamp:tm
  • Number: simulated position data:4 (x,y,z, posture angle ) , timeStamp:1
  • Semantics: current Simulated Position data (the position of center of rob ots model) [0]: X data [1]: Y data [2]: Z data [3]: THETA (posture angle)
  • Unit: X,Y,Z data : [m], THETA[rad] , timeStamp: [sec],[nanosec]

Definition at line 462 of file MotorControl.h.

Definition at line 485 of file MotorControl.h.

OutPort<TimedDoubleSeq> MotorControl::m_OutSimulatedPositionToLocalizationOut [protected]

current Simulated Position data

  • Type: simulated position data: double, timeStamp:tm
  • Number: simulated position data:4 (x,y,z, posture angle ) , timeStamp:1
  • Semantics: current Simulated Position data (the position of center of rob ots model) [0]: X data [1]: Y data [2]: Z data [3]: THETA (posture angle)
  • Unit: X,Y,Z data : [m], THETA[rad] , timeStamp: [sec],[nanosec]

Definition at line 498 of file MotorControl.h.

double MotorControl::m_PGainL [protected]

Left Wheel's P gain value of PD control

  • Name: PGainL PGainL
  • DefaultValue: 5.0

Definition at line 317 of file MotorControl.h.

double MotorControl::m_PGainR [protected]

Right Wheel's P gain value of PD control

  • Name: PGainR PGainR
  • DefaultValue: 5.0

Definition at line 329 of file MotorControl.h.

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

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

Definition at line 400 of file MotorControl.h.

radius of left wheel of mobile robot

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

Definition at line 377 of file MotorControl.h.

radius of right wheel of mobile robot

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

Definition at line 385 of file MotorControl.h.

ID number of right wheel of mobile robot.

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

Definition at line 369 of file MotorControl.h.

offset for adjustment of initial posture angle

  • Name: SimulatedOffsetAngle SimulatedOffsetAngle
  • DefaultValue: 0.0

Definition at line 353 of file MotorControl.h.

distance from CenterOfBody to CenterOfAxle of Model

  • Name: SimulatedOffsetX SimulatedOffsetX
  • DefaultValue: 0.0

Definition at line 341 of file MotorControl.h.

distance from CenterOfBody to CenterOfAxle of Model

  • Name: SimulatedOffsetY SimulatedOffsetY
  • DefaultValue: 0.0

Definition at line 347 of file MotorControl.h.

TimedVelocity MotorControl::m_TargetVelocity [protected]

Definition at line 405 of file MotorControl.h.

InPort<TimedVelocity> MotorControl::m_TargetVelocityIn [protected]

target Trans/Rot Velocity of robot's center data for PD control

  • Type: Trans/Rot velocity data: double, timeStamp:tm
  • Number: Trans velocity data:2, Rot velocity data:1, timeStamp:1
  • Semantics: target Trans/Rot Velocity of robot's center data for PD contro l [Trans Velocity]: translational velocity of robot's center [m/sec] [Rot Velocity]: rotation velocity (swing velocity) of robot's center [rad/sec]
  • Unit: Trans velocity [m/s], Rot velocity [rad/s], timeStamp: [sec],[nan osec]

Definition at line 417 of file MotorControl.h.

TimedDoubleSeq MotorControl::m_Torque [protected]

Definition at line 463 of file MotorControl.h.

OutPort<TimedDoubleSeq> MotorControl::m_TorqueOut [protected]

Torque data

  • Type: Torque data: double, timeStamp:tm
  • Number: Torque data:2, timeStamp:1
  • Semantics: Torque data [0]: left wheel's torque data [1]: right wheel's torque data
  • Unit: torque data : [], timeStamp: [sec],[nanosec]

Definition at line 473 of file MotorControl.h.

unsigned long MotorControl::nsec [private]

time [nano sec]

Definition at line 567 of file MotorControl.h.

double MotorControl::qOld[Dof] [private]

for holding previous wheel angle's data

Definition at line 569 of file MotorControl.h.

unsigned long MotorControl::sec [private]

time [sec]

Definition at line 566 of file MotorControl.h.

double MotorControl::TimeStamp [private]

time stamp (sec + 1.0e-9*nsec);

Definition at line 564 of file MotorControl.h.

double MotorControl::TimeStampOld [private]

previous time stamp

Definition at line 565 of file MotorControl.h.

double MotorControl::timeStep [private]

timeStep([sec])

Definition at line 563 of file MotorControl.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