3 #include <std_srvs/SetBool.h> 4 #include <std_srvs/Trigger.h> 11 std_srvs::Trigger::Response &res){
14 res.message =
"Start Calibration process";
19 res.message =
"End Calibration process (see console to get info)";
27 std_srvs::Trigger::Response &res){
30 res.message =
"Calibration saved";
35 res.message =
"No Calibration found";
40 int main(
int argc,
char **argv)
45 ROS_INFO(
"SBG DRIVER - Init node & load params");
49 ROS_INFO(
"SBG DRIVER - Ellipse connect");
bool end_mag_calibration()
bool save_mag_calibration()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool calibration_process(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
int main(int argc, char **argv)
bool one_calibration_done
bool start_mag_calibration()
bool calibration_save(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)