#include <SetTwistHandler.h>
Public Member Functions | |
unsigned int | getObjectType () const |
void | handleSimulation () |
SetTwistHandler () | |
void | synchronize () |
~SetTwistHandler () | |
Static Public Attributes | |
static const unsigned int | SET_OBJ_TWIST_DATA_ANG_GAIN = SET_OBJ_TWIST_DATA_LIN_GAIN+1 |
static const unsigned int | SET_OBJ_TWIST_DATA_LIN_GAIN = SET_OBJ_TWIST_DATA_MAIN+1 |
static const unsigned int | SET_OBJ_TWIST_DATA_MAIN = 550 |
The main identifier of a Set Twist object. | |
Protected Member Functions | |
void | _initialize () |
void | TwistCommandCallback (const geometry_msgs::TwistStamped &msg) |
Protected Attributes | |
simFloat | _angGain |
simInt | _isStatic |
simFloat | _linGain |
ros::Subscriber | _sub |
geometry_msgs::TwistStamped | _twistCommands |
Handler to control the velocity of an object. It automatically subscribes to geometry_msgs/TwistStamped messages for receiving twist commands. To move the object, generate a message geometry_msgs/TwistStamped in the topic /vrep/object_name_Vrep/SetTwist
Definition at line 15 of file SetTwistHandler.h.
Definition at line 14 of file SetTwistHandler.cpp.
Definition at line 22 of file SetTwistHandler.cpp.
void SetTwistHandler::_initialize | ( | ) | [protected, virtual] |
Implements GenericObjectHandler.
Definition at line 138 of file SetTwistHandler.cpp.
unsigned int SetTwistHandler::getObjectType | ( | ) | const [virtual] |
Implements GenericObjectHandler.
Definition at line 25 of file SetTwistHandler.cpp.
void SetTwistHandler::handleSimulation | ( | ) | [virtual] |
Implements GenericObjectHandler.
Definition at line 59 of file SetTwistHandler.cpp.
void SetTwistHandler::synchronize | ( | ) | [virtual] |
Reimplemented from GenericObjectHandler.
Definition at line 29 of file SetTwistHandler.cpp.
void SetTwistHandler::TwistCommandCallback | ( | const geometry_msgs::TwistStamped & | msg | ) | [protected] |
Callback for velocity commands.
Definition at line 182 of file SetTwistHandler.cpp.
simFloat SetTwistHandler::_angGain [protected] |
Definition at line 69 of file SetTwistHandler.h.
simInt SetTwistHandler::_isStatic [protected] |
Specifies if the object is static or dynamically enabled
Definition at line 66 of file SetTwistHandler.h.
simFloat SetTwistHandler::_linGain [protected] |
Definition at line 68 of file SetTwistHandler.h.
ros::Subscriber SetTwistHandler::_sub [protected] |
Subscriber for Obj twist.
Definition at line 51 of file SetTwistHandler.h.
geometry_msgs::TwistStamped SetTwistHandler::_twistCommands [protected] |
Last received TwistCommand message.
Definition at line 56 of file SetTwistHandler.h.
const unsigned int SetTwistHandler::SET_OBJ_TWIST_DATA_ANG_GAIN = SET_OBJ_TWIST_DATA_LIN_GAIN+1 [static] |
Definition at line 39 of file SetTwistHandler.h.
const unsigned int SetTwistHandler::SET_OBJ_TWIST_DATA_LIN_GAIN = SET_OBJ_TWIST_DATA_MAIN+1 [static] |
Definition at line 38 of file SetTwistHandler.h.
const unsigned int SetTwistHandler::SET_OBJ_TWIST_DATA_MAIN = 550 [static] |
The main identifier of a Set Twist object.
Definition at line 37 of file SetTwistHandler.h.