vrepSubscriber.h
Go to the documentation of this file.
1 // This file is part of the ROS PLUGIN for V-REP
2 //
3 // Copyright 2006-2014 Coppelia Robotics GmbH. All rights reserved.
4 // marc@coppeliarobotics.com
5 // www.coppeliarobotics.com
6 //
7 // A big thanks to Svetlin Penkov for his precious help!
8 //
9 // The ROS PLUGIN is licensed under the terms of GNU GPL:
10 //
11 // -------------------------------------------------------------------
12 // The ROS PLUGIN is free software: you can redistribute it and/or modify
13 // it under the terms of the GNU General Public License as published by
14 // the Free Software Foundation, either version 3 of the License, or
15 // (at your option) any later version.
16 //
17 // THE ROS PLUGIN IS DISTRIBUTED "AS IS", WITHOUT ANY EXPRESS OR IMPLIED
18 // WARRANTY. THE USER WILL USE IT AT HIS/HER OWN RISK. THE ORIGINAL
19 // AUTHORS AND COPPELIA ROBOTICS GMBH WILL NOT BE LIABLE FOR DATA LOSS,
20 // DAMAGES, LOSS OF PROFITS OR ANY OTHER KIND OF LOSS WHILE USING OR
21 // MISUSING THIS SOFTWARE.
22 //
23 // See the GNU General Public License for more details.
24 //
25 // You should have received a copy of the GNU General Public License
26 // along with the ROS PLUGIN. If not, see <http://www.gnu.org/licenses/>.
27 // -------------------------------------------------------------------
28 //
29 // This file was automatically created for V-REP release V3.1.3 on Sept. 30th 2014
30 
31 #ifndef VREP_SUBSCRIBER_H
32 #define VREP_SUBSCRIBER_H
33 
34 #include <ros/ros.h>
35 #include <image_transport/image_transport.h>
36 
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"
58 //#include <trajectory_msgs/JointTrajectory.h>
59 
60 /*
61 struct SJointTrajectory
62 {
63  std::vector<std::string> jointNames;
64  std::vector<SJointTrajectoryPoint> points
65 };
66 
67 struct SJointTrajectoryPoint
68 {
69  std::vector<double> positions;
70  std::vector<double> velocities;
71  std::vector<double> accelerations;
72  std::vector<double> effort;
73  float timeFromStart;
74 };
75 */
76 
78 {
79 public:
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);
81  virtual ~CSubscriberData();
82 
83  bool getIsValid();
84  void setSubscriberID(int id);
85  int getSubscriberID();
86  void shutDownSubscriber();
87 
88 protected:
91 
92  bool isValid;
93  int cmdID;
94  int auxInt1;
95  int auxInt2;
97  std::string auxStr;
98  std::string topicName;
99  ros::Subscriber generalSubscriber;
100  image_transport::Subscriber imageSubscriber;
101 
102 public:
103  void addStatusbarMessageCallback(const std_msgs::String::ConstPtr& msg);
104  void auxiliaryConsolePrintCallback(const std_msgs::String::ConstPtr& txt);
105  void clearFloatSignalCallback(const std_msgs::UInt8::ConstPtr& options);
106  void clearIntegerSignalCallback(const std_msgs::UInt8::ConstPtr& options);
107  void clearStringSignalCallback(const std_msgs::UInt8::ConstPtr& options);
108  void setArrayParameterCallback(const geometry_msgs::Point32::ConstPtr& param);
109  void setBooleanParameterCallback(const std_msgs::UInt8::ConstPtr& param);
110  void setFloatingParameterCallback(const std_msgs::Float32::ConstPtr& param);
111  void setIntegerParameterCallback(const std_msgs::Int32::ConstPtr& param);
112  void setFloatSignalCallback(const std_msgs::Float32::ConstPtr& sig);
113  void setIntegerSignalCallback(const std_msgs::Int32::ConstPtr& sig);
114  void setJointForceCallback(const std_msgs::Float64::ConstPtr& force);
115  void setJointPositionCallback(const std_msgs::Float64::ConstPtr& pos);
116  void setJointTargetPositionCallback(const std_msgs::Float64::ConstPtr& pos);
117  void setJointTargetVelocityCallback(const std_msgs::Float64::ConstPtr& vel);
118  void setTwistCommandCallback(const geometry_msgs::Twist::ConstPtr& vel);
119  void setObjectFloatParameterCallback(const std_msgs::Float32::ConstPtr& param);
120  void setObjectIntParameterCallback(const std_msgs::Int32::ConstPtr& param);
121  void setObjectPoseCallback(const geometry_msgs::PoseStamped::ConstPtr& pose);
122  void setObjectPositionCallback(const geometry_msgs::Point::ConstPtr& pos);
123  void setObjectQuaternionCallback(const geometry_msgs::Quaternion::ConstPtr& quaternion);
124  void setObjectSelectionCallback(const std_msgs::Int32MultiArray::ConstPtr& objHandles);
125  void setStringSignalCallback(const std_msgs::String::ConstPtr& sig);
126  void appendStringSignalCallback(const std_msgs::String::ConstPtr& sig);
127  void setUIButtonLabelCallback(const std_msgs::String::ConstPtr& label);
128  void setUIButtonPropertyCallback(const std_msgs::Int32::ConstPtr& prop);
129  void setUISlider(const std_msgs::Int32::ConstPtr& pos);
130  void setVisionSensorImageCallback(const sensor_msgs::Image::ConstPtr& image);
131  void setJoySensorCallback(const sensor_msgs::Joy::ConstPtr& joyPacket);
132  void setJointStateCallback(const vrep_common::JointSetStateData::ConstPtr& data);
133 // void setJointTrajectoryCallback(const trajectory_msgs::JointTrajectory::ConstPtr& data);
134 };
135 
136 #endif
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 &param)
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)
std::string topicName
void setObjectFloatParameterCallback(const std_msgs::Float32::ConstPtr &param)
void setIntegerParameterCallback(const std_msgs::Int32::ConstPtr &param)
virtual ~CSubscriberData()
void setFloatingParameterCallback(const std_msgs::Float32::ConstPtr &param)
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 addStatusbarMessageCallback(const std_msgs::String::ConstPtr &msg)
void setJointTargetPositionCallback(const std_msgs::Float64::ConstPtr &pos)
void setObjectIntParameterCallback(const std_msgs::Int32::ConstPtr &param)
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 &param)
void setStringSignalCallback(const std_msgs::String::ConstPtr &sig)
void setSubscriberID(int id)
std::string auxStr


vrep_plugin
Author(s): Marc - modified by Barros
autogenerated on Mon Mar 2 2015 01:32:59