valves.cpp
Go to the documentation of this file.
1 
27 #include "sr_hand/hand/valves.h"
28 // our robot code
29 
30 #include <sstream>
31 #include <string>
32 #include <vector>
33 // messages
34 
35 
36 namespace shadowrobot
37 {
39  n_tilde("~"), publish_rate(0.0)
40  {
41  /* We need to attach the program to the robot, or fail if we cannot. */
42  if (robot_init() < 0)
43  {
44  ROS_FATAL("Robot interface broken\n");
45  ROS_BREAK();
46  }
47 
48  /* We need to attach the program to the hand as well, or fail if we cannot. */
49  if (hand_init() < 0)
50  {
51  ROS_FATAL("Arm interface broken\n");
52  ROS_BREAK();
53  }
54 
55  // set publish frequency
56  double publish_freq;
57  n_tilde.param("publish_frequency", publish_freq, 10.0);
58  publish_rate = ros::Rate(publish_freq);
59 
60 #ifdef HAND_MUSCLE
61  for (unsigned int i = 0; i < START_OF_ARM; ++i)
62  {
64  }
65 #endif
66 #ifdef ARM
67  for (unsigned int i = START_OF_ARM; i < NUM_HAND_JOINTS; ++i)
68  {
70  }
71 #endif
72  }
73 
75  {
76  }
77 
78  void Valves::init_subs_and_pubs(int index_joint)
79  {
80  std::vector <std::string> subname(2);
81  subname[0] = "Flex";
82  subname[1] = "Ext";
83 
84  int subname_index = 0;
85 
86  std::string name = hand_joints[index_joint].joint_name;
87  for (unsigned int j = 0; j < hand_joints[index_joint].num_actuators; ++j)
88  {
89  // ! for the old hand the phalange 4 only used the spring and the Ext only
90  subname_index = (hand_joints[index_joint].num_actuators == 1) ? 1 : j;
91 
92  // Pressure
93  struct sensor s = hand_joints[index_joint].a.muscle.pressure[j];
94  valves_sensors.push_back(s);
95  std::stringstream ss_valve_name;
96  ss_valve_name << hand_joints[index_joint].joint_name << "_"
97  << subname[subname_index] << "_Pressure";
98  std::string valve_name = ss_valve_name.str();
99  ROS_DEBUG("%s", valve_name.c_str());
100  std::string topic = valve_name + "/status";
101  valves_publishers.push_back(n_tilde.advertise<std_msgs::Float64>(topic, 2));
102  topic = valve_name + "/cmd";
103  valves_subscribers.push_back(n_tilde.subscribe<std_msgs::Float64>(topic, 10,
104  boost::bind(&Valves::valve_command, this, _1,
105  valves_sensors.size() - 1)));
106 
107  // Pressure_Target
108  ss_valve_name.str(std::string());
109  s = hand_joints[index_joint].a.muscle.pressure_target[j];
110  valves_sensors.push_back(s);
111  ss_valve_name << hand_joints[index_joint].joint_name << "_"
112  << subname[subname_index] << "_Target";
113  valve_name = ss_valve_name.str();
114  ROS_DEBUG("%s", valve_name.c_str());
115  topic = valve_name + "/status";
116  valves_publishers.push_back(n_tilde.advertise<std_msgs::Float64>(topic, 2));
117  topic = valve_name + "/cmd";
118  valves_subscribers.push_back(n_tilde.subscribe<std_msgs::Float64>(topic, 10,
119  boost::bind(&Valves::valve_command, this, _1,
120  valves_sensors.size() - 1)));
121 
122  // Muscles
123  ss_valve_name.str(std::string());
124  s = hand_joints[index_joint].a.muscle.muscles[j];
125  valves_sensors.push_back(s);
126  ss_valve_name << hand_joints[index_joint].joint_name << "_"
127  << subname[subname_index];
128  valve_name = ss_valve_name.str();
129  ROS_DEBUG("%s", valve_name.c_str());
130  topic = valve_name + "/status";
131  valves_publishers.push_back(n_tilde.advertise<std_msgs::Float64>(topic, 2));
132  topic = valve_name + "/cmd";
133  valves_subscribers.push_back(n_tilde.subscribe<std_msgs::Float64>(topic, 10,
134  boost::bind(&Valves::valve_command, this, _1,
135  valves_sensors.size() - 1)));
136 
137  // Fill
138  ss_valve_name.str(std::string());
139  s = hand_joints[index_joint].a.muscle.valves[j][FILL_VALVE];
140  valves_sensors.push_back(s);
141  ss_valve_name << hand_joints[index_joint].joint_name << "_"
142  << subname[subname_index] << "_Fill";
143  valve_name = ss_valve_name.str();
144  ROS_DEBUG("%s", valve_name.c_str());
145  topic = valve_name + "/status";
146  valves_publishers.push_back(n_tilde.advertise<std_msgs::Float64>(topic, 2));
147  topic = valve_name + "/cmd";
148  valves_subscribers.push_back(n_tilde.subscribe<std_msgs::Float64>(topic, 10,
149  boost::bind(&Valves::valve_command, this, _1,
150  valves_sensors.size() - 1)));
151 
152  // Empty
153  ss_valve_name.str(std::string());
154  s = hand_joints[index_joint].a.muscle.valves[j][EMPTY_VALVE];
155  valves_sensors.push_back(s);
156  ss_valve_name << hand_joints[index_joint].joint_name << "_"
157  << subname[subname_index] << "_Empty";
158  valve_name = ss_valve_name.str();
159  ROS_DEBUG("%s", valve_name.c_str());
160  topic = valve_name + "/status";
161  valves_publishers.push_back(n_tilde.advertise<std_msgs::Float64>(topic, 2));
162  topic = valve_name + "/cmd";
163  valves_subscribers.push_back(n_tilde.subscribe<std_msgs::Float64>(topic, 10,
164  boost::bind(&Valves::valve_command, this, _1,
165  valves_sensors.size() - 1)));
166  }
167  }
168 
169 
182  void Valves::valve_command(const std_msgs::Float64ConstPtr &msg, int index_valve)
183  {
184  // @fixme: do some clipping on the value first?
185  robot_update_sensor(&(valves_sensors[index_valve]), msg->data);
186  }
187 
193  {
194  std_msgs::Float64 msg_valves;
195 
196  for (unsigned int i = 0; i < valves_sensors.size(); ++i)
197  {
198  msg_valves.data = robot_read_sensor(&(valves_sensors[i]));
199 
200  valves_publishers[i].publish(msg_valves);
201  }
202 
203  ros::spinOnce();
205  }
206 } // namespace shadowrobot
207 
208 
209 /* For the emacs weenies in the crowd.
210 Local Variables:
211  c-basic-offset: 2
212 End:
213 */
#define ROS_FATAL(...)
This is a ROS Interface used to directly access the valves on Shadow Robot&#39;s muscle robots...
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Rate publish_rate
Definition: valves.h:63
~Valves()
destructor
Definition: valves.cpp:74
std::vector< ros::Subscriber > valves_subscribers
Definition: valves.h:60
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void valve_command(const std_msgs::Float64ConstPtr &msg, int index_valve)
Definition: valves.cpp:182
std::vector< struct sensor > valves_sensors
Definition: valves.h:57
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle n_tilde
Definition: valves.h:62
std::vector< ros::Publisher > valves_publishers
Definition: valves.h:59
bool sleep()
void init_subs_and_pubs(int index_joint)
Definition: valves.cpp:78
ROSCPP_DECL void spinOnce()
#define ROS_BREAK()
#define ROS_DEBUG(...)


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