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

#include <ManipulatorHandler.h>

Inheritance diagram for ManipulatorHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

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

Protected Member Functions

void _initialize ()
void jointCommandCallback (const sensor_msgs::JointStateConstPtr &msg)
 Callback for joint commands.
void VelMobCommandCallback (const geometry_msgs::TwistConstPtr &msg)
 Callback for joint commands.

Protected Attributes

double _acquisitionFrequency
 Joint status publication frequency.
double _axle_lenght
 Number of found joint.
CustomDataHeaders::ManipulatorCtrlMode _defaultModeCtrl
 Default mode controller.
std::vector< int > _handleOfJoints
 Handle of the manipulator joints.
std::vector
< CustomDataHeaders::ManipulatorCtrlMode
_jointCtrlMode
 Manipulator control mode. See ManipulatorCtrlMode.
std::vector< std::string > _jointNames
 Names of the manipulator joints.
ros::Time _lastPrintedMsg
 Time of the last message printed on the console.
simFloat _lastPublishedStatus
 Time of the last published joint status.
sensor_msgs::JointState _lastReceivedCmd
 The last received joint command.
simFloat _lastReceivedCmdTime
 Time of the last received joint command.
double _mb_radius
unsigned int _numJoints
 Number of found joint.
ros::Publisher _pub
 Publisher for the joint status.
ros::Subscriber _sub
 Subscriber for the joint commands.
ros::Subscriber _subVelMob
 Subscriber for the Mobile robots velocity commands .

Detailed Description

Definition at line 11 of file ManipulatorHandler.h.


Constructor & Destructor Documentation

Definition at line 14 of file ManipulatorHandler.cpp.

Definition at line 23 of file ManipulatorHandler.cpp.


Member Function Documentation

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

Implements GenericObjectHandler.

Definition at line 165 of file ManipulatorHandler.cpp.

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

Implements GenericObjectHandler.

Definition at line 26 of file ManipulatorHandler.cpp.

Implements GenericObjectHandler.

Definition at line 41 of file ManipulatorHandler.cpp.

void ManipulatorHandler::jointCommandCallback ( const sensor_msgs::JointStateConstPtr &  msg) [protected]

Callback for joint commands.

Definition at line 400 of file ManipulatorHandler.cpp.

void ManipulatorHandler::synchronize ( ) [virtual]

Reimplemented from GenericObjectHandler.

Definition at line 30 of file ManipulatorHandler.cpp.

void ManipulatorHandler::VelMobCommandCallback ( const geometry_msgs::TwistConstPtr &  msg) [protected]

Callback for joint commands.

Definition at line 417 of file ManipulatorHandler.cpp.


Member Data Documentation

Joint status publication frequency.

Definition at line 55 of file ManipulatorHandler.h.

Number of found joint.

Lenght mobile robot

Definition at line 84 of file ManipulatorHandler.h.

Default mode controller.

Definition at line 90 of file ManipulatorHandler.h.

std::vector<int> ManipulatorHandler::_handleOfJoints [protected]

Handle of the manipulator joints.

Definition at line 40 of file ManipulatorHandler.h.

Manipulator control mode. See ManipulatorCtrlMode.

Definition at line 70 of file ManipulatorHandler.h.

std::vector<std::string> ManipulatorHandler::_jointNames [protected]

Names of the manipulator joints.

Definition at line 43 of file ManipulatorHandler.h.

Time of the last message printed on the console.

Definition at line 64 of file ManipulatorHandler.h.

Time of the last published joint status.

Definition at line 58 of file ManipulatorHandler.h.

sensor_msgs::JointState ManipulatorHandler::_lastReceivedCmd [protected]

The last received joint command.

Definition at line 67 of file ManipulatorHandler.h.

Time of the last received joint command.

Definition at line 61 of file ManipulatorHandler.h.

double ManipulatorHandler::_mb_radius [protected]

Definition at line 87 of file ManipulatorHandler.h.

unsigned int ManipulatorHandler::_numJoints [protected]

Number of found joint.

Definition at line 79 of file ManipulatorHandler.h.

Publisher for the joint status.

Definition at line 46 of file ManipulatorHandler.h.

Subscriber for the joint commands.

Definition at line 49 of file ManipulatorHandler.h.

Subscriber for the Mobile robots velocity commands .

Definition at line 52 of file ManipulatorHandler.h.


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


manipulator_handler
Author(s): Giovanni Claudio
autogenerated on Mon Apr 3 2017 04:03:52