Public Member Functions | Protected Member Functions | Protected Attributes
QuadrotorHandler Class Reference

#include <QuadrotorHandler.h>

Inheritance diagram for QuadrotorHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

unsigned int getObjectType () const
void handleSimulation ()
 QuadrotorHandler ()
void synchronize ()
 ~QuadrotorHandler ()

Protected Member Functions

void _initialize ()
void CommandsCallback (const sensor_msgs::JointStateConstPtr &msg)

Protected Attributes

std::vector< double > _Commands
int _handleOfCoM
int _handleOfJoint [4]
simFloat _jointPosition [4][3]
ros::Time _lastPrintedMsg
simFloat _lastPublishedStatusTime
sensor_msgs::JointState _lastReceivedCmd
ros::Time _lastReceivedCmdTime
double _ObjStatusFrequency
ros::Publisher _pubIMU
ros::Publisher _pubPose
ros::Publisher _pubTwist
simFloat _quadrotorMass
ros::Subscriber _sub
float _torqueToForceRatio

Detailed Description

Handler of a Quadrotor object.

Definition at line 13 of file QuadrotorHandler.h.


Constructor & Destructor Documentation

Definition at line 18 of file QuadrotorHandler.cpp.

Definition at line 32 of file QuadrotorHandler.cpp.


Member Function Documentation

void QuadrotorHandler::_initialize ( ) [protected, virtual]

Implements GenericObjectHandler.

Definition at line 252 of file QuadrotorHandler.cpp.

void QuadrotorHandler::CommandsCallback ( const sensor_msgs::JointStateConstPtr &  msg) [protected]

Callback for command message reception.

Parameters:
msgReceived force command message.

Definition at line 355 of file QuadrotorHandler.cpp.

unsigned int QuadrotorHandler::getObjectType ( ) const [virtual]

Implements GenericObjectHandler.

Definition at line 35 of file QuadrotorHandler.cpp.

Implements GenericObjectHandler.

Definition at line 69 of file QuadrotorHandler.cpp.

void QuadrotorHandler::synchronize ( ) [virtual]

Reimplemented from GenericObjectHandler.

Definition at line 39 of file QuadrotorHandler.cpp.


Member Data Documentation

std::vector<double> QuadrotorHandler::_Commands [protected]

Last received TKMotorCommands commands.

Definition at line 90 of file QuadrotorHandler.h.

Handle of the robot CoM.

Definition at line 40 of file QuadrotorHandler.h.

Handles of the four propellers.

Definition at line 35 of file QuadrotorHandler.h.

simFloat QuadrotorHandler::_jointPosition[4][3] [protected]

Position of the four propellers w.r.t. the robot CoM.

Definition at line 50 of file QuadrotorHandler.h.

Timer for printing messages.

Definition at line 80 of file QuadrotorHandler.h.

Time of the last Obj twist.

Definition at line 95 of file QuadrotorHandler.h.

sensor_msgs::JointState QuadrotorHandler::_lastReceivedCmd [protected]

Last received TKCommands message.

Definition at line 85 of file QuadrotorHandler.h.

Timer for received commands.

Definition at line 75 of file QuadrotorHandler.h.

Obj twist frequency

Definition at line 101 of file QuadrotorHandler.h.

Publisher for the robot status.

Definition at line 65 of file QuadrotorHandler.h.

Publisher for the robot status.

Definition at line 55 of file QuadrotorHandler.h.

Publisher for the robot status.

Definition at line 59 of file QuadrotorHandler.h.

simFloat QuadrotorHandler::_quadrotorMass [protected]

Handle of the robot CoM.

Definition at line 45 of file QuadrotorHandler.h.

Subscriber for force commands.

Definition at line 70 of file QuadrotorHandler.h.

Ratio between force ( $ f$) and torque ( $\tau$) produced by the propeller, i.e. $\tau = \alpha f$

Definition at line 30 of file QuadrotorHandler.h.


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


quadrotor_handler
Author(s): Giovanni Claudio
autogenerated on Mon Apr 3 2017 04:03:54