36 #include <boost/format.hpp>
37 #include <boost/shared_ptr.hpp>
38 #include <boost/thread/mutex.hpp>
98 std::string param_value;
100 std::stringstream parser(param_value);
102 while (parser >>
value)
103 rslt.push_back(
value);
105 bool eof = parser.eof();
117 ROS_DEBUG(
"LOADING TRIGGER CONTROLLER NODE");
124 ROS_DEBUG(
"MultiTriggerController::init starting");
129 ROS_ERROR(
"MultiTriggerController was not given a digital_output parameter.");
136 ROS_ERROR(
"MultiTriggerController could not find digital output named \"%s\".",
146 std::vector<string> topics;
147 std::vector<double> times;
148 std::vector<uint32_t> values;
154 if (times.size() != topics.size() || times.size() != values.size())
155 ROS_ERROR(
"'topics', 'times' and 'values' parameters must have same length in %s. Ignoring initial settings.",
159 for (
unsigned int i = 0; i < times.size(); i++)
161 ethercat_trigger_controllers::MultiWaveformTransition t;
165 config_.transitions.push_back(t);
168 ethercat_trigger_controllers::SetMultiWaveform::Request req;
170 ethercat_trigger_controllers::SetMultiWaveform::Response dummy;
177 ROS_DEBUG(
"MultiTriggerController::init completed successfully.");
183 ethercat_trigger_controllers::SetMultiWaveform::Request &req,
184 ethercat_trigger_controllers::SetMultiWaveform::Response &resp)
186 std::vector<boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Header> > > new_pubs;
187 new_pubs.reserve(
config_.transitions.size());
188 ethercat_trigger_controllers::MultiWaveform &new_config = req.waveform;
190 double prev_time = -1;
192 double new_transition_period = round((now - new_config.zero_offset) / new_config.period);
193 double current_period_start = new_config.zero_offset + new_transition_period * new_config.period;
194 double now_offset = now - current_period_start;
195 unsigned int new_transition_index = 0;
198 if (new_transition_period <= 0)
200 resp.status_message =
"MultiTrigger period must be >0.";
201 resp.success =
false;
204 for (std::vector<ethercat_trigger_controllers::MultiWaveformTransition>::iterator trans = new_config.transitions.begin();
205 trans != new_config.transitions.end() && resp.success; trans++)
207 if (trans->time < now_offset)
208 new_transition_index++;
210 if (trans->time < 0 || trans->time >= new_config.period)
212 resp.status_message = (boost::format(
"MultiTriggerController::setMultiWaveformSrv transition time (%f) must be >= 0 and < period (%f).")%
213 trans->time%new_config.period).str();
214 resp.success =
false;
217 if (prev_time >= trans->time)
219 resp.status_message = (boost::format(
"MultiTriggerController::setMultiWaveformSrv transition times must be in increasing order. %f >= %f")%
220 prev_time%trans->time).str();
221 resp.success =
false;
225 if (new_transition_index == new_config.transitions.size())
227 new_transition_index = 0;
228 new_transition_period++;
231 double new_transition_time = current_period_start + new_config.transitions[new_transition_index].time;
239 for (std::vector<ethercat_trigger_controllers::MultiWaveformTransition>::iterator trans = new_config.transitions.begin();
240 trans != new_config.transitions.end() && resp.success; trans++)
244 if (trans->topic.compare(
"-"))
247 new_pubs.push_back(new_pub);
259 ROS_ERROR(
"%s", resp.status_message.c_str());