control_loop.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, Qiayuan Liao
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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 //
35 // Created by qiayuan on 12/30/20.
36 //
37 
38 #pragma once
39 
41 
42 #include <chrono>
43 #include <thread>
44 
45 #include <ros/ros.h>
47 
48 namespace rm_hw
49 {
50 using namespace std::chrono;
51 using clock = high_resolution_clock;
52 
53 class RmRobotHWLoop
54 {
55 public:
62  RmRobotHWLoop(ros::NodeHandle& nh, std::shared_ptr<RmRobotHW> hardware_interface);
63 
64  ~RmRobotHWLoop();
75  void update();
76 
77 private:
78  // Startup and shutdown of the internal node inside a roscpp program
79  ros::NodeHandle nh_;
80 
81  // Settings
82  double cycle_time_error_threshold_{};
83 
84  // Timing
85  std::thread loop_thread_;
86  std::atomic_bool loop_running_;
87  double loop_hz_{};
88  ros::Duration elapsed_time_;
89  clock::time_point last_time_;
90 
97  std::shared_ptr<controller_manager::ControllerManager> controller_manager_;
98 
99  // Abstract Hardware Interface for your robot
100  std::shared_ptr<RmRobotHW> hardware_interface_;
101 };
102 } // namespace rm_hw
ros.h
update
void update(controller_manager::ControllerManager &cm, const ros::TimerEvent &e)
controller_manager.h
rm_hw::clock
high_resolution_clock clock
Definition: control_loop.h:82
hardware_interface
rm_hw::RmRobotHWLoop
Definition: control_loop.h:84
hardware_interface.h
rm_hw
Definition: control_loop.h:48
ros::Duration
ros::NodeHandle


rm_hw
Author(s): Qiayuan Liao
autogenerated on Tue May 6 2025 02:23:44