#include <SetTwistHandler.h>
Public Member Functions | |
unsigned int | getObjectType () const |
void | handleSimulation () |
SetTwistHandler () | |
void | synchronize () |
~SetTwistHandler () | |
Protected Member Functions | |
void | _initialize () |
void | TwistCommandCallback (const geometry_msgs::TwistStamped &msg) |
Protected Attributes | |
simInt | _isStatic |
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 17 of file SetTwistHandler.cpp.
void SetTwistHandler::_initialize | ( | ) | [protected, virtual] |
Implements GenericObjectHandler.
Definition at line 114 of file SetTwistHandler.cpp.
unsigned int SetTwistHandler::getObjectType | ( | ) | const [virtual] |
Implements GenericObjectHandler.
Definition at line 20 of file SetTwistHandler.cpp.
void SetTwistHandler::handleSimulation | ( | ) | [virtual] |
Implements GenericObjectHandler.
Definition at line 54 of file SetTwistHandler.cpp.
void SetTwistHandler::synchronize | ( | ) | [virtual] |
Reimplemented from GenericObjectHandler.
Definition at line 24 of file SetTwistHandler.cpp.
void SetTwistHandler::TwistCommandCallback | ( | const geometry_msgs::TwistStamped & | msg | ) | [protected] |
Callback for velocity commands.
Definition at line 165 of file SetTwistHandler.cpp.
simInt SetTwistHandler::_isStatic [protected] |
Specifies if the object is static or dynamically enabled
Definition at line 61 of file SetTwistHandler.h.
ros::Subscriber SetTwistHandler::_sub [protected] |
Subscriber for Obj twist.
Definition at line 46 of file SetTwistHandler.h.
geometry_msgs::TwistStamped SetTwistHandler::_twistCommands [protected] |
Last received TwistCommand message.
Definition at line 51 of file SetTwistHandler.h.