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);
58 for (
int i = 0; i < rpc_value[
"services_name"].size(); ++i)
66 service->getService().response.is_calibrated =
false;
70 bool is_calibrated =
true;
72 is_calibrated &= service->isCalibrated();
78 service->callService();
84 static std::vector<std::string> getControllersName(XmlRpc::XmlRpcValue& rpc_value)
86 std::vector<std::string> controllers;
87 for (
int i = 0; i < rpc_value.size(); ++i)
89 controllers.push_back(rpc_value[i]);
99 : controller_manager_(controller_manager), switched_(false)
102 ros::NodeHandle nh_global;
104 nh_global.param(
"use_sim_time", use_sim_time,
false);
105 if (use_sim_time || rpc_value.getType() != XmlRpc::XmlRpcValue::TypeArray)
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();
115 if (calibration_services_.empty())
117 calibration_itr_ = calibration_services_.begin();
119 for (
auto service : calibration_services_)
120 service.setCalibratedFalse();
122 void update(
const ros::Time& time,
bool flip_controllers)
124 if (calibration_services_.empty())
130 if (calibration_itr_->isCalibrated())
132 if (flip_controllers)
134 controller_manager_.
stopControllers(calibration_itr_->start_controllers);
138 else if ((time - last_query_).toSec() > .2)
141 calibration_itr_->callService();
148 if (calibration_itr_ != calibration_services_.end())
151 controller_manager_.
stopControllers(calibration_itr_->stop_controllers);
122 void update(
const ros::Time& time,
bool flip_controllers) {
…}
161 return calibration_itr_ == calibration_services_.end();
165 if (calibration_services_.empty())
167 if (calibration_itr_ != calibration_services_.end() && switched_)
168 controller_manager_.
stopControllers(calibration_itr_->stop_controllers);
174 calibration_itr_ = calibration_services_.end();
180 ros::Time last_query_;
181 std::vector<CalibrationService> calibration_services_;
182 std::vector<CalibrationService>::iterator calibration_itr_;
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