39 n_tilde(
"~"), publish_rate(0.0)
61 for (
unsigned int i = 0; i < START_OF_ARM; ++i)
67 for (
unsigned int i = START_OF_ARM; i < NUM_HAND_JOINTS; ++i)
80 std::vector <std::string> subname(2);
84 int subname_index = 0;
86 std::string name = hand_joints[index_joint].joint_name;
87 for (
unsigned int j = 0; j < hand_joints[index_joint].num_actuators; ++j)
90 subname_index = (hand_joints[index_joint].num_actuators == 1) ? 1 : j;
93 struct sensor s = hand_joints[index_joint].a.muscle.pressure[j];
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();
100 std::string topic = valve_name +
"/status";
102 topic = valve_name +
"/cmd";
108 ss_valve_name.str(std::string());
109 s = hand_joints[index_joint].a.muscle.pressure_target[j];
111 ss_valve_name << hand_joints[index_joint].joint_name <<
"_" 112 << subname[subname_index] <<
"_Target";
113 valve_name = ss_valve_name.str();
115 topic = valve_name +
"/status";
117 topic = valve_name +
"/cmd";
123 ss_valve_name.str(std::string());
124 s = hand_joints[index_joint].a.muscle.muscles[j];
126 ss_valve_name << hand_joints[index_joint].joint_name <<
"_" 127 << subname[subname_index];
128 valve_name = ss_valve_name.str();
130 topic = valve_name +
"/status";
132 topic = valve_name +
"/cmd";
138 ss_valve_name.str(std::string());
139 s = hand_joints[index_joint].a.muscle.valves[j][FILL_VALVE];
141 ss_valve_name << hand_joints[index_joint].joint_name <<
"_" 142 << subname[subname_index] <<
"_Fill";
143 valve_name = ss_valve_name.str();
145 topic = valve_name +
"/status";
147 topic = valve_name +
"/cmd";
153 ss_valve_name.str(std::string());
154 s = hand_joints[index_joint].a.muscle.valves[j][EMPTY_VALVE];
156 ss_valve_name << hand_joints[index_joint].joint_name <<
"_" 157 << subname[subname_index] <<
"_Empty";
158 valve_name = ss_valve_name.str();
160 topic = valve_name +
"/status";
162 topic = valve_name +
"/cmd";
194 std_msgs::Float64 msg_valves;
This is a ROS Interface used to directly access the valves on Shadow Robot's muscle robots...
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::vector< ros::Subscriber > valves_subscribers
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void valve_command(const std_msgs::Float64ConstPtr &msg, int index_valve)
std::vector< struct sensor > valves_sensors
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< ros::Publisher > valves_publishers
void init_subs_and_pubs(int index_joint)
ROSCPP_DECL void spinOnce()