multi_trigger_controller.cpp
Go to the documentation of this file.
1 
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2009, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <boost/format.hpp>
37 
39 #include "ros/console.h"
41 
43 
44 using std::string;
45 using namespace controller;
46 
48 {
49  ROS_DEBUG("creating controller...");
50 }
51 
52 MultiTriggerController::~MultiTriggerController()
53 {
54 }
55 
57 {
58  int maxloops = 10; // @todo Workaround to avoid breaking realtime in response to #3274. Need to revamp things to fix this better.
59 
60  if (!config_.transitions.empty() && config_mutex_.try_lock())
61  { // If we missed the lock, then hold current value for now.
62  ros::Time cur_time = robot_->getTime();
63 
64  while (cur_time.toSec() >= transition_time_) // Usually only happens at most once per update.
65  {
66  if (!maxloops--)
67  {
68  //ROS_ERROR("MultiTriggerController exceeded iteration limit. Please report this to Blaise."); // @todo remove this
69  break;
70  }
71 
72  //ROS_INFO("hit %f %f %i", cur_time.toSec(), transition_time_, config_.transitions[transition_index_].value);
73  // Do the transition
75  if (pubs_[transition_index_] && pubs_[transition_index_]->trylock())
76  {
77  pubs_[transition_index_]->msg_.stamp = cur_time;
78  pubs_[transition_index_]->unlockAndPublish();
79  }
80 
81  // Prepare for next transition
82  if (++transition_index_ == config_.transitions.size())
83  {
86  }
87  transition_time_ = config_.transitions[transition_index_].time + config_.period * transition_period_ + config_.zero_offset;
88  }
89  config_mutex_.unlock();
90  }
91 }
92 
93 template <class T>
94 static bool parseParamList(ros::NodeHandle nh, std::string param, std::vector<T> &rslt)
95 {
96  std::string param_value;
97  nh.getParam(param, param_value);
98  std::stringstream parser(param_value);
99  T value;
100  while (parser >> value)
101  rslt.push_back(value);
102 
103  bool eof = parser.eof();
104 
105  if (!eof)
106  ROS_ERROR("Error parsing '%s/%s' argument to MultiTriggerController.", nh.getNamespace().c_str(), param.c_str());
107 
108  return eof; // Returns true on success
109 }
110 
112 {
113  node_handle_ = n;
114 
115  ROS_DEBUG("LOADING TRIGGER CONTROLLER NODE");
116  //string prefix = config->Attribute("name");
117  //ROS_DEBUG_STREAM("the prefix is "<<prefix);
118 
119  assert(robot);
120  robot_=robot;
121 
122  ROS_DEBUG("MultiTriggerController::init starting");
123 
124  // Get the digital out name.
125 
126  if (!n.getParam("digital_output", digital_output_name_)){
127  ROS_ERROR("MultiTriggerController was not given a digital_output parameter.");
128  return false;
129  }
130 
132  if (!digital_out)
133  {
134  ROS_ERROR("MultiTriggerController could not find digital output named \"%s\".",
135  digital_output_name_.c_str());
136  return false;
137  }
138 
139  digital_out_command_ = &digital_out->command_;
140 
141  n.param("period", config_.period, 1.);
142  n.param("zero_offset", config_.zero_offset, 0.);
143 
144  std::vector<string> topics;
145  std::vector<double> times;
146  std::vector<uint32_t> values;
147 
148  waveform_ = node_handle_.advertise<ethercat_trigger_controllers::MultiWaveform>("waveform", 1, true);
149 
150  if (parseParamList(n, "times", times) && parseParamList(n, "topics", topics) && parseParamList(n, "values", values))
151  {
152  if (times.size() != topics.size() || times.size() != values.size())
153  ROS_ERROR("'topics', 'times' and 'values' parameters must have same length in %s. Ignoring initial settings.",
154  n.getNamespace().c_str());
155  else
156  {
157  for (unsigned int i = 0; i < times.size(); i++)
158  {
159  ethercat_trigger_controllers::MultiWaveformTransition t;
160  t.time = times[i];
161  t.value = values[i];
162  t.topic = topics[i];
163  config_.transitions.push_back(t);
164  }
165 
166  ethercat_trigger_controllers::SetMultiWaveform::Request req;
167  req.waveform = config_;
168  ethercat_trigger_controllers::SetMultiWaveform::Response dummy;
169  setMultiWaveformSrv(req, dummy);
170  }
171  }
172 
174 
175  ROS_DEBUG("MultiTriggerController::init completed successfully.");
176 
177  return true;
178 }
179 
181  ethercat_trigger_controllers::SetMultiWaveform::Request &req,
182  ethercat_trigger_controllers::SetMultiWaveform::Response &resp)
183 {
184  std::vector<boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Header> > > new_pubs;
185  new_pubs.reserve(config_.transitions.size());
186  ethercat_trigger_controllers::MultiWaveform &new_config = req.waveform;
187 
188  double prev_time = -1; // There is a check for negative values below.
189  double now = ros::Time::now().toSec();
190  double new_transition_period = round((now - new_config.zero_offset) / new_config.period);
191  double current_period_start = new_config.zero_offset + new_transition_period * new_config.period;
192  double now_offset = now - current_period_start;
193  unsigned int new_transition_index = 0;
194  resp.success = true;
195 
196  if (new_transition_period <= 0)
197  {
198  resp.status_message = "MultiTrigger period must be >0.";
199  resp.success = false;
200  }
201 
202  for (std::vector<ethercat_trigger_controllers::MultiWaveformTransition>::iterator trans = new_config.transitions.begin();
203  trans != new_config.transitions.end() && resp.success; trans++)
204  {
205  if (trans->time < now_offset)
206  new_transition_index++;
207 
208  if (trans->time < 0 || trans->time >= new_config.period)
209  {
210  resp.status_message = (boost::format("MultiTriggerController::setMultiWaveformSrv transition time (%f) must be >= 0 and < period (%f).")%
211  trans->time%new_config.period).str();
212  resp.success = false;
213  }
214 
215  if (prev_time >= trans->time)
216  {
217  resp.status_message = (boost::format("MultiTriggerController::setMultiWaveformSrv transition times must be in increasing order. %f >= %f")%
218  prev_time%trans->time).str();
219  resp.success = false;
220  }
221  }
222 
223  if (new_transition_index == new_config.transitions.size())
224  {
225  new_transition_index = 0;
226  new_transition_period++;
227  }
228 
229  double new_transition_time = current_period_start + new_config.transitions[new_transition_index].time;
230 
231 // ROS_DEBUG("MultiTriggerController::setMultiWaveformSrv completed successfully"
232 // " rr=%f ph=%f al=%i r=%i p=%i dc=%f.", config_.rep_rate, config_.phase,
233 // config_.active_low, config_.running, config_.pulsed, config_.duty_cycle);
234 
235  if (resp.success)
236  {
237  for (std::vector<ethercat_trigger_controllers::MultiWaveformTransition>::iterator trans = new_config.transitions.begin();
238  trans != new_config.transitions.end() && resp.success; trans++)
239  {
241 
242  if (trans->topic.compare("-"))
243  new_pub.reset(new realtime_tools::RealtimePublisher<std_msgs::Header>(node_handle_, trans->topic, 10));
244 
245  new_pubs.push_back(new_pub);
246  }
247 
248  boost::mutex::scoped_lock lock(config_mutex_);
249  config_ = new_config;
250  pubs_ = new_pubs;
251  transition_period_ = new_transition_period;
252  transition_index_ = new_transition_index;
253  transition_time_ = new_transition_time;
254  waveform_.publish(req.waveform);
255  }
256  else
257  ROS_ERROR("%s", resp.status_message.c_str());
258 
259  return true;
260 }
void publish(const boost::shared_ptr< M > &message) const
pr2_mechanism_model::RobotState * robot_
std::vector< boost::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > > pubs_
pr2_hardware_interface::HardwareInterface * hw_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
DigitalOut * getDigitalOut(const std::string &name) const
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
PLUGINLIB_EXPORT_CLASS(pr2_mechanism_model::PR2BeltCompensatorTransmission, pr2_mechanism_model::Transmission) namespace pr2_mechanism_model
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const std::string & getNamespace() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
pr2_hardware_interface::DigitalOutCommand * digital_out_command_
bool getParam(const std::string &key, std::string &s) const
static Time now()
double & value
static bool parseParamList(ros::NodeHandle nh, std::string param, std::vector< T > &rslt)
#define ROS_ERROR(...)
bool setMultiWaveformSrv(ethercat_trigger_controllers::SetMultiWaveform::Request &req, ethercat_trigger_controllers::SetMultiWaveform::Response &resp)
#define ROS_DEBUG(...)


ethercat_trigger_controllers
Author(s): Blaise Gassend
autogenerated on Wed Jun 5 2019 19:33:55