trigger_controller.h
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 #ifndef TRIGGER_CONTROLLER_H
36 #define TRIGGER_CONTROLLER_H
37 
38 #include <ros/node_handle.h>
41 #include <ethercat_trigger_controllers/SetWaveform.h>
43 #include <std_msgs/Header.h>
44 #include <boost/scoped_ptr.hpp>
45 
52 namespace controller
53 {
54 typedef ethercat_trigger_controllers::SetWaveform::Request trigger_configuration;
55 
56 class TriggerControllerNode;
57 
59 {
60 public:
62 
64 
65  void update();
66 
68 
82  static double getTick(double t, trigger_configuration const &config)
83  {
84  return t * config.rep_rate - config.phase;
85  }
86 
101  static double getTick(const ros::Time &t, trigger_configuration const &config)
102  {
103  return getTick(t.toSec(), config);
104  }
105 
120  static double getTickStartTimeSecFromPhase(double tick, trigger_configuration const &config)
121  {
122  return (floor(tick) + config.phase) / config.rep_rate;
123  }
124 
139  static ros::Time getTickStartTimeFromPhase(double tick, trigger_configuration const &config)
140  {
141  return ros::Time(getTickStartTimeSecFromPhase(tick, config));
142  }
143 
158  static ros::Time getTickStartTime(ros::Time time, trigger_configuration const &config)
159  {
160  return ros::Time(getTickStartTimeSec(time.toSec(), config));
161  }
162 
177  static double getTickStartTimeSec(double time, trigger_configuration const &config)
178  {
179  return getTickStartTimeSecFromPhase(getTick(time, config), config);
180  }
181 
194  static ros::Duration getTickDuration(trigger_configuration &config)
195  {
196  return ros::Duration(getTickDurationSec(config));
197  }
198 
211  static double getTickDurationSec(trigger_configuration &config)
212  {
213  if (!config.running)
214  return 0;
215  else if (config.pulsed)
216  return 1e-3; // @todo the update rate should be in an include file somewhere.
217  else
218  return config.duty_cycle / config.rep_rate;
219  }
220 
221 private:
222  double getTick();
223 
224  bool setWaveformSrv(trigger_configuration &req,
225  ethercat_trigger_controllers::SetWaveform::Response &resp);
226 
229 
230  double prev_tick_;
231 
234 
235  boost::scoped_ptr<
237  std_msgs::Header> > rising_edge_pub_, falling_edge_pub_;
238  bool last_out_;
239 
240  // Configuration of controller.
241  trigger_configuration config_;
242  std::string actuator_name_;
243 };
244 
245 };
246 
247 #endif
248 
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > falling_edge_pub_
static double getTickDurationSec(trigger_configuration &config)
Gets the time during which the output will be active during each cycle.
static ros::Duration getTickDuration(trigger_configuration &config)
Gets the time during which the output will be active during each cycle.
static double getTick(double t, trigger_configuration const &config)
Convert time to an unrolled phase (in cycles).
pr2_hardware_interface::DigitalOutCommand * digital_out_command_
ros::ServiceServer set_waveform_handle_
static double getTickStartTimeSecFromPhase(double tick, trigger_configuration const &config)
Gets the ros::Time at which a cycle starts.
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > rising_edge_pub_
pr2_mechanism_model::RobotState * robot_
static ros::Time getTickStartTimeFromPhase(double tick, trigger_configuration const &config)
Gets the ros::Time at which a cycle starts.
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
ethercat_trigger_controllers::SetWaveform::Request trigger_configuration
static double getTickStartTimeSec(double time, trigger_configuration const &config)
Gets the ros::Time at which a cycle starts.
static double getTick(const ros::Time &t, trigger_configuration const &config)
Convert time to an unrolled phase (in cycles).
bool setWaveformSrv(trigger_configuration &req, ethercat_trigger_controllers::SetWaveform::Response &resp)
static ros::Time getTickStartTime(ros::Time time, trigger_configuration const &config)
Gets the ros::Time at which a cycle starts.


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