sr_subscriber.h
Go to the documentation of this file.
1 
28 #ifndef SR_HAND_SR_SUBSCRIBER_H
29 #define SR_HAND_SR_SUBSCRIBER_H
30 
31 #include <ros/ros.h>
32 #include <vector>
33 #include <string>
34 #include <map>
35 
36 #include <boost/smart_ptr.hpp>
37 
38 // messages
39 #include <sr_robot_msgs/joints_data.h>
40 #include <sr_robot_msgs/joint.h>
41 #include <sr_robot_msgs/contrlr.h>
42 #include <sr_robot_msgs/sendupdate.h>
43 #include <sr_robot_msgs/config.h>
44 #include <sr_robot_msgs/reverseKinematics.h>
45 #include <std_msgs/Float64.h>
46 
48 
49 using ros::NodeHandle;
50 using ros::Subscriber;
52 
53 namespace shadowrobot
54 {
55 
61 {
62 public:
69 
71  ~SRSubscriber();
72 
73 private:
76 
79 
81  void init();
82 
84  // CALLBACKS //
86 
93  void sendupdateCallback(const sr_robot_msgs::sendupdateConstPtr &msg);
94 
97 
104  void cmd_callback(const std_msgs::Float64ConstPtr &msg, std::string &joint_name);
105 
107  std::vector<Subscriber> controllers_sub;
108 
114  void contrlrCallback(const sr_robot_msgs::contrlrConstPtr &msg);
115 
118 
123  void configCallback(const sr_robot_msgs::configConstPtr &msg);
124 
127 }; // end class ShadowhandSubscriber
128 
129 } // namespace shadowrobot
130 
131 #endif // SR_HAND_SR_SUBSCRIBER_H
void contrlrCallback(const sr_robot_msgs::contrlrConstPtr &msg)
boost::shared_ptr< SRArticulatedRobot > sr_articulated_robot
The shadowhand / shadowarm object (can be either an object connected to the real robot or a virtual h...
Definition: sr_subscriber.h:78
Subscriber config_sub
The subscriber to the config topic.
void configCallback(const sr_robot_msgs::configConstPtr &msg)
void init()
init function
void sendupdateCallback(const sr_robot_msgs::sendupdateConstPtr &msg)
std::vector< Subscriber > controllers_sub
The vector of subscribers to the different joint topics.
Subscriber sendupdate_sub
The subscriber to the sendupdate topic.
Definition: sr_subscriber.h:96
void cmd_callback(const std_msgs::Float64ConstPtr &msg, std::string &joint_name)
Subscriber contrlr_sub
The subscriber to the contrlr topic.
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...
NodeHandle node
ros node handle
Definition: sr_subscriber.h:75
SRSubscriber(boost::shared_ptr< SRArticulatedRobot > sr_art_robot)
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...


sr_hand
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:53