control_loop.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, University of Colorado, Boulder
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Univ of CO, Boulder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Original Author: Dave Coleman (https://github.com/davetcoleman/ros_control_boilerplate) */
36 
37 #ifndef CONTROL_LOOP
38 #define CONTROL_LOOP
39 
40 #include <chrono>
41 
42 // for shared pointer
43 #include <memory>
44 // for runtime_error
45 #include <stdexcept>
46 
47 // ROS
48 #include <ros/ros.h>
49 
50 // ROS control
52 
53 // The hardware interface to dynamixels
55 
56 namespace dynamixel {
57  // To make use of steady_clock and duration_cast shorter
58  using namespace std::chrono;
59 
60  template <class Protocol>
61  class DynamixelLoop {
63 
64  public:
66  ros::NodeHandle& nh,
67  std::shared_ptr<hw_int> hardware_interface)
68  : _nh(nh),
69  _hardware_interface(hardware_interface)
70  {
71  // Create the controller manager
72  _controller_manager.reset(new controller_manager::ControllerManager(_hardware_interface.get(), _nh));
73 
74  // Load rosparams
75  int error = 0;
76  ros::NodeHandle np("~");
77  error += !np.getParam("loop_frequency", _loop_hz);
78  error += !np.getParam("cycle_time_error_threshold", _cycle_time_error_threshold);
79  if (error > 0) {
80  char error_message[] = "could not retrieve one of the required parameters\n\tdynamixel_hw/loop_hz or dynamixel_hw/cycle_time_error_threshold";
81  ROS_ERROR_STREAM(error_message);
82  throw std::runtime_error(error_message);
83  }
84 
85  // Get current time for use with first update
86  _last_time = steady_clock::now();
87 
88  // Start timer that will periodically call DynamixelLoop::update
89  _desired_update_freq = ros::Duration(1 / _loop_hz);
90  _non_realtime_loop = _nh.createTimer(_desired_update_freq, &DynamixelLoop::update, this);
91  }
92 
100  void update(const ros::TimerEvent&)
101  {
102  // Get change in time
103  _current_time = steady_clock::now();
104  duration<double> time_span
105  = duration_cast<duration<double>>(_current_time - _last_time);
106  _elapsed_time = ros::Duration(time_span.count());
107  _last_time = _current_time;
108 
109  // Check cycle time for excess delay
110  const double cycle_time_error = (_elapsed_time - _desired_update_freq).toSec();
111  if (cycle_time_error > _cycle_time_error_threshold) {
112  ROS_WARN_STREAM("Cycle time exceeded error threshold by: "
113  << cycle_time_error - _cycle_time_error_threshold << "s, "
114  << "cycle time: " << _elapsed_time << "s, "
115  << "threshold: " << _cycle_time_error_threshold << "s");
116  }
117 
118  // Input
119  // get the hardware's state
120  _hardware_interface->read(ros::Time::now(), _elapsed_time);
121 
122  // Control
123  // let the controller compute the new command (via the controller manager)
124  _controller_manager->update(ros::Time::now(), _elapsed_time);
125 
126  // Output
127  // send the new command to hardware
128  _hardware_interface->write(ros::Time::now(), _elapsed_time);
129  }
130 
131  private:
132  // Startup and shutdown of the internal node inside a roscpp program
134 
135  // Settings
138 
139  // Timing
142  double _loop_hz;
143  steady_clock::time_point _last_time;
144  steady_clock::time_point _current_time;
145 
152  std::shared_ptr<controller_manager::ControllerManager> _controller_manager;
153 
155  std::shared_ptr<hw_int> _hardware_interface;
156  };
157 } // namespace dynamixel
158 
159 #endif
steady_clock::time_point _current_time
std::shared_ptr< controller_manager::ControllerManager > _controller_manager
steady_clock::time_point _last_time
std::shared_ptr< hw_int > _hardware_interface
Abstract Hardware Interface for your robot.
ros::Duration _desired_update_freq
typename dynamixel::DynamixelHardwareInterface< Protocol > hw_int
DynamixelLoop(ros::NodeHandle &nh, std::shared_ptr< hw_int > hardware_interface)
#define ROS_WARN_STREAM(args)
void update(const ros::TimerEvent &)
bool getParam(const std::string &key, std::string &s) const
static Time now()
#define ROS_ERROR_STREAM(args)


dynamixel_control_hw
Author(s):
autogenerated on Mon Jun 10 2019 13:04:02