rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
calibration_queue.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 5/27/21.
36//
37
38#pragma once
39
42
43namespace rm_common
44{
46{
47public:
48 CalibrationService(XmlRpc::XmlRpcValue& rpc_value, ros::NodeHandle& nh)
49 {
50 ROS_ASSERT(rpc_value.hasMember("start_controllers"));
51 ROS_ASSERT(rpc_value.hasMember("stop_controllers"));
52 ROS_ASSERT(rpc_value.hasMember("services_name"));
53 ROS_ASSERT(rpc_value["start_controllers"].getType() == XmlRpc::XmlRpcValue::TypeArray);
54 ROS_ASSERT(rpc_value["stop_controllers"].getType() == XmlRpc::XmlRpcValue::TypeArray);
55 ROS_ASSERT(rpc_value["services_name"].getType() == XmlRpc::XmlRpcValue::TypeArray);
56 start_controllers = getControllersName(rpc_value["start_controllers"]);
57 stop_controllers = getControllersName(rpc_value["stop_controllers"]);
58 for (int i = 0; i < rpc_value["services_name"].size(); ++i)
59 {
60 query_services.push_back(new QueryCalibrationServiceCaller(nh, rpc_value["services_name"][i]));
61 }
62 }
64 {
65 for (auto& service : query_services)
66 service->getService().response.is_calibrated = false;
67 }
69 {
70 bool is_calibrated = true;
71 for (auto& service : query_services)
72 is_calibrated &= service->isCalibrated();
73 return is_calibrated;
74 }
76 {
77 for (auto& service : query_services)
78 service->callService();
79 }
80 std::vector<std::string> start_controllers, stop_controllers;
81 std::vector<QueryCalibrationServiceCaller*> query_services;
82
83private:
84 static std::vector<std::string> getControllersName(XmlRpc::XmlRpcValue& rpc_value)
85 {
86 std::vector<std::string> controllers;
87 for (int i = 0; i < rpc_value.size(); ++i)
88 {
89 controllers.push_back(rpc_value[i]);
90 }
91 return controllers;
92 }
93};
94
96{
97public:
98 explicit CalibrationQueue(XmlRpc::XmlRpcValue& rpc_value, ros::NodeHandle& nh, ControllerManager& controller_manager)
99 : controller_manager_(controller_manager), switched_(false)
100 {
101 // Don't calibration if using simulation
102 ros::NodeHandle nh_global;
103 bool use_sim_time;
104 nh_global.param("use_sim_time", use_sim_time, false);
105 if (use_sim_time || rpc_value.getType() != XmlRpc::XmlRpcValue::TypeArray)
106 return;
107 for (int i = 0; i < rpc_value.size(); ++i)
108 calibration_services_.emplace_back(rpc_value[i], nh);
109 last_query_ = ros::Time::now();
110 calibration_itr_ = calibration_services_.end();
111 // Start with calibrated, you should use reset() to start calibration.
112 }
113 void reset()
114 {
115 if (calibration_services_.empty())
116 return;
117 calibration_itr_ = calibration_services_.begin();
118 switched_ = false;
119 for (auto service : calibration_services_)
120 service.setCalibratedFalse();
121 }
122 void update(const ros::Time& time, bool flip_controllers)
123 {
124 if (calibration_services_.empty())
125 return;
126 if (isCalibrated())
127 return;
128 if (switched_)
129 {
130 if (calibration_itr_->isCalibrated())
131 {
132 if (flip_controllers)
133 controller_manager_.startControllers(calibration_itr_->stop_controllers);
134 controller_manager_.stopControllers(calibration_itr_->start_controllers);
135 calibration_itr_++;
136 switched_ = false;
137 }
138 else if ((time - last_query_).toSec() > .2)
139 {
140 last_query_ = time;
141 calibration_itr_->callService();
142 }
143 }
144 else
145 {
146 // Switch controllers
147 switched_ = true;
148 if (calibration_itr_ != calibration_services_.end())
149 {
150 controller_manager_.startControllers(calibration_itr_->start_controllers);
151 controller_manager_.stopControllers(calibration_itr_->stop_controllers);
152 }
153 }
154 }
155 void update(const ros::Time& time)
156 {
157 update(time, true);
158 }
160 {
161 return calibration_itr_ == calibration_services_.end();
162 }
164 {
165 if (calibration_services_.empty())
166 return;
167 if (calibration_itr_ != calibration_services_.end() && switched_)
168 controller_manager_.stopControllers(calibration_itr_->stop_controllers);
169 }
170 void stop()
171 {
172 if (switched_)
173 {
174 calibration_itr_ = calibration_services_.end();
175 switched_ = false;
176 }
177 }
178
179private:
180 ros::Time last_query_;
181 std::vector<CalibrationService> calibration_services_;
182 std::vector<CalibrationService>::iterator calibration_itr_;
183 ControllerManager& controller_manager_;
184 bool switched_;
185};
186} // namespace rm_common
Definition calibration_queue.h:96
void stop()
Definition calibration_queue.h:170
CalibrationQueue(XmlRpc::XmlRpcValue &rpc_value, ros::NodeHandle &nh, ControllerManager &controller_manager)
Definition calibration_queue.h:98
void stopController()
Definition calibration_queue.h:163
void update(const ros::Time &time, bool flip_controllers)
Definition calibration_queue.h:122
bool isCalibrated()
Definition calibration_queue.h:159
void update(const ros::Time &time)
Definition calibration_queue.h:155
void reset()
Definition calibration_queue.h:113
Definition calibration_queue.h:46
void setCalibratedFalse()
Definition calibration_queue.h:63
std::vector< QueryCalibrationServiceCaller * > query_services
Definition calibration_queue.h:81
std::vector< std::string > stop_controllers
Definition calibration_queue.h:80
std::vector< std::string > start_controllers
Definition calibration_queue.h:80
bool isCalibrated()
Definition calibration_queue.h:68
void callService()
Definition calibration_queue.h:75
CalibrationService(XmlRpc::XmlRpcValue &rpc_value, ros::NodeHandle &nh)
Definition calibration_queue.h:48
Definition controller_manager.h:49
void startControllers(const std::vector< std::string > &controllers)
Definition controller_manager.h:122
void stopControllers(const std::vector< std::string > &controllers)
Definition controller_manager.h:127
Definition service_caller.h:162
Definition calibration_queue.h:44