31 #ifndef VREP_SUBSCRIBER_H
32 #define VREP_SUBSCRIBER_H
35 #include <image_transport/image_transport.h>
37 #include <sensor_msgs/Image.h>
38 #include <sensor_msgs/image_encodings.h>
39 #include <sensor_msgs/JointState.h>
40 #include <sensor_msgs/Joy.h>
41 #include <std_msgs/Int32MultiArray.h>
42 #include <std_msgs/Float32.h>
43 #include <std_msgs/Float64.h>
44 #include <std_msgs/Int32.h>
45 #include <std_msgs/UInt8.h>
46 #include <std_msgs/String.h>
47 #include <geometry_msgs/Point.h>
48 #include <geometry_msgs/Vector3.h>
49 #include <geometry_msgs/PoseStamped.h>
50 #include <geometry_msgs/Quaternion.h>
51 #include <geometry_msgs/Twist.h>
52 #include "vrep_common/VisionSensorDepthBuff.h"
53 #include "vrep_common/ForceSensorData.h"
54 #include "vrep_common/ProximitySensorData.h"
55 #include "vrep_common/VisionSensorData.h"
56 #include "vrep_common/VrepInfo.h"
57 #include "vrep_common/JointSetStateData.h"
80 CSubscriberData(ros::NodeHandle* node,
const char* _topicName,
int queueSize,
int _streamCmd,
int _auxInt1,
int _auxInt2,
const char* _auxString,image_transport::ImageTransport* images_streamer[1],
int& imgStreamerCnt);
129 void setUISlider(
const std_msgs::Int32::ConstPtr& pos);
void clearStringSignalCallback(const std_msgs::UInt8::ConstPtr &options)
void setJointStateCallback(const vrep_common::JointSetStateData::ConstPtr &data)
void appendStringSignalCallback(const std_msgs::String::ConstPtr &sig)
void clearFloatSignalCallback(const std_msgs::UInt8::ConstPtr &options)
void setObjectPositionCallback(const geometry_msgs::Point::ConstPtr &pos)
void setBooleanParameterCallback(const std_msgs::UInt8::ConstPtr ¶m)
void setUIButtonLabelCallback(const std_msgs::String::ConstPtr &label)
void setJointPositionCallback(const std_msgs::Float64::ConstPtr &pos)
void shutDownGeneralSubscriber()
void setFloatSignalCallback(const std_msgs::Float32::ConstPtr &sig)
void setObjectPoseCallback(const geometry_msgs::PoseStamped::ConstPtr &pose)
void setIntegerSignalCallback(const std_msgs::Int32::ConstPtr &sig)
void setJoySensorCallback(const sensor_msgs::Joy::ConstPtr &joyPacket)
void setVisionSensorImageCallback(const sensor_msgs::Image::ConstPtr &image)
void setObjectFloatParameterCallback(const std_msgs::Float32::ConstPtr ¶m)
void setIntegerParameterCallback(const std_msgs::Int32::ConstPtr ¶m)
virtual ~CSubscriberData()
void setFloatingParameterCallback(const std_msgs::Float32::ConstPtr ¶m)
CSubscriberData(ros::NodeHandle *node, const char *_topicName, int queueSize, int _streamCmd, int _auxInt1, int _auxInt2, const char *_auxString, image_transport::ImageTransport *images_streamer[1], int &imgStreamerCnt)
image_transport::Subscriber imageSubscriber
ros::Subscriber generalSubscriber
void shutDownSubscriber()
void addStatusbarMessageCallback(const std_msgs::String::ConstPtr &msg)
void setJointTargetPositionCallback(const std_msgs::Float64::ConstPtr &pos)
void setObjectIntParameterCallback(const std_msgs::Int32::ConstPtr ¶m)
void clearIntegerSignalCallback(const std_msgs::UInt8::ConstPtr &options)
void setUIButtonPropertyCallback(const std_msgs::Int32::ConstPtr &prop)
void auxiliaryConsolePrintCallback(const std_msgs::String::ConstPtr &txt)
void setJointForceCallback(const std_msgs::Float64::ConstPtr &force)
void setTwistCommandCallback(const geometry_msgs::Twist::ConstPtr &vel)
void setUISlider(const std_msgs::Int32::ConstPtr &pos)
void shutDownImageSubscriber()
void setJointTargetVelocityCallback(const std_msgs::Float64::ConstPtr &vel)
void setObjectSelectionCallback(const std_msgs::Int32MultiArray::ConstPtr &objHandles)
void setObjectQuaternionCallback(const geometry_msgs::Quaternion::ConstPtr &quaternion)
void setArrayParameterCallback(const geometry_msgs::Point32::ConstPtr ¶m)
void setStringSignalCallback(const std_msgs::String::ConstPtr &sig)
void setSubscriberID(int id)