tactile.cpp
Go to the documentation of this file.
1 
29 #include <ros/ros.h>
30 #include <string>
31 
32 #include <boost/thread/mutex.hpp>
33 
34 // messages
35 #include <std_msgs/Float64.h>
36 
37 // a ros subscriber (will be instantiated later on)
39 std_msgs::Float64::_data_type data[5];
40 boost::mutex update_mutex;
41 
42 
43 void callback_ff(const std_msgs::Float64ConstPtr &msg)
44 {
45  update_mutex.lock();
46  data[0] = msg->data;
47  update_mutex.unlock();
48 }
49 
50 void callback_mf(const std_msgs::Float64ConstPtr &msg)
51 {
52  update_mutex.lock();
53  data[1] = msg->data;
54  update_mutex.unlock();
55 }
56 
57 void callback_rf(const std_msgs::Float64ConstPtr &msg)
58 {
59  update_mutex.lock();
60  data[2] = msg->data;
61  update_mutex.unlock();
62 }
63 
64 void callback_lf(const std_msgs::Float64ConstPtr &msg)
65 {
66  update_mutex.lock();
67  data[3] = msg->data;
68  update_mutex.unlock();
69 }
70 
71 void callback_th(const std_msgs::Float64ConstPtr &msg)
72 {
73  update_mutex.lock();
74  data[4] = msg->data;
75  update_mutex.unlock();
76 }
77 
78 
79 int main(int argc, char **argv)
80 {
81  // init the ros node
82  ros::init(argc, argv, "test_tactile");
83 
84  ros::NodeHandle node_tactile;
85 
86  sub[0] = node_tactile.subscribe("/sr_tactile/touch/ff", 2, callback_ff);
87  sub[1] = node_tactile.subscribe("/sr_tactile/touch/mf", 2, callback_mf);
88  sub[2] = node_tactile.subscribe("/sr_tactile/touch/rf", 2, callback_rf);
89  sub[3] = node_tactile.subscribe("/sr_tactile/touch/lf", 2, callback_lf);
90  sub[4] = node_tactile.subscribe("/sr_tactile/touch/th", 2, callback_th);
91 
92  ros::Rate publish_rate = ros::Rate(20.0);
93  std_msgs::Float64::_data_type cur_data[5] = {0};
94 
95  while (ros::ok())
96  {
97  update_mutex.lock();
98  for (int i = 0; i < 5; i++)
99  {
100  cur_data[i] = data[i];
101  }
102  update_mutex.unlock();
103 
104  ROS_ERROR("TACTILE SENSOR READING: %f %f %f %f %f",
105  cur_data[0],
106  cur_data[1],
107  cur_data[2],
108  cur_data[3],
109  cur_data[4]);
110 
111  publish_rate.sleep();
112  ros::spinOnce();
113  }
114 
115  return 0;
116 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void callback_mf(const std_msgs::Float64ConstPtr &msg)
Definition: tactile.cpp:50
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
Definition: tactile.cpp:79
void callback_th(const std_msgs::Float64ConstPtr &msg)
Definition: tactile.cpp:71
bool sleep()
void callback_rf(const std_msgs::Float64ConstPtr &msg)
Definition: tactile.cpp:57
void callback_ff(const std_msgs::Float64ConstPtr &msg)
Definition: tactile.cpp:43
void callback_lf(const std_msgs::Float64ConstPtr &msg)
Definition: tactile.cpp:64
ros::Subscriber sub[5]
Definition: tactile.cpp:38
boost::mutex update_mutex
Definition: tactile.cpp:40
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
std_msgs::Float64::_data_type data[5]
Definition: tactile.cpp:39


sr_tactile_sensors
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:46